diff --git a/apps/3d_rec_framework/tools/apps/src/global_classification.cpp b/apps/3d_rec_framework/tools/apps/src/global_classification.cpp index e21f1f43637..0e2e9766b78 100644 --- a/apps/3d_rec_framework/tools/apps/src/global_classification.cpp +++ b/apps/3d_rec_framework/tools/apps/src/global_classification.cpp @@ -103,7 +103,6 @@ segmentAndClassify (typename pcl::rec_3d_framework::GlobalNNPipeline= 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; diff --git a/cuda/apps/src/kinect_normals_cuda.cpp b/cuda/apps/src/kinect_normals_cuda.cpp index c4807774751..b7b5072f12c 100644 --- a/cuda/apps/src/kinect_normals_cuda.cpp +++ b/cuda/apps/src/kinect_normals_cuda.cpp @@ -121,9 +121,9 @@ class NormalEstimation // we got a cloud in device.. boost::shared_ptr::type> normals; - float focallength = 580/2.0; { ScopeTimeCPU time ("Normal Estimation"); + float focallength = 580/2.0; normals = computePointNormals::type > (data->points.begin (), data->points.end (), focallength, data, 0.05, 30); } go_on = false; @@ -164,11 +164,11 @@ class NormalEstimation d2c.compute (depth_image, image, constant, data, false, 1, smoothing_nr_iterations, smoothing_filter_size); //d2c.compute (depth_image, image, constant, data, true, 2); - boost::shared_ptr::type> normals; - float focallength = 580/2.0; + boost::shared_ptr::type> normals; { ScopeTimeCPU time ("Normal Estimation"); normals = computeFastPointNormals (data); + //float focallength = 580/2.0; //normals = computePointNormals::type > (data->points.begin (), data->points.end (), focallength, data, 0.05, 30); } diff --git a/cuda/sample_consensus/src/msac.cpp b/cuda/sample_consensus/src/msac.cpp index 886761d9193..31b95ddaf6f 100644 --- a/cuda/sample_consensus/src/msac.cpp +++ b/cuda/sample_consensus/src/msac.cpp @@ -159,7 +159,7 @@ pcl_cuda::MultiRandomSampleConsensus::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::epsilon (), p_no_outliers); // Avoid division by -Inf p_no_outliers = (std::min) (1.0f - std::numeric_limits::epsilon (), p_no_outliers); // Avoid division by 0. if (p_no_outliers == 1.0f) @@ -186,7 +186,7 @@ pcl_cuda::MultiRandomSampleConsensus::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::epsilon (), p_no_outliers); // Avoid division by -Inf p_no_outliers = (std::min) (1.0f - std::numeric_limits::epsilon (), p_no_outliers); // Avoid division by 0. if (p_no_outliers != 1.0f) @@ -227,8 +227,6 @@ pcl_cuda::MultiRandomSampleConsensus::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; @@ -240,7 +238,6 @@ pcl_cuda::MultiRandomSampleConsensus::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) @@ -252,7 +249,6 @@ pcl_cuda::MultiRandomSampleConsensus::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) @@ -280,7 +276,7 @@ pcl_cuda::MultiRandomSampleConsensus::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::epsilon (), p_no_outliers); // Avoid division by -Inf p_no_outliers = (std::min) (1.0f - std::numeric_limits::epsilon (), p_no_outliers); // Avoid division by 0. if (p_no_outliers == 1.0f) @@ -291,7 +287,6 @@ pcl_cuda::MultiRandomSampleConsensus::computeModel (int debug_verbosity } } - //std::cerr << "invalid models: " << counter_invalid << " , inlier models: " << counter_inliers << std::endl; } } } diff --git a/gpu/kinfu/tools/evaluation.cpp b/gpu/kinfu/tools/evaluation.cpp index 9206f726b30..3c88a44b4bc 100644 --- a/gpu/kinfu/tools/evaluation.cpp +++ b/gpu/kinfu/tools/evaluation.cpp @@ -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) diff --git a/gpu/kinfu/tools/kinfu_app_sim.cpp b/gpu/kinfu/tools/kinfu_app_sim.cpp index 166fff749e6..074b4bc4b35 100644 --- a/gpu/kinfu/tools/kinfu_app_sim.cpp +++ b/gpu/kinfu/tools/kinfu_app_sim.cpp @@ -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) @@ -412,7 +412,6 @@ capture (Eigen::Isometry3d pose_in,unsigned short* depth_buffer_mm,const uint8_t std::vector > poses; std::vector 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. diff --git a/gpu/kinfu_large_scale/src/cyclical_buffer.cpp b/gpu/kinfu_large_scale/src/cyclical_buffer.cpp index 26d5ba658bf..3b957245cce 100644 --- a/gpu/kinfu_large_scale/src/cyclical_buffer.cpp +++ b/gpu/kinfu_large_scale/src/cyclical_buffer.cpp @@ -132,11 +132,6 @@ pcl::gpu::kinfuLS::CyclicalBuffer::performShift (const TsdfVolume::Ptr volume, c // retrieve existing data from the world model PointCloud::Ptr previously_existing_slice (new PointCloud); - 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, diff --git a/gpu/kinfu_large_scale/tools/evaluation.cpp b/gpu/kinfu_large_scale/tools/evaluation.cpp index 99235ea5f07..b8d8d090ef9 100644 --- a/gpu/kinfu_large_scale/tools/evaluation.cpp +++ b/gpu/kinfu_large_scale/tools/evaluation.cpp @@ -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) diff --git a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp index d440dab848d..5dbf6f88f58 100644 --- a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp +++ b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp @@ -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))); diff --git a/gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp b/gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp index a6c7f34eb4b..f0663f0b94e 100644 --- a/gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp +++ b/gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp @@ -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) @@ -410,7 +410,6 @@ capture (Eigen::Isometry3d pose_in,unsigned short* depth_buffer_mm,const uint8_t std::vector > poses; std::vector 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. diff --git a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp index 13554db453e..4fc2f144046 100644 --- a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp +++ b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp @@ -291,8 +291,6 @@ void showCameras (pcl::texture_mapping::CameraVector cams, pcl::PointCloud::C } myReadFile.seekg(ios::beg); - char current_line[1024]; double val; // go to line 2 to read translations @@ -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) @@ -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 ()); diff --git a/gpu/people/src/people_detector.cpp b/gpu/people/src/people_detector.cpp index feed7f7fd0e..b65340d6a82 100644 --- a/gpu/people/src/people_detector.cpp +++ b/gpu/people/src/people_detector.cpp @@ -181,10 +181,7 @@ pcl::gpu::people::PeopleDetector::process (const pcl::PointCloud::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(); @@ -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_); @@ -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; } @@ -271,10 +269,7 @@ pcl::gpu::people::PeopleDetector::processProb (const pcl::PointCloud::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 @@ -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_); @@ -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; diff --git a/io/src/vlp_grabber.cpp b/io/src/vlp_grabber.cpp index f996f20d3b7..0cdab3011f0 100644 --- a/io/src/vlp_grabber.cpp +++ b/io/src/vlp_grabber.cpp @@ -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; @@ -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; diff --git a/keypoints/src/agast_2d.cpp b/keypoints/src/agast_2d.cpp index 4341b9c467c..0503dd8e4b1 100644 --- a/keypoints/src/agast_2d.cpp +++ b/keypoints/src/agast_2d.cpp @@ -116,7 +116,6 @@ pcl::keypoints::agast::AbstractAgastDetector::applyNonMaxSuppression ( std::vector >::const_iterator curr_corner; int lastRowCorner_ind = 0, next_lastRowCorner_ind = 0; std::vector::iterator nms_flags_p; - std::vector >::iterator curr_corner_nms; int j; int num_corners_all = int (corners_all.size ()); int n_max_corners = int (corners_nms.capacity ()); @@ -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--) diff --git a/ml/src/kmeans.cpp b/ml/src/kmeans.cpp index 8d476e4b98d..f4e95745dd0 100644 --- a/ml/src/kmeans.cpp +++ b/ml/src/kmeans.cpp @@ -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; @@ -181,7 +180,6 @@ pcl::Kmeans::kMeans () clusters_to_points_[to_cluster].insert(pid); } } - num_iterations++; } // end while } diff --git a/simulation/src/glsl_shader.cpp b/simulation/src/glsl_shader.cpp index 2e712259987..c085df7d175 100644 --- a/simulation/src/glsl_shader.cpp +++ b/simulation/src/glsl_shader.cpp @@ -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; diff --git a/surface/src/on_nurbs/fitting_curve_2d_apdm.cpp b/surface/src/on_nurbs/fitting_curve_2d_apdm.cpp index 23dd3cabefb..1191a8d380b 100644 --- a/surface/src/on_nurbs/fitting_curve_2d_apdm.cpp +++ b/surface/src/on_nurbs/fitting_curve_2d_apdm.cpp @@ -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++) { @@ -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; } } @@ -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++; } } diff --git a/surface/src/on_nurbs/fitting_curve_2d_asdm.cpp b/surface/src/on_nurbs/fitting_curve_2d_asdm.cpp index 5758801b0c6..f656e3e48dd 100644 --- a/surface/src/on_nurbs/fitting_curve_2d_asdm.cpp +++ b/surface/src/on_nurbs/fitting_curve_2d_asdm.cpp @@ -278,8 +278,8 @@ FittingCurve2dASDM::assembleInterior (double wInt, double sigma2, double rScale, updateTNR = true; } - unsigned i1 (0); - unsigned i2 (0); + //unsigned i1 (0); + //unsigned i2 (0); for (unsigned p = 0; p < nInt; p++) { @@ -349,12 +349,12 @@ FittingCurve2dASDM::assembleInterior (double wInt, double sigma2, double rScale, if ((pcp - pt).dot (n) >= 0.0) { d = (pcp - pt).norm (); - i1++; + //i1++; } else { d = -(pcp - pt).norm (); - i2++; + //i2++; } // evaluate if point lies inside or outside the closed curve diff --git a/surface/src/on_nurbs/fitting_curve_2d_pdm.cpp b/surface/src/on_nurbs/fitting_curve_2d_pdm.cpp index bc559d3081c..06a5ea5534f 100644 --- a/surface/src/on_nurbs/fitting_curve_2d_pdm.cpp +++ b/surface/src/on_nurbs/fitting_curve_2d_pdm.cpp @@ -206,7 +206,7 @@ FittingCurve2dPDM::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++) { @@ -232,7 +232,7 @@ FittingCurve2dPDM::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; } } @@ -256,7 +256,7 @@ FittingCurve2dPDM::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++; } } diff --git a/surface/src/on_nurbs/triangulation.cpp b/surface/src/on_nurbs/triangulation.cpp index 891e5b55a97..2ad20cef76c 100644 --- a/surface/src/on_nurbs/triangulation.cpp +++ b/surface/src/on_nurbs/triangulation.cpp @@ -223,7 +223,6 @@ Triangulation::convertTrimmedSurface2PolygonMesh (const ON_NurbsSurface &nurbs, createIndices (polygons, 0, resolution, resolution); vector_vec2d points (cloud->size (), Eigen::Vector2d ()); - std::vector params (cloud->size (), 0.0); std::vector pt_is_in (cloud->size (), false); Eigen::Vector3d a0, a1; @@ -235,17 +234,17 @@ Triangulation::convertTrimmedSurface2PolygonMesh (const ON_NurbsSurface &nurbs, for (unsigned i = 0; i < cloud->size (); i++) { - double err, param; + double err; Eigen::Vector2d pc, tc; pcl::PointXYZ &v = cloud->at (i); Eigen::Vector2d vp (v.x, v.y); if (curve.Order () == 2) - param = pcl::on_nurbs::FittingCurve2dAPDM::inverseMappingO2 (curve, vp, err, pc, tc); + pcl::on_nurbs::FittingCurve2dAPDM::inverseMappingO2 (curve, vp, err, pc, tc); else { - param = pcl::on_nurbs::FittingCurve2dAPDM::findClosestElementMidPoint (curve, vp); - param = pcl::on_nurbs::FittingCurve2dAPDM::inverseMapping (curve, vp, param, err, pc, tc, rScale); + double param = pcl::on_nurbs::FittingCurve2dAPDM::findClosestElementMidPoint (curve, vp); + pcl::on_nurbs::FittingCurve2dAPDM::inverseMapping (curve, vp, param, err, pc, tc, rScale); } Eigen::Vector3d a (vp (0) - pc (0), vp (1) - pc (1), 0.0); @@ -253,7 +252,6 @@ Triangulation::convertTrimmedSurface2PolygonMesh (const ON_NurbsSurface &nurbs, Eigen::Vector3d z = a.cross (b); points[i] = pc; - params[i] = param; pt_is_in[i] = (z (2) >= 0.0); } diff --git a/test/2d/test_2d.cpp b/test/2d/test_2d.cpp index a7d8c7f452c..a421e46fbd7 100644 --- a/test/2d/test_2d.cpp +++ b/test/2d/test_2d.cpp @@ -241,17 +241,13 @@ TEST(Edge, canny) edge_->setHysteresisThresholdHigh (50); edge_->detectEdgeCanny (*output_cloud); - int count = 0; for (int i = 1; i < height - 1; i++) { for (int j = 1; j < width - 1; j++) { - if (fabs ((*output_cloud)(j,i).magnitude - (*gt_output_cloud)(j,i).intensity) > 50) - count++; EXPECT_NEAR ((*output_cloud)(j,i).magnitude, (*gt_output_cloud)(j,i).intensity, 255); } } - //EXPECT_LE(count, 0.1*height*width); } void threshold(pcl::PointCloud::Ptr &cloud, float thresh){ diff --git a/test/common/test_eigen.cpp b/test/common/test_eigen.cpp index 4ab723eea77..cc0bfc58e80 100644 --- a/test/common/test_eigen.cpp +++ b/test/common/test_eigen.cpp @@ -744,14 +744,13 @@ TEST (PCL, eigen33f) const Scalar epsilon = 1e-3f; const unsigned iterations = 1000000; bool r_failed; - bool c_failed; unsigned r_fail_count = 0; unsigned c_fail_count = 0; // test floating point row-major : row-major for (unsigned idx = 0; idx < iterations; ++idx) { - r_failed = c_failed = false; + r_failed = false; // generate test matrices generateSymPosMatrix3x3 (r_matrix); c_matrix = r_matrix; @@ -781,17 +780,10 @@ TEST (PCL, eigen33f) c_result = c_vectors * c_eigenvalues.asDiagonal () * c_vectors.transpose (); c_error = c_result - c_matrix; diff = c_error.cwiseAbs (). sum (); - if (diff > epsilon) - c_failed = true; g_result = c_vectors * c_vectors.transpose (); g_error = g_result - CMatrix::Identity (); diff = g_error.cwiseAbs (). sum (); - if (diff > epsilon) - c_failed = true; - - if(c_failed) - ++c_fail_count; } // less than 1% failure rate diff --git a/test/common/test_intensity.cpp b/test/common/test_intensity.cpp index abd10f38a9c..a55585b78f4 100644 --- a/test/common/test_intensity.cpp +++ b/test/common/test_intensity.cpp @@ -72,7 +72,6 @@ TEST (PointOperators, PointXYZRGBtoPointXYZI) // Disabled. Doesn't make any sense //EXPECT_EQ (p2.intensity, static_cast (299*p0.r + 587*p0.g + 114*p0.b)/1000.0f + static_cast (299*p1.r + 587*p1.g + 114*p1.b)/1000.0f); - value = rgb_intensity (p1); intensity.set (p2, rgb_intensity (p1) * 0.1f); EXPECT_NEAR (p2.intensity, static_cast (299*p1.r + 587*p1.g + 114*p1.b) / 1000.0f * 0.1, 1e-4); } diff --git a/test/octree/test_octree.cpp b/test/octree/test_octree.cpp index d9a1f4c8ed3..a44504397e4 100644 --- a/test/octree/test_octree.cpp +++ b/test/octree/test_octree.cpp @@ -293,13 +293,11 @@ TEST (PCL, Octree_Dynamic_Depth_Test) octree.enableDynamicDepth (leafAggSize); octree.addPointsFromInputCloud (); - unsigned int leaf_node_counter = 0; // iterate over tree OctreePointCloudPointVector::LeafNodeDepthFirstIterator it2; const OctreePointCloudPointVector::LeafNodeDepthFirstIterator it2_end = octree.leaf_depth_end(); for (it2 = octree.leaf_depth_begin(); it2 != it2_end; ++it2) { - ++leaf_node_counter; unsigned int depth = it2.getCurrentOctreeDepth (); ASSERT_TRUE ((depth == 1) || (depth == 6)); } diff --git a/test/octree/test_octree_iterator.cpp b/test/octree/test_octree_iterator.cpp index 08fc40a8f31..33a2147a1b4 100644 --- a/test/octree/test_octree_iterator.cpp +++ b/test/octree/test_octree_iterator.cpp @@ -517,7 +517,6 @@ TEST_F (OctreeBaseIteratorsForLoopTest, LeafNodeDepthFirstIterator) IteratorT it_a; IteratorT it_a_end = oct_a_.leaf_depth_end (); - unsigned int node_count = 0; unsigned int branch_count = 0; unsigned int leaf_count = 0; @@ -534,10 +533,9 @@ TEST_F (OctreeBaseIteratorsForLoopTest, LeafNodeDepthFirstIterator) { leaf_count++; } - node_count++; } - // Check the node_count, branch_count and leaf_count values + // Check the branch_count and leaf_count values ASSERT_EQ (leaf_count, 64); ASSERT_EQ (branch_count, 0); ASSERT_EQ (oct_a_.getLeafCount (), leaf_count); @@ -545,7 +543,6 @@ TEST_F (OctreeBaseIteratorsForLoopTest, LeafNodeDepthFirstIterator) // Iterate over the octree oct_a_ with a depth max of 1. // As oct_a_ has a depth level of 2, we should only iterate // over 9 branch node: the root node + 8 node at depth 1 - node_count = 0; branch_count = 0; leaf_count = 0; unsigned int max_depth = 1; @@ -561,10 +558,9 @@ TEST_F (OctreeBaseIteratorsForLoopTest, LeafNodeDepthFirstIterator) { leaf_count++; } - node_count++; } - // Check the node_count, branch_count and leaf_count values + // Check the branch_count and leaf_count values ASSERT_EQ (leaf_count, 0); ASSERT_EQ (branch_count, 0); } diff --git a/test/outofcore/test_outofcore.cpp b/test/outofcore/test_outofcore.cpp index 06693ae9114..b14b823b19e 100644 --- a/test/outofcore/test_outofcore.cpp +++ b/test/outofcore/test_outofcore.cpp @@ -491,7 +491,6 @@ TEST_F (OutofcoreTest, Outofcore_ConstructorSafety) //(Case 4): Load existing tree from disk octree_disk octree_from_disk (filename_otreeB, true); - vector numPoints = octree_from_disk.getNumPointsVector (); EXPECT_EQ (numPts , octree_from_disk.getNumPointsAtDepth (octree_from_disk.getDepth ())) << "Failure to count the number of points in a tree already existing on disk\n"; }