未验证 提交 131c2aff 编写于 作者: C Chakshu Gupta 提交者: GitHub

Remove unused variables (#3621)

Remove unneeded variables
上级 46008299
......@@ -452,8 +452,6 @@ CPCSegmentation Parameters: \n\
using AdjacencyIterator = LCCPSegmentation<PointT>::AdjacencyIterator;
using EdgeID = LCCPSegmentation<PointT>::EdgeID;
std::set<EdgeID> edge_drawn;
const unsigned char black_color [3] = {0, 0, 0};
const unsigned char white_color [3] = {255, 255, 255};
const unsigned char concave_color [3] = {255, 0, 0};
......
......@@ -79,7 +79,6 @@ main (int, char **argv)
tree_ec->setInputCloud (cloud_ptr);
// Extracting Euclidean clusters using cloud and its normals
std::vector<int> indices;
std::vector<pcl::PointIndices> cluster_indices;
const float tolerance = 0.5f; // 50cm tolerance in (x, y, z) coordinate system
const double eps_angle = 5 * (M_PI / 180.0); // 5degree tolerance in normals
......
......@@ -377,8 +377,6 @@ LCCPSegmentation Parameters: \n\
using AdjacencyIterator = LCCPSegmentation<PointT>::AdjacencyIterator;
using EdgeID = LCCPSegmentation<PointT>::EdgeID;
std::set<EdgeID> edge_drawn;
const unsigned char convex_color [3] = {255, 255, 255};
const unsigned char concave_color [3] = {255, 0, 0};
const unsigned char* color;
......
......@@ -60,7 +60,6 @@ pcl::IFSReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c
std::uint32_t nr_points = 0;
std::ifstream fs;
std::string line;
if (file_name.empty() || !boost::filesystem::exists (file_name))
{
......
......@@ -52,8 +52,6 @@ OutofcoreCloud::PcdQueue OutofcoreCloud::pcd_queue;
void
OutofcoreCloud::pcdReaderThread ()
{
std::string pcd_file;
std::size_t timestamp = 0;
while (true)
......
......@@ -564,7 +564,6 @@ bool pcl::GlobalHypothesesVerification<ModelT, SceneT>::addModel(typename pcl::P
std::vector<int> explained_indices;
std::vector<float> outliers_weight;
std::vector<float> explained_indices_distances;
std::vector<float> unexplained_indices_weights;
std::vector<int> nn_indices;
std::vector<float> nn_distances;
......
......@@ -74,9 +74,6 @@ pcl::registration::CorrespondenceRejectorSampleConsensus<PointT>::getRemainingCo
target_indices[i] = original_correspondences[i].index_match;
}
// from pcl/registration/icp.hpp:
std::vector<int> source_indices_good;
std::vector<int> target_indices_good;
{
// From the set of correspondences found, attempt to remove outliers
// Create the registration model
......
......@@ -78,10 +78,6 @@ pcl::registration::CorrespondenceRejectorSampleConsensus2D<PointT>::getRemaining
target_indices[i] = original_correspondences[i].index_match;
}
// from pcl/registration/icp.hpp:
std::vector<int> source_indices_good;
std::vector<int> target_indices_good;
// From the set of correspondences found, attempt to remove outliers
typename pcl::SampleConsensusModelRegistration2D<PointT>::Ptr model (new pcl::SampleConsensusModelRegistration2D<PointT> (input_, source_indices));
// Pass the target_indices
......
......@@ -57,7 +57,6 @@ pcl::LeastMedianSquares<PointT>::computeModel (int debug_verbosity_level)
iterations_ = 0;
double d_best_penalty = std::numeric_limits<double>::max();
std::vector<int> best_model;
std::vector<int> selection;
Eigen::VectorXf model_coefficients;
std::vector<double> distances;
......
......@@ -59,7 +59,6 @@ pcl::MaximumLikelihoodSampleConsensus<PointT>::computeModel (int debug_verbosity
double d_best_penalty = std::numeric_limits<double>::max();
double k = 1.0;
std::vector<int> best_model;
std::vector<int> selection;
Eigen::VectorXf model_coefficients;
std::vector<double> distances;
......
......@@ -58,7 +58,6 @@ pcl::MEstimatorSampleConsensus<PointT>::computeModel (int debug_verbosity_level)
double d_best_penalty = std::numeric_limits<double>::max();
double k = 1.0;
std::vector<int> best_model;
std::vector<int> selection;
Eigen::VectorXf model_coefficients;
std::vector<double> distances;
......
......@@ -58,7 +58,6 @@ pcl::RandomizedMEstimatorSampleConsensus<PointT>::computeModel (int debug_verbos
double d_best_penalty = std::numeric_limits<double>::max();
double k = 1.0;
std::vector<int> best_model;
std::vector<int> selection;
Eigen::VectorXf model_coefficients;
std::vector<double> distances;
......
......@@ -585,8 +585,6 @@ pcl::SupervoxelClustering<PointT>::getLabeledCloud () const
pcl::copyPointCloud (*input_,*labeled_cloud);
typename pcl::PointCloud <PointT>::const_iterator i_input = input_->begin ();
std::vector <int> indices;
std::vector <float> sqr_distances;
for (auto i_labeled = labeled_cloud->begin (); i_labeled != labeled_cloud->end (); ++i_labeled,++i_input)
{
if ( !pcl::isFinite<PointT> (*i_input))
......
......@@ -469,7 +469,6 @@ pcl::ConcaveHull<PointInT>::performReconstruction (PointCloud &alpha_shape, std:
alpha_shape.points.resize (vertices);
std::vector<std::vector<int> > connected;
PointCloud alpha_shape_sorted;
alpha_shape_sorted.points.resize (vertices);
......
......@@ -302,9 +302,6 @@ pcl::TextureMapping<PointInT>::mapMultipleTexturesToMeshUV (pcl::TextureMesh &te
// convert mesh's cloud to pcl format for ease
pcl::fromPCLPointCloud2 (tex_mesh.cloud, *originalCloud);
// texture coordinates for each mesh
std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > texture_map;
for (std::size_t m = 0; m < cams.size (); ++m)
{
// get current camera parameters
......
......@@ -390,7 +390,6 @@ ClosingBoundary::optimizeBoundary (std::vector<ON_NurbsSurface> &nurbs_list, std
FittingSurface fit (&data_list[n1], nurbs_list[n1]);
FittingSurface::Parameter paramFP (1.0, param.smoothness, 0.0, 1.0, param.smoothness, 0.0);
std::vector<double> wBnd, wInt;
for (std::size_t i = 0; i < data_list[n1].boundary.size (); i++)
data_list[n1].boundary_weight.push_back (param.boundary_weight);
for (std::size_t i = 0; i < data_list[n1].interior.size (); i++)
......
......@@ -207,9 +207,6 @@ SparseMat::nonzeros ()
void
SparseMat::printLong ()
{
std::map<int, std::map<int, double> >::iterator it_row;
std::map<int, double>::iterator it_col;
int si, sj;
size (si, sj);
......
......@@ -189,12 +189,6 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Neighbours_Within_Radius_Search)
search::OrganizedNeighbor<PointXYZ> organizedNeighborSearch;
std::vector<int> k_indices;
std::vector<float> k_sqr_distances;
std::vector<int> k_indices_bruteforce;
std::vector<float> k_sqr_distances_bruteforce;
// typical focal length from kinect
constexpr double oneOverFocalLength = 0.0018;
......
......@@ -477,12 +477,6 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search_
pcl::search::Search<PointXYZ>* organizedNeighborSearch = new pcl::search::OrganizedNeighbor<PointXYZ>();
std::vector<int> k_indices;
std::vector<float> k_sqr_distances;
std::vector<int> k_indices_bruteforce;
std::vector<float> k_sqr_distances_bruteforce;
// typical focal length from kinect
unsigned int randomIdx;
......
......@@ -174,7 +174,7 @@ main (int argc, char** argv)
int subdiv_level = 1;
double scan_dist = 3;
std::string fname, base;
std::string fname;
char seq[256];
// Compute start/stop for vertical and horizontal
......
......@@ -91,7 +91,6 @@ template <typename PointInT, typename StateT> void
pcl::tracking::ParticleFilterTracker<PointInT, StateT>::initParticles (bool reset)
{
particles_.reset (new PointCloudState ());
std::vector<double> initial_noise_mean;
if (reset)
{
representative_state_.zero ();
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册