Skip to content

Commit

Permalink
Use std::cout/std::cerr/std::endl instead of just cout/cerr/end… (#3326)
Browse files Browse the repository at this point in the history
Use std::cout/std::cerr/std::endl instead of just cout/cerr/endl [apps-filters]
  • Loading branch information
taketwo authored Sep 10, 2019
2 parents 063c104 + 1e74528 commit ea2bb24
Show file tree
Hide file tree
Showing 45 changed files with 375 additions and 375 deletions.
44 changes: 22 additions & 22 deletions apps/src/feature_matching.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ ICCVTutorial<FeatureType>::ICCVTutorial(pcl::Keypoint<pcl::PointXYZRGB, pcl::Poi
template<typename FeatureType>
void ICCVTutorial<FeatureType>::segmentation (const typename pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& source, const typename pcl::PointCloud<pcl::PointXYZRGB>::Ptr& segmented) const
{
cout << "segmentation..." << std::flush;
std::cout << "segmentation..." << std::flush;
// fit plane and keep points above that plane
pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);
pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
Expand All @@ -196,9 +196,9 @@ void ICCVTutorial<FeatureType>::segmentation (const typename pcl::PointCloud<pcl
extract.filter (*segmented);
std::vector<int> indices;
pcl::removeNaNFromPointCloud(*segmented, *segmented, indices);
cout << "OK" << endl;
std::cout << "OK" << std::endl;

cout << "clustering..." << std::flush;
std::cout << "clustering..." << std::flush;
// euclidean clustering
typename pcl::search::KdTree<pcl::PointXYZRGB>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGB>);
tree->setInputCloud (segmented);
Expand All @@ -214,10 +214,10 @@ void ICCVTutorial<FeatureType>::segmentation (const typename pcl::PointCloud<pcl

if (!cluster_indices.empty ())//use largest cluster
{
cout << cluster_indices.size() << " clusters found";
std::cout << cluster_indices.size() << " clusters found";
if (cluster_indices.size() > 1)
cout <<" Using largest one...";
cout << endl;
std::cout <<" Using largest one...";
std::cout << std::endl;
typename pcl::IndicesPtr indices (new std::vector<int>);
*indices = cluster_indices[0].indices;
extract.setInputCloud (segmented);
Expand All @@ -231,10 +231,10 @@ void ICCVTutorial<FeatureType>::segmentation (const typename pcl::PointCloud<pcl
template<typename FeatureType>
void ICCVTutorial<FeatureType>::detectKeypoints (const typename pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& input, const pcl::PointCloud<pcl::PointXYZI>::Ptr& keypoints) const
{
cout << "keypoint detection..." << std::flush;
std::cout << "keypoint detection..." << std::flush;
keypoint_detector_->setInputCloud(input);
keypoint_detector_->compute(*keypoints);
cout << "OK. keypoints found: " << keypoints->points.size() << endl;
std::cout << "OK. keypoints found: " << keypoints->points.size() << std::endl;
}

template<typename FeatureType>
Expand All @@ -253,26 +253,26 @@ void ICCVTutorial<FeatureType>::extractDescriptors (typename pcl::PointCloud<pcl
if (feature_from_normals)
//if (boost::dynamic_pointer_cast<typename pcl::FeatureFromNormals<pcl::PointXYZRGB, pcl::Normal, FeatureType> > (feature_extractor_))
{
cout << "normal estimation..." << std::flush;
std::cout << "normal estimation..." << std::flush;
typename pcl::PointCloud<pcl::Normal>::Ptr normals (new pcl::PointCloud<pcl::Normal>);
pcl::NormalEstimation<pcl::PointXYZRGB, pcl::Normal> normal_estimation;
normal_estimation.setSearchMethod (pcl::search::Search<pcl::PointXYZRGB>::Ptr (new pcl::search::KdTree<pcl::PointXYZRGB>));
normal_estimation.setRadiusSearch (0.01);
normal_estimation.setInputCloud (input);
normal_estimation.compute (*normals);
feature_from_normals->setInputNormals(normals);
cout << "OK" << endl;
std::cout << "OK" << std::endl;
}

cout << "descriptor extraction..." << std::flush;
std::cout << "descriptor extraction..." << std::flush;
feature_extractor_->compute (*features);
cout << "OK" << endl;
std::cout << "OK" << std::endl;
}

template<typename FeatureType>
void ICCVTutorial<FeatureType>::findCorrespondences (typename pcl::PointCloud<FeatureType>::Ptr source, typename pcl::PointCloud<FeatureType>::Ptr target, std::vector<int>& correspondences) const
{
cout << "correspondence assignment..." << std::flush;
std::cout << "correspondence assignment..." << std::flush;
correspondences.resize (source->size());

// Use a KdTree to search for the nearest matches in feature space
Expand All @@ -288,13 +288,13 @@ void ICCVTutorial<FeatureType>::findCorrespondences (typename pcl::PointCloud<Fe
descriptor_kdtree.nearestKSearch (*source, i, k, k_indices, k_squared_distances);
correspondences[i] = k_indices[0];
}
cout << "OK" << endl;
std::cout << "OK" << std::endl;
}

template<typename FeatureType>
void ICCVTutorial<FeatureType>::filterCorrespondences ()
{
cout << "correspondence rejection..." << std::flush;
std::cout << "correspondence rejection..." << std::flush;
std::vector<std::pair<unsigned, unsigned> > correspondences;
for (size_t cIdx = 0; cIdx < source2target_.size (); ++cIdx)
if (target2source_[source2target_[cIdx]] == static_cast<int> (cIdx))
Expand All @@ -312,25 +312,25 @@ void ICCVTutorial<FeatureType>::filterCorrespondences ()
rejector.setInputTarget (target_keypoints_);
rejector.setInputCorrespondences(correspondences_);
rejector.getCorrespondences(*correspondences_);
cout << "OK" << endl;
std::cout << "OK" << std::endl;
}

template<typename FeatureType>
void ICCVTutorial<FeatureType>::determineInitialTransformation ()
{
cout << "initial alignment..." << std::flush;
std::cout << "initial alignment..." << std::flush;
pcl::registration::TransformationEstimation<pcl::PointXYZI, pcl::PointXYZI>::Ptr transformation_estimation (new pcl::registration::TransformationEstimationSVD<pcl::PointXYZI, pcl::PointXYZI>);

transformation_estimation->estimateRigidTransformation (*source_keypoints_, *target_keypoints_, *correspondences_, initial_transformation_matrix_);

pcl::transformPointCloud(*source_segmented_, *source_transformed_, initial_transformation_matrix_);
cout << "OK" << endl;
std::cout << "OK" << std::endl;
}

template<typename FeatureType>
void ICCVTutorial<FeatureType>::determineFinalTransformation ()
{
cout << "final registration..." << std::flush;
std::cout << "final registration..." << std::flush;
pcl::Registration<pcl::PointXYZRGB, pcl::PointXYZRGB>::Ptr registration (new pcl::IterativeClosestPoint<pcl::PointXYZRGB, pcl::PointXYZRGB>);
registration->setInputSource (source_transformed_);
//registration->setInputSource (source_segmented_);
Expand All @@ -341,13 +341,13 @@ void ICCVTutorial<FeatureType>::determineFinalTransformation ()
registration->setMaximumIterations (1000);
registration->align(*source_registered_);
transformation_matrix_ = registration->getFinalTransformation();
cout << "OK" << endl;
std::cout << "OK" << std::endl;
}

template<typename FeatureType>
void ICCVTutorial<FeatureType>::reconstructSurface ()
{
cout << "surface reconstruction..." << std::flush;
std::cout << "surface reconstruction..." << std::flush;
// merge the transformed and the target point cloud
pcl::PointCloud<pcl::PointXYZRGB>::Ptr merged (new pcl::PointCloud<pcl::PointXYZRGB>);
*merged = *source_registered_;
Expand Down Expand Up @@ -375,7 +375,7 @@ void ICCVTutorial<FeatureType>::reconstructSurface ()
surface_reconstructor_->setSearchMethod(tree);
surface_reconstructor_->setInputCloud(vertices);
surface_reconstructor_->reconstruct(surface_);
cout << "OK" << endl;
std::cout << "OK" << std::endl;
}

template<typename FeatureType>
Expand Down
10 changes: 5 additions & 5 deletions apps/src/ni_linemod.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,13 +180,13 @@ class NILinemod
keyboard_callback (const visualization::KeyboardEvent&, void*)
{
//if (event.getKeyCode())
// cout << "the key \'" << event.getKeyCode() << "\' (" << event.getKeyCode() << ") was";
// std::cout << "the key \'" << event.getKeyCode() << "\' (" << event.getKeyCode() << ") was";
//else
// cout << "the special key \'" << event.getKeySym() << "\' was";
// std::cout << "the special key \'" << event.getKeySym() << "\' was";
//if (event.keyDown())
// cout << " pressed" << endl;
// std::cout << " pressed" << std::endl;
//else
// cout << " released" << endl;
// std::cout << " released" << std::endl;
}

/////////////////////////////////////////////////////////////////////////
Expand All @@ -195,7 +195,7 @@ class NILinemod
{
//if (mouse_event.getType() == visualization::MouseEvent::MouseButtonPress && mouse_event.getButton() == visualization::MouseEvent::LeftButton)
//{
// cout << "left button pressed @ " << mouse_event.getX () << " , " << mouse_event.getY () << endl;
// std::cout << "left button pressed @ " << mouse_event.getX () << " , " << mouse_event.getY () << std::endl;
//}
}

Expand Down
12 changes: 6 additions & 6 deletions apps/src/openni_3d_concave_hull.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -177,15 +177,15 @@ usage (char ** argv)
{
for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
{
cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
<< ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
<< " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
<< " <serial-number> (only in Linux and for devices which provide serial numbers)" << endl;
std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
<< ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
<< " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
<< " <serial-number> (only in Linux and for devices which provide serial numbers)" << std::endl;
}
}
else
cout << "No devices connected." << endl;
std::cout << "No devices connected." << std::endl;
}

int
Expand Down
12 changes: 6 additions & 6 deletions apps/src/openni_3d_convex_hull.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -175,15 +175,15 @@ usage (char ** argv)
{
for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
{
cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
<< ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
<< " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
<< " <serial-number> (only in Linux and for devices which provide serial numbers)" << endl;
std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
<< ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
<< " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
<< " <serial-number> (only in Linux and for devices which provide serial numbers)" << std::endl;
}
}
else
cout << "No devices connected." << endl;
std::cout << "No devices connected." << std::endl;
}

int
Expand Down
12 changes: 6 additions & 6 deletions apps/src/openni_boundary_estimation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -196,15 +196,15 @@ usage (char ** argv)
{
for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
{
cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
<< ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
<< " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
<< " <serial-number> (only in Linux and for devices which provide serial numbers)" << endl;
std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
<< ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
<< " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
<< " <serial-number> (only in Linux and for devices which provide serial numbers)" << std::endl;
}
}
else
cout << "No devices connected." << endl;
std::cout << "No devices connected." << std::endl;
}

int
Expand Down
18 changes: 9 additions & 9 deletions apps/src/openni_color_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ class OpenNIPassthrough
if (lookup[i])
++set;

cout << "used colors: " << set << endl;
std::cout << "used colors: " << set << std::endl;

color_filter_.setLookUpTable (lookup);
}
Expand Down Expand Up @@ -158,15 +158,15 @@ usage (char ** argv)
{
for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
{
cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
<< ", connected: " << (int)driver.getBus (deviceIdx) << " @ " << (int)driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
<< " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
<< " <serial-number> (only in Linux and for devices which provide serial numbers)" << endl;
std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
<< ", connected: " << (int)driver.getBus (deviceIdx) << " @ " << (int)driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
<< " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
<< " <serial-number> (only in Linux and for devices which provide serial numbers)" << std::endl;
}
}
else
cout << "No devices connected." << endl;
std::cout << "No devices connected." << std::endl;
}

int
Expand All @@ -192,7 +192,7 @@ main (int argc, char ** argv)

if (pcl::console::parse_3x_arguments (argc, argv, "-rgb", rr, gg, bb, true) != -1 )
{
cout << "-rgb present" << endl;
std::cout << "-rgb present" << std::endl;
int rad;
int idx = pcl::console::parse_argument (argc, argv, "-radius", rad);
if (idx != -1)
Expand All @@ -217,7 +217,7 @@ main (int argc, char ** argv)
}
else
{
cout << "device does not provide rgb stream" << endl;
std::cout << "device does not provide rgb stream" << std::endl;
}

return (0);
Expand Down
12 changes: 6 additions & 6 deletions apps/src/openni_fast_mesh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -162,15 +162,15 @@ usage (char ** argv)
{
for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
{
cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
<< ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
<< " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
<< " <serial-number> (only in Linux and for devices which provide serial numbers)" << endl;
std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
<< ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
<< " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
<< " <serial-number> (only in Linux and for devices which provide serial numbers)" << std::endl;
}
}
else
cout << "No devices connected." << endl;
std::cout << "No devices connected." << std::endl;
}

int
Expand Down
12 changes: 6 additions & 6 deletions apps/src/openni_feature_persistence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -242,15 +242,15 @@ usage (char ** argv)
{
for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
{
cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
<< ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
<< " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
<< " <serial-number> (only in Linux and for devices which provide serial numbers)" << endl;
std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
<< ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
<< " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
<< " <serial-number> (only in Linux and for devices which provide serial numbers)" << std::endl;
}
}
else
cout << "No devices connected." << endl;
std::cout << "No devices connected." << std::endl;
}

int
Expand Down
Loading

0 comments on commit ea2bb24

Please sign in to comment.