Skip to content

Commit

Permalink
Fixed all passedByValue hints by CppCheck 1.85
Browse files Browse the repository at this point in the history
  • Loading branch information
Heiko Thiel committed Nov 30, 2018
1 parent e5eb7be commit d8b9538
Show file tree
Hide file tree
Showing 19 changed files with 23 additions and 23 deletions.
2 changes: 1 addition & 1 deletion apps/src/openni_grab_frame.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -220,7 +220,7 @@ class OpenNIGrabFrame
}

void
setOptions (std::string filename, std::string pcd_format, bool paused, bool visualizer)
setOptions (const std::string &filename, const std::string &pcd_format, bool paused, bool visualizer)
{
boost::filesystem::path path(filename);

Expand Down
2 changes: 1 addition & 1 deletion apps/src/openni_octree_compression.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ do \
}while(false)

void
print_usage (std::string msg)
print_usage (const std::string &msg)
{
std::cerr << msg << std::endl;
std::cout << usage << std::endl;
Expand Down
2 changes: 1 addition & 1 deletion apps/src/openni_organized_compression.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ do \
}while(false)

void
print_usage (std::string msg)
print_usage (const std::string &msg)
{
std::cerr << msg << std::endl;
std::cout << usage << std::endl;
Expand Down
2 changes: 1 addition & 1 deletion apps/src/openni_tracking.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -509,7 +509,7 @@ class OpenNISegmentTracking
}

void extractSegmentCluster (const CloudConstPtr &cloud,
const std::vector<pcl::PointIndices> cluster_indices,
const std::vector<pcl::PointIndices> &cluster_indices,
const int segment_index,
Cloud &result)
{
Expand Down
2 changes: 1 addition & 1 deletion apps/src/stereo_ground_segmentation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ class HRCSSegmentation
int smooth_strong;

public:
HRCSSegmentation (std::vector<std::string> left_images, std::vector<std::string> right_images) :
HRCSSegmentation (const std::vector<std::string> &left_images, const std::vector<std::string> &right_images) :
viewer (new pcl::visualization::PCLVisualizer ("3D Viewer")),
image_viewer (new pcl::visualization::ImageViewer ("Image Viewer")),
prev_cloud (new pcl::PointCloud<PointT>),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ pcl::DavidSDKGrabber::Ptr davidsdk_ptr;
* @returns the OpenCV type
*/
int
getOpenCVType (std::string type)
getOpenCVType (const std::string &type)
{
if (type == "CV_32FC1")
return CV_32FC1;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ pcl::EnsensoGrabber::Ptr ensenso_ptr;
* @returns the OpenCV type
*/
int
getOpenCVType (std::string type)
getOpenCVType (const std::string &type)
{
if (type == "CV_32FC1")
return CV_32FC1;
Expand Down
4 changes: 2 additions & 2 deletions examples/segmentation/example_supervoxels.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ void removeText (boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer);
* \param[in] field_name Fieldname to check
* \return True if field has been found, false otherwise */
bool
hasField (const pcl::PCLPointCloud2 &pc2, const std::string field_name);
hasField (const pcl::PCLPointCloud2 &pc2, const std::string &field_name);


using namespace pcl;
Expand Down Expand Up @@ -559,7 +559,7 @@ void removeText (boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer)
}

bool
hasField (const pcl::PCLPointCloud2 &pc2, const std::string field_name)
hasField (const pcl::PCLPointCloud2 &pc2, const std::string &field_name)
{
for (size_t cf = 0; cf < pc2.fields.size (); ++cf)
if (pc2.fields[cf].name == field_name)
Expand Down
2 changes: 1 addition & 1 deletion gpu/kinfu/tools/camera_pose.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ class CameraPoseWriter : public CameraPoseProcessor
/**
* @param output_filename name of file to write
*/
CameraPoseWriter (std::string output_filename) :
CameraPoseWriter (const std::string &output_filename) :
output_filename_ (output_filename)
{
out_stream_.open (output_filename_.c_str () );
Expand Down
2 changes: 1 addition & 1 deletion gpu/kinfu/tools/kinfu_app_sim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -977,7 +977,7 @@ struct KinFuApp
}

void
execute (int argc, char** argv, std::string plyfile)
execute (int argc, char** argv, const std::string &plyfile)
{
PtrStepSz<const unsigned short> depth;
PtrStepSz<const KinfuTracker::PixelRGB> rgb24;
Expand Down
2 changes: 1 addition & 1 deletion gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -975,7 +975,7 @@ struct KinFuApp
}

void
execute (int argc, char** argv, std::string plyfile)
execute (int argc, char** argv, const std::string &plyfile)
{
PtrStepSz<const unsigned short> depth;
PtrStepSz<const KinfuTracker::PixelRGB> rgb24;
Expand Down
2 changes: 1 addition & 1 deletion simulation/tools/sim_terminal_demo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ void printHelp (int, char **argv)


// Output the simulated output to file:
void write_sim_output(string fname_root){
void write_sim_output(const string &fname_root){
pcl::PointCloud<pcl::PointXYZRGB>::Ptr pc_out (new pcl::PointCloud<pcl::PointXYZRGB>);

// Read Color Buffer from the GPU before creating PointCloud:
Expand Down
2 changes: 1 addition & 1 deletion simulation/tools/sim_viewer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -225,7 +225,7 @@ pp_callback (const pcl::visualization::PointPickingEvent& event, void* cookie)
ph_global.spinOnce ();
}

void capture (Eigen::Isometry3d pose_in, string point_cloud_fname)
void capture (Eigen::Isometry3d pose_in, const string &point_cloud_fname)
{
// No reference image - but this is kept for compatibility with range_test_v2:
float* reference = new float[range_likelihood_->getRowHeight() * range_likelihood_->getColWidth()];
Expand Down
6 changes: 3 additions & 3 deletions test/geometry/test_mesh_common_functions.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ const unsigned int max_number_boundary_vertices = 100;

/** \brief Check if the faces of the mesh are equal to the reference faces (defined by a vector of vertices). */
template <class MeshT> bool
hasFaces (const MeshT& mesh, const std::vector <typename MeshT::VertexIndices> faces, const bool verbose = false)
hasFaces (const MeshT& mesh, const std::vector <typename MeshT::VertexIndices> &faces, const bool verbose = false)
{
typedef typename MeshT::VertexAroundFaceCirculator VAFC;
typedef typename MeshT::VertexIndices VertexIndices;
Expand Down Expand Up @@ -114,7 +114,7 @@ hasFaces (const MeshT& mesh, const std::vector <typename MeshT::VertexIndices> f
* \note This method assumes that the vertex data is of type 'int'.
*/
template <class MeshT> bool
hasFaces (const MeshT& mesh, const std::vector <std::vector <int> > faces, const bool verbose = false)
hasFaces (const MeshT& mesh, const std::vector <std::vector <int> > f&aces, const bool verbose = false)
{
typedef typename MeshT::VertexAroundFaceCirculator VAFC;
typedef typename MeshT::FaceIndex FaceIndex;
Expand Down Expand Up @@ -293,7 +293,7 @@ isCircularPermutation (const ContainerT& expected, const ContainerT& actual, con

/** \brief Check if both the inner and outer input vector are a circular permutation. */
template <class ContainerT> bool
isCircularPermutationVec (const std::vector <ContainerT> expected, const std::vector <ContainerT> actual, const bool verbose = false)
isCircularPermutationVec (const std::vector <ContainerT> &expected, const std::vector <ContainerT> &actual, const bool verbose = false)
{
const unsigned int n = static_cast<unsigned int> (expected.size ());
EXPECT_EQ (n, actual.size ());
Expand Down
2 changes: 1 addition & 1 deletion tools/compute_cloud_error.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ loadCloud (const std::string &filename, pcl::PCLPointCloud2 &cloud)

void
compute (const pcl::PCLPointCloud2::ConstPtr &cloud_source, const pcl::PCLPointCloud2::ConstPtr &cloud_target,
pcl::PCLPointCloud2 &output, std::string correspondence_type)
pcl::PCLPointCloud2 &output, const std::string &correspondence_type)
{
// Estimate
TicToc tt;
Expand Down
2 changes: 1 addition & 1 deletion tools/morph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ saveCloud (const std::string &filename, const Cloud &output)

int
batchProcess (const vector<string> &pcd_files, string &output_dir,
float resolution, std::string method)
float resolution, const std::string &method)
{
vector<string> st;
for (size_t i = 0; i < pcd_files.size (); ++i)
Expand Down
2 changes: 1 addition & 1 deletion tools/obj_rec_ransac_accepted_hypotheses.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,7 @@ vtk_to_pointcloud (const char* file_name, PointCloud<PointXYZ>& pcl_points, Poin
//===============================================================================================================================

void
showHypothesisAsCoordinateFrame (Hypothesis& hypo, CallbackParameters* parameters, string frame_name)
showHypothesisAsCoordinateFrame (Hypothesis& hypo, CallbackParameters* parameters, const string &frame_name)
{
float rot_col[3], x_dir[3], y_dir[3], z_dir[3], origin[3], scale = 2.0f*parameters->objrec_.getPairWidth ();
pcl::ModelCoefficients coeffs; coeffs.values.resize (6);
Expand Down
2 changes: 1 addition & 1 deletion tools/passthrough_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ saveCloud (const std::string &filename, const pcl::PCLPointCloud2 &output)

int
batchProcess (const vector<string> &pcd_files, string &output_dir,
std::string field_name, float min, float max, bool inside, bool keep_organized)
const std::string &field_name, float min, float max, bool inside, bool keep_organized)
{
vector<string> st;
for (size_t i = 0; i < pcd_files.size (); ++i)
Expand Down
4 changes: 2 additions & 2 deletions tools/tiff2pcd.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,13 +61,13 @@ using namespace pcl;

void processAndSave( vtkSmartPointer<vtkImageData> depth_data,
vtkSmartPointer<vtkImageData> rgb_data,
std::string time,
const std::string& time,
float focal_length,
bool format,
bool color,
bool depth,
bool use_output_path,
std::string output_path)
const std::string& output_path)
{
// Retrieve the entries from the image data and copy them into the output RGB cloud
int rgb_components = rgb_data->GetNumberOfScalarComponents();
Expand Down

0 comments on commit d8b9538

Please sign in to comment.