Skip to content

Commit

Permalink
Merge pull request #2556 from SergioRAgostinho/suppress-warnings
Browse files Browse the repository at this point in the history
Suppress miscelanious warnings
  • Loading branch information
taketwo committed Oct 14, 2018
2 parents 5efd95a + 2ac5f85 commit 5783aa0
Show file tree
Hide file tree
Showing 6 changed files with 10 additions and 7 deletions.
1 change: 0 additions & 1 deletion apps/cloud_composer/src/properties_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,6 @@ pcl::cloud_composer::PropertiesModel::copyProperties (const PropertiesModel* to_
for (int i=0; i < to_copy->rowCount (); ++i){
QList <QStandardItem*> new_row;
QStandardItem* parent = to_copy->item(i,0);
QModelIndex parent_index = to_copy->index(i,0);
qDebug () << "Copying "<<parent->text()<< " cols ="<<to_copy->columnCount ();
new_row.append (parent->clone ());
for (int j=1; j < to_copy->columnCount (); ++j)
Expand Down
8 changes: 6 additions & 2 deletions io/src/dinast_grabber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,8 +125,12 @@ pcl::DinastGrabber::setupDevice (int device_position, const int id_vendor, const
sstream << "[pcl::DinastGrabber::setupDevice] libusb initialization failure, LIBUSB_ERROR: "<< ret;
PCL_THROW_EXCEPTION (pcl::IOException, sstream.str ());
}

libusb_set_debug (context_, 3);

#if defined(LIBUSB_API_VERSION) && (LIBUSB_API_VERSION >= 0x01000106)
libusb_set_option (context_, LIBUSB_OPTION_LOG_LEVEL, 3);
#else
libusb_set_debug (context_, 3);
#endif
libusb_device **devs = NULL;

// Get the list of USB devices
Expand Down
2 changes: 1 addition & 1 deletion io/src/obj_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -395,7 +395,7 @@ pcl::OBJReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c
if (line[0] == 'v')
{
// Vertex (v)
if ((line[1] == ' ')) {
if (line[1] == ' ') {
++nr_point;
continue;
}
Expand Down
2 changes: 1 addition & 1 deletion io/src/pcd_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -373,7 +373,7 @@ pcl::PCDReader::readHeader (std::istream &fs, pcl::PCLPointCloud2 &cloud,
}
}

if (int (cloud.width * cloud.height) != nr_points)
if (cloud.width * cloud.height != nr_points)
{
PCL_ERROR ("[pcl::PCDReader::readHeader] HEIGHT (%d) x WIDTH (%d) != number of points (%d)\n", cloud.height, cloud.width, nr_points);
return (-1);
Expand Down
2 changes: 1 addition & 1 deletion registration/include/pcl/registration/impl/ia_kfpcs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ pcl::registration::KFPCSInitialAlignment <PointSource, PointTarget, NormalT, Sca

// generate a subset of indices of size ransac_iterations_ on which to evaluate candidates on
std::size_t nr_indices = indices_->size ();
if (nr_indices < ransac_iterations_)
if (nr_indices < size_t (ransac_iterations_))
indices_validation_ = indices_;
else
for (int i = 0; i < ransac_iterations_; i++)
Expand Down
2 changes: 1 addition & 1 deletion surface/include/pcl/surface/impl/concave_hull.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -242,7 +242,7 @@ pcl::ConcaveHull<PointInT>::performReconstruction (PointCloud &alpha_shape, std:
int max_vertex_id = 0;
FORALLvertices
{
if (vertex->id + 1 > max_vertex_id)
if (vertex->id + 1 > unsigned (max_vertex_id))
max_vertex_id = vertex->id + 1;
}

Expand Down

0 comments on commit 5783aa0

Please sign in to comment.