Skip to content

Commit

Permalink
Fixed 44 of 99 unreadVariable hints raised by CppCheck 1.85 (not all,…
Browse files Browse the repository at this point in the history
… because there are some false positives and ignored hints in tutorials and 3rdParty directories)
  • Loading branch information
Heiko Thiel committed Nov 27, 2018
1 parent 72f41b6 commit e29cd20
Show file tree
Hide file tree
Showing 26 changed files with 41 additions and 107 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,6 @@ segmentAndClassify (typename pcl::rec_3d_framework::GlobalNNPipeline<DistT, Poin
global.getCategory (categories);
global.getConfidence (conf);

std::string category = categories[0];
Eigen::Vector4f centroid;
pcl::compute3DCentroid (*xyz_points, indices[i].indices, centroid);
for (size_t kk = 0; kk < categories.size (); kk++)
Expand Down
6 changes: 0 additions & 6 deletions apps/src/grabcut_2d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -471,12 +471,6 @@ int main (int argc, char** argv)
return (-1);
}

std::string object_file = "object.pcd", background_file = "background.pcd";
if (parsed_file_indices.size () >= 3)
background_file = argv[parsed_file_indices[2]];
if (parsed_file_indices.size () >= 2)
object_file = argv[parsed_file_indices[1]];

pcl::PCDReader reader;
// Test the header
pcl::PCLPointCloud2 dummy;
Expand Down
6 changes: 3 additions & 3 deletions cuda/apps/src/kinect_normals_cuda.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,9 +121,9 @@ class NormalEstimation
// we got a cloud in device..

boost::shared_ptr<typename Storage<float4>::type> normals;
float focallength = 580/2.0;
{
ScopeTimeCPU time ("Normal Estimation");
float focallength = 580/2.0;
normals = computePointNormals<Storage, typename PointIterator<Storage,PointXYZRGB>::type > (data->points.begin (), data->points.end (), focallength, data, 0.05, 30);
}
go_on = false;
Expand Down Expand Up @@ -164,11 +164,11 @@ class NormalEstimation
d2c.compute<Storage> (depth_image, image, constant, data, false, 1, smoothing_nr_iterations, smoothing_filter_size);
//d2c.compute<Storage> (depth_image, image, constant, data, true, 2);

boost::shared_ptr<typename Storage<float4>::type> normals;
float focallength = 580/2.0;
boost::shared_ptr<typename Storage<float4>::type> normals;
{
ScopeTimeCPU time ("Normal Estimation");
normals = computeFastPointNormals<Storage> (data);
//float focallength = 580/2.0;
//normals = computePointNormals<Storage, typename PointIterator<Storage,PointXYZRGB>::type > (data->points.begin (), data->points.end (), focallength, data, 0.05, 30);
}

Expand Down
11 changes: 3 additions & 8 deletions cuda/sample_consensus/src/msac.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -159,7 +159,7 @@ pcl_cuda::MultiRandomSampleConsensus<Storage>::computeModel (int debug_verbosity

// Compute the k parameter (k=log(z)/log(1-w^n))
float w = (float)((float)n_best_inliers_count / (float)nr_remaining_points);
float p_no_outliers = 1.0f - pow (w, 1.0f);
float p_no_outliers = 1.0f - w;
p_no_outliers = (std::max) (std::numeric_limits<float>::epsilon (), p_no_outliers); // Avoid division by -Inf
p_no_outliers = (std::min) (1.0f - std::numeric_limits<float>::epsilon (), p_no_outliers); // Avoid division by 0.
if (p_no_outliers == 1.0f)
Expand All @@ -186,7 +186,7 @@ pcl_cuda::MultiRandomSampleConsensus<Storage>::computeModel (int debug_verbosity

// Compute the k parameter (k=log(z)/log(1-w^n))
float w = (float)((float)min_nr_in_shape / (float)nr_remaining_points);
float p_no_outliers = 1.0f - pow (w, 1.0f);
float p_no_outliers = 1.0f - w;
p_no_outliers = (std::max) (std::numeric_limits<float>::epsilon (), p_no_outliers); // Avoid division by -Inf
p_no_outliers = (std::min) (1.0f - std::numeric_limits<float>::epsilon (), p_no_outliers); // Avoid division by 0.
if (p_no_outliers != 1.0f)
Expand Down Expand Up @@ -227,8 +227,6 @@ pcl_cuda::MultiRandomSampleConsensus<Storage>::computeModel (int debug_verbosity
n_best_inliers_count = 0;
k = max_batches_ * iterations_per_batch_;
// go through all other models, invalidating those whose samples are inliers to the best one
int counter_invalid = 0;
int counter_inliers = 0;

//for (unsigned int b = 0; b <= cur_batch; b++)
unsigned int b = cur_batch;
Expand All @@ -240,7 +238,6 @@ pcl_cuda::MultiRandomSampleConsensus<Storage>::computeModel (int debug_verbosity
if (!hypothesis_valid[b * iterations_per_batch_ + j])
{
//std::cerr << "model " << j << " in batch " << b <<" is an invalid model" << std::endl;
counter_invalid ++;
continue;
}
if ((b*iterations_per_batch_ + j) == extracted_model)
Expand All @@ -252,7 +249,6 @@ pcl_cuda::MultiRandomSampleConsensus<Storage>::computeModel (int debug_verbosity
if (sac_model_->isSampleInlier (hypotheses_inliers_stencils[extracted_model], h_samples[b], j))
{
//std::cerr << "sample point for model " << j << " in batch " << b <<" is inlier to best model " << extracted_model << std::endl;
counter_inliers ++;
hypothesis_valid[b * iterations_per_batch_ + j] = false;
hypotheses_inlier_count[b*iterations_per_batch_ + j] = 0;
if (j <= i)
Expand Down Expand Up @@ -280,7 +276,7 @@ pcl_cuda::MultiRandomSampleConsensus<Storage>::computeModel (int debug_verbosity

// Compute the k parameter (k=log(z)/log(1-w^n))
float w = (float)((float)n_best_inliers_count / (float)nr_remaining_points);
float p_no_outliers = 1.0f - pow (w, 1.0f);
float p_no_outliers = 1.0f - w;
p_no_outliers = (std::max) (std::numeric_limits<float>::epsilon (), p_no_outliers); // Avoid division by -Inf
p_no_outliers = (std::min) (1.0f - std::numeric_limits<float>::epsilon (), p_no_outliers); // Avoid division by 0.
if (p_no_outliers == 1.0f)
Expand All @@ -291,7 +287,6 @@ pcl_cuda::MultiRandomSampleConsensus<Storage>::computeModel (int debug_verbosity

}
}
//std::cerr << "invalid models: " << counter_invalid << " , inlier models: " << counter_inliers << std::endl;
}
}
}
Expand Down
4 changes: 1 addition & 3 deletions gpu/kinfu/tools/evaluation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,9 +85,7 @@ Evaluation::Evaluation(const std::string& folder) : folder_(folder), visualizati
string rgb_file = folder_ + "rgb.txt";

readFile(depth_file, depth_stamps_and_filenames_);
readFile(rgb_file, rgb_stamps_and_filenames_);

string associated_file = folder_ + "associated.txt";
readFile(rgb_file, rgb_stamps_and_filenames_);
}

void Evaluation::setMatchFile(const std::string& file)
Expand Down
5 changes: 2 additions & 3 deletions gpu/kinfu/tools/kinfu_app_sim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -328,8 +328,8 @@ write_rgb_image(const uint8_t* rgb_buffer)
void
depthBufferToMM(const float* depth_buffer,unsigned short* depth_img)
{
int npixels = range_likelihood_->getWidth() * range_likelihood_->getHeight();
// unsigned short * depth_img = new unsigned short[npixels ];
//int npixels = range_likelihood_->getWidth() * range_likelihood_->getHeight();
//unsigned short * depth_img = new unsigned short[npixels ];
for (int y = 0; y < 480; ++y)
{
for (int x = 0; x < 640; ++x)
Expand Down Expand Up @@ -412,7 +412,6 @@ capture (Eigen::Isometry3d pose_in,unsigned short* depth_buffer_mm,const uint8_t

std::vector<Eigen::Isometry3d, Eigen::aligned_allocator<Eigen::Isometry3d> > poses;
std::vector<float> scores;
int n = 1;
poses.push_back (pose_in);
// HACK: mfallon modified computeLikelihoods to only call render() (which is currently private)
// need to make render public and use it.
Expand Down
5 changes: 0 additions & 5 deletions gpu/kinfu_large_scale/src/cyclical_buffer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,11 +132,6 @@ pcl::gpu::kinfuLS::CyclicalBuffer::performShift (const TsdfVolume::Ptr volume, c

// retrieve existing data from the world model
PointCloud<PointXYZI>::Ptr previously_existing_slice (new PointCloud<PointXYZI>);
double min_bound_x = buffer_.origin_GRID_global.x + buffer_.voxels_size.x - 1;
double new_origin_x = buffer_.origin_GRID_global.x + offset_x;
double new_origin_y = buffer_.origin_GRID_global.y + offset_y;
double new_origin_z = buffer_.origin_GRID_global.z + offset_z;

world_model_.getExistingData (buffer_.origin_GRID_global.x, buffer_.origin_GRID_global.y, buffer_.origin_GRID_global.z,
offset_x, offset_y, offset_z,
buffer_.voxels_size.x - 1, buffer_.voxels_size.y - 1, buffer_.voxels_size.z - 1,
Expand Down
4 changes: 1 addition & 3 deletions gpu/kinfu_large_scale/tools/evaluation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,9 +85,7 @@ Evaluation::Evaluation(const std::string& folder) : folder_(folder), visualizati
string rgb_file = folder_ + "rgb.txt";

readFile(depth_file, depth_stamps_and_filenames_);
readFile(rgb_file, rgb_stamps_and_filenames_);

string associated_file = folder_ + "associated.txt";
readFile(rgb_file, rgb_stamps_and_filenames_);
}

void Evaluation::setMatchFile(const std::string& file)
Expand Down
2 changes: 0 additions & 2 deletions gpu/kinfu_large_scale/tools/kinfuLS_app.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -419,8 +419,6 @@ struct SceneCloudView
// create a 5-point visual for each camera
pcl::PointXYZ p1, p2, p3, p4, p5;
p1.x=0; p1.y=0; p1.z=0;
double angleX = RAD2DEG (2.0 * atan (width / (2.0*focal)));
double angleY = RAD2DEG (2.0 * atan (height / (2.0*focal)));
double dist = 0.75;
double minX, minY, maxX, maxY;
maxX = dist*tan (atan (width / (2.0*focal)));
Expand Down
5 changes: 2 additions & 3 deletions gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -326,8 +326,8 @@ write_rgb_image(const uint8_t* rgb_buffer)
void
depthBufferToMM(const float* depth_buffer,unsigned short* depth_img)
{
int npixels = range_likelihood_->getWidth() * range_likelihood_->getHeight();
// unsigned short * depth_img = new unsigned short[npixels ];
//int npixels = range_likelihood_->getWidth() * range_likelihood_->getHeight();
//unsigned short * depth_img = new unsigned short[npixels ];
for (int y = 0; y < 480; ++y)
{
for (int x = 0; x < 640; ++x)
Expand Down Expand Up @@ -410,7 +410,6 @@ capture (Eigen::Isometry3d pose_in,unsigned short* depth_buffer_mm,const uint8_t

std::vector<Eigen::Isometry3d, Eigen::aligned_allocator<Eigen::Isometry3d> > poses;
std::vector<float> scores;
int n = 1;
poses.push_back (pose_in);
// HACK: mfallon modified computeLikelihoods to only call render() (which is currently private)
// need to make render public and use it.
Expand Down
5 changes: 0 additions & 5 deletions gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -291,8 +291,6 @@ void showCameras (pcl::texture_mapping::CameraVector cams, pcl::PointCloud<pcl::
// create a 5-point visual for each camera
pcl::PointXYZ p1, p2, p3, p4, p5;
p1.x=0; p1.y=0; p1.z=0;
double angleX = RAD2DEG (2.0 * atan (width / (2.0*focal)));
double angleY = RAD2DEG (2.0 * atan (height / (2.0*focal)));
double dist = 0.75;
double minX, minY, maxX, maxY;
maxX = dist*tan (atan (width / (2.0*focal)));
Expand Down Expand Up @@ -375,7 +373,6 @@ bool readCamPoseFile(std::string filename, pcl::TextureMapping<pcl::PointXYZ>::C
}
myReadFile.seekg(ios::beg);

char current_line[1024];
double val;

// go to line 2 to read translations
Expand Down Expand Up @@ -450,7 +447,6 @@ main (int argc, char** argv)

const boost::filesystem::path base_dir (".");
std::string extension (".txt");
int cpt_cam = 0;
for (boost::filesystem::directory_iterator it (base_dir); it != boost::filesystem::directory_iterator (); ++it)
{
if(boost::filesystem::is_regular_file (it->status ()) && boost::filesystem::extension (it->path ()) == extension)
Expand All @@ -459,7 +455,6 @@ main (int argc, char** argv)
readCamPoseFile(it->path ().string (), cam);
cam.texture_file = boost::filesystem::basename (it->path ()) + ".png";
my_cams.push_back (cam);
cpt_cam++ ;
}
}
PCL_INFO ("\tLoaded %d textures.\n", my_cams.size ());
Expand Down
29 changes: 12 additions & 17 deletions gpu/people/src/people_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -181,10 +181,7 @@ pcl::gpu::people::PeopleDetector::process (const pcl::PointCloud<PointTC>::Const

int
pcl::gpu::people::PeopleDetector::process ()
{
int cols = cloud_device_.cols();
int rows = cloud_device_.rows();

{
rdf_detector_->process(depth_device1_, cloud_host_, AREA_THRES);

const RDFBodyPartsDetector::BlobMatrix& sorted = rdf_detector_->getBlobMatrix();
Expand All @@ -205,6 +202,7 @@ pcl::gpu::people::PeopleDetector::process ()
shs5(cloud_host_, seed, &flowermat_host_.points[0]);
}

int cols = cloud_device_.cols();
fg_mask_.upload(flowermat_host_.points, cols);
device::Dilatation::invoke(fg_mask_, kernelRect5x5_, fg_mask_grown_);

Expand All @@ -221,18 +219,18 @@ pcl::gpu::people::PeopleDetector::process ()
{
Tree2 t2;
buildTree(sorted2, cloud_host_, Neck, c, t2);
int par = 0;
/*int par = 0;
for(int f = 0; f < NUM_PARTS; f++)
{
/* if(t2.parts_lid[f] == NO_CHILD)
if(t2.parts_lid[f] == NO_CHILD)
{
cerr << "1;";
par++;
}
else
cerr << "0;";*/
}
static int counter = 0; // TODO move this logging to PeopleApp
cerr << "0;";
}*/
//static int counter = 0; // TODO move this logging to PeopleApp
//cerr << t2.nr_parts << ";" << par << ";" << t2.total_dist_error << ";" << t2.norm_dist_error << ";" << counter++ << ";" << endl;
return 2;
}
Expand Down Expand Up @@ -271,10 +269,7 @@ pcl::gpu::people::PeopleDetector::processProb (const pcl::PointCloud<PointTC>::C

int
pcl::gpu::people::PeopleDetector::processProb ()
{
int cols = cloud_device_.cols();
int rows = cloud_device_.rows();

{
PCL_DEBUG("[pcl::gpu::people::PeopleDetector::processProb] : (D) : called\n");

// First iteration no tracking can take place
Expand Down Expand Up @@ -346,6 +341,7 @@ pcl::gpu::people::PeopleDetector::processProb ()
shs5(cloud_host_, seed, &flowermat_host_.points[0]);
}

int cols = cloud_device_.cols();
fg_mask_.upload(flowermat_host_.points, cols);
device::Dilatation::invoke(fg_mask_, kernelRect5x5_, fg_mask_grown_);

Expand Down Expand Up @@ -374,20 +370,19 @@ pcl::gpu::people::PeopleDetector::processProb ()
{
Tree2 t2;
buildTree(sorted2, cloud_host_, Neck, c, t2, person_attribs_);
int par = 0;
//int par = 0;
for(int f = 0; f < NUM_PARTS; f++)
{
if(t2.parts_lid[f] == NO_CHILD)
{
cerr << "1;";
par++;
//par++;
}
else
cerr << "0;";
}
std::cerr << std::endl;
static int counter = 0; // TODO move this logging to PeopleApp

//static int counter = 0; // TODO move this logging to PeopleApp
//cerr << t2.nr_parts << ";" << par << ";" << t2.total_dist_error << ";" << t2.norm_dist_error << ";" << counter++ << ";" << endl;
first_iteration_ = false;
return 2;
Expand Down
3 changes: 0 additions & 3 deletions io/src/vlp_grabber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,6 @@ pcl::VLPGrabber::getDefaultNetworkAddress ()
void
pcl::VLPGrabber::toPointClouds (HDLDataPacket *dataPacket)
{
static uint32_t scan_counter = 0;
static uint32_t sweep_counter = 0;
if (sizeof(HDLLaserReturn) != 3)
return;
Expand All @@ -110,8 +109,6 @@ pcl::VLPGrabber::toPointClouds (HDLDataPacket *dataPacket)
time (&system_time);
time_t velodyne_time = (system_time & 0x00000000ffffffffl) << 32 | dataPacket->gpsTimestamp;

scan_counter++;

double interpolated_azimuth_delta;

uint8_t index = 1;
Expand Down
2 changes: 0 additions & 2 deletions keypoints/src/agast_2d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,6 @@ pcl::keypoints::agast::AbstractAgastDetector::applyNonMaxSuppression (
std::vector<pcl::PointUV, Eigen::aligned_allocator<pcl::PointUV> >::const_iterator curr_corner;
int lastRowCorner_ind = 0, next_lastRowCorner_ind = 0;
std::vector<int>::iterator nms_flags_p;
std::vector<pcl::PointUV, Eigen::aligned_allocator<pcl::PointUV> >::iterator curr_corner_nms;
int j;
int num_corners_all = int (corners_all.size ());
int n_max_corners = int (corners_nms.capacity ());
Expand Down Expand Up @@ -144,7 +143,6 @@ pcl::keypoints::agast::AbstractAgastDetector::applyNonMaxSuppression (
nms_flags.resize (num_corners_all);

nms_flags_p = nms_flags.begin ();
curr_corner_nms = corners_nms.begin ();

// set all flags to MAXIMUM
for (j = num_corners_all; j > 0; j--)
Expand Down
2 changes: 0 additions & 2 deletions ml/src/kmeans.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,6 @@ pcl::Kmeans::kMeans ()
{
bool not_converged = true;
bool move;
unsigned int num_iterations = 0;
PointId pid;
ClusterId cid, to_cluster;
float d, min;
Expand Down Expand Up @@ -181,7 +180,6 @@ pcl::Kmeans::kMeans ()
clusters_to_points_[to_cluster].insert(pid);
}
}
num_iterations++;
} // end while
}

Expand Down
2 changes: 0 additions & 2 deletions simulation/src/glsl_shader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,8 +129,6 @@ pcl::simulation::gllib::Program::addShaderFile (const std::string& filename, Sha
char* text = readTextFile (filename.c_str ());
if(text == NULL) return (false);

std::string source(text);

bool rval = addShaderText (text, shader_type);
delete [] text;
return rval;
Expand Down
6 changes: 3 additions & 3 deletions surface/src/on_nurbs/fitting_curve_2d_apdm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -239,7 +239,7 @@ FittingCurve2dAPDM::addCPsOnClosestPointViolation (double max_error)
// m_data->interior_line_start.clear ();
// m_data->interior_line_end.clear ();

int nknots (0);
//int nknots (0);

for (unsigned i = 0; i < elements.size () - 1; i++)
{
Expand All @@ -265,7 +265,7 @@ FittingCurve2dAPDM::addCPsOnClosestPointViolation (double max_error)
m_nurbs.InsertKnot (xi + 0.5 * dxi, 1);
// m_data->interior_line_start.push_back (p2);
// m_data->interior_line_end.push_back (p1);
nknots++;
//nknots++;
inserted = true;
}
}
Expand All @@ -289,7 +289,7 @@ FittingCurve2dAPDM::addCPsOnClosestPointViolation (double max_error)
m_nurbs.InsertKnot (xi, 1);
// m_data->interior_line_start.push_back (p2);
// m_data->interior_line_end.push_back (p1);
nknots++;
//nknots++;
}
}

Expand Down
Loading

0 comments on commit e29cd20

Please sign in to comment.