Skip to content

Commit

Permalink
big refactorization of the include headers for pcl_visualization. Major
Browse files Browse the repository at this point in the history
changes include: forward declarations for most classes used in headers,
and inclusion of real headers (e.g., VTK) in the cpp implementations;
fixes for certain command line tools, apps and examples in PCL that were
not including the headers they were using correctly.
  • Loading branch information
rbrusu committed Jun 18, 2013
1 parent 19dd2a1 commit aff4fe9
Show file tree
Hide file tree
Showing 57 changed files with 1,045 additions and 720 deletions.
2 changes: 1 addition & 1 deletion apps/cloud_composer/src/items/fpfh_item.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include <pcl/apps/cloud_composer/items/fpfh_item.h>
#include <pcl/apps/cloud_composer/qt.h>

#include <vtkRenderWindow.h>

pcl::cloud_composer::FPFHItem::FPFHItem (QString name, pcl::PointCloud<pcl::FPFHSignature33>::Ptr fpfh_ptr, double radius)
: CloudComposerItem (name)
Expand Down
4 changes: 2 additions & 2 deletions apps/cloud_composer/src/tool_interface/abstract_tool.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@ pcl::cloud_composer::AbstractTool::AbstractTool (PropertiesModel* parameter_mode
}

QList <pcl::cloud_composer::CloudComposerItem*>
pcl::cloud_composer::AbstractTool::performAction (QList <const CloudComposerItem*> input_data, PointTypeFlags::PointType type)
pcl::cloud_composer::AbstractTool::performAction (QList <const CloudComposerItem*>, PointTypeFlags::PointType)
{
qDebug () << "AbstractTool::performTemplatedAction";
return QList <CloudComposerItem*> ();
}
}
4 changes: 2 additions & 2 deletions apps/cloud_composer/tools/euclidean_clustering.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ pcl::cloud_composer::EuclideanClusteringTool::~EuclideanClusteringTool ()
}

QList <pcl::cloud_composer::CloudComposerItem*>
pcl::cloud_composer::EuclideanClusteringTool::performAction (ConstItemList input_data, PointTypeFlags::PointType type)
pcl::cloud_composer::EuclideanClusteringTool::performAction (ConstItemList input_data, PointTypeFlags::PointType)
{
QList <CloudComposerItem*> output;
const CloudComposerItem* input_item;
Expand Down Expand Up @@ -133,4 +133,4 @@ pcl::cloud_composer::EuclideanClusteringToolFactory::createToolParameterModel (Q


return parameter_model;
}
}
4 changes: 2 additions & 2 deletions apps/modeler/include/pcl/apps/modeler/parameter.h
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ namespace pcl
public:
IntParameter(const std::string& name, const std::string& description, int value, int low, int high, int step=1):
Parameter(name, description, value), low_(low), high_(high), step_(step){}
~IntParameter(){}
virtual ~IntParameter(){}

operator int() const {return boost::any_cast<int>(current_value_);}

Expand Down Expand Up @@ -202,7 +202,7 @@ namespace pcl
public:
DoubleParameter(const std::string& name, const std::string& description, double value, double low, double high, double step=0.01):
Parameter(name, description, value), low_(low), high_(high), step_(step){}
~DoubleParameter(){}
virtual ~DoubleParameter(){}

operator double() const {return boost::any_cast<double>(current_value_);}

Expand Down
1 change: 1 addition & 0 deletions apps/src/convolve.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include <pcl/console/print.h>
#include <pcl/filters/convolution.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl/common/time.h>

void
usage (char ** argv)
Expand Down
1 change: 1 addition & 0 deletions apps/src/face_detection/openni_face_detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
#include "pcl/recognition/face_detection/rf_face_detector_trainer.h"
#include "pcl/apps/face_detection/openni_frame_source.h"
#include "pcl/apps/face_detection/face_detection_apps_utils.h"
#include <pcl/common/time.h>
#include <pcl/console/parse.h>
#include <pcl/features/integral_image_normal.h>

Expand Down
2 changes: 2 additions & 0 deletions apps/src/openni_passthrough.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,8 @@
// PCL
#include <pcl/console/parse.h>

#include <vtkRenderWindow.h>

////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
OpenNIPassthrough::OpenNIPassthrough (pcl::OpenNIGrabber& grabber)
: vis_ ()
Expand Down
2 changes: 2 additions & 0 deletions apps/src/organized_segmentation_demo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@
#include <pcl/segmentation/extract_polygonal_prism_data.h>
#include <pcl/surface/convex_hull.h>

#include <vtkRenderWindow.h>

void
displayPlanarRegions (std::vector<pcl::PlanarRegion<PointT>, Eigen::aligned_allocator<pcl::PlanarRegion<PointT> > > &regions,
boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer)
Expand Down
4 changes: 4 additions & 0 deletions examples/segmentation/example_supervoxels.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,10 @@
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl/segmentation/supervoxels.h>

#include <vtkImageReader2Factory.h>
#include <vtkImageReader2.h>
#include <vtkImageData.h>
#include <vtkImageFlip.h>

using namespace pcl;

Expand Down
1 change: 1 addition & 0 deletions people/apps/main_ground_based_people_detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@
#include <pcl/io/openni_grabber.h>
#include <pcl/sample_consensus/sac_model_plane.h>
#include <pcl/people/ground_based_people_detection_app.h>
#include <pcl/common/time.h>

typedef pcl::PointXYZRGBA PointT;
typedef pcl::PointCloud<PointT> PointCloudT;
Expand Down
6 changes: 3 additions & 3 deletions people/include/pcl/people/impl/person_classifier.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -199,9 +199,9 @@ pcl::people::PersonClassifier<PointT>::copyMakeBorder (PointCloudPtr& input_imag
int y_end_in = std::min(int(input_image->height-1), ymin+height-1);

int x_start_out = std::max(0, -xmin);
int x_end_out = x_start_out + (x_end_in - x_start_in);
//int x_end_out = x_start_out + (x_end_in - x_start_in);
int y_start_out = std::max(0, -ymin);
int y_end_out = y_start_out + (y_end_in - y_start_in);
//int y_end_out = y_start_out + (y_end_in - y_start_in);

for (unsigned int i = 0; i < (y_end_in - y_start_in + 1); i++)
{
Expand Down Expand Up @@ -284,7 +284,7 @@ pcl::people::PersonClassifier<PointT>::evaluate (PointCloudPtr& image,
Eigen::Vector3f& bottom,
Eigen::Vector3f& top,
Eigen::Vector3f& centroid,
Eigen::Matrix3f intrinsics_matrix,
Eigen::Matrix3f,
bool vertical)
{
float pixel_height;
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 @@ -669,7 +669,7 @@ loadPolygonMeshModel (char* polygon_file)
}

void
initialize (int argc, char** argv)
initialize (int, char** argv)
{
const GLubyte* version = glGetString (GL_VERSION);
std::cout << "OpenGL Version: " << version << std::endl;
Expand Down
2 changes: 2 additions & 0 deletions tools/obj_rec_ransac_accepted_hypotheses.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,8 @@
#include <pcl/io/pcd_io.h>
#include <pcl/point_cloud.h>
#include <vtkPolyDataReader.h>
#include <vtkRenderWindow.h>
#include <vtkTransformPolyDataFilter.h>
#include <vtkDoubleArray.h>
#include <vtkDataArray.h>
#include <vtkPointData.h>
Expand Down
1 change: 1 addition & 0 deletions tools/obj_rec_ransac_orr_octree.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,7 @@
#include <vtkPolyDataReader.h>
#include <vtkCubeSource.h>
#include <vtkPointData.h>
#include <vtkRenderWindow.h>
#include <vector>
#include <list>
#include <cstdlib>
Expand Down
1 change: 1 addition & 0 deletions tools/obj_rec_ransac_orr_octree_zprojection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@
#include <pcl/io/pcd_io.h>
#include <pcl/recognition/ransac_based/orr_octree_zprojection.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <vtkRenderWindow.h>
#include <vtkPolyData.h>
#include <vtkAppendPolyData.h>
#include <vtkPolyDataReader.h>
Expand Down
4 changes: 4 additions & 0 deletions tools/obj_rec_ransac_result.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,10 @@
#include <vtkDataArray.h>
#include <vtkPointData.h>
#include <vtkHedgeHog.h>
#include <vtkTransformPolyDataFilter.h>
#include <vtkRenderer.h>
#include <vtkRenderWindow.h>
#include <vtkTransform.h>
#include <cstdio>
#include <vector>
#include <list>
Expand Down
5 changes: 4 additions & 1 deletion tools/octree_viewer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
* */

#include <pcl/io/pcd_io.h>

#include <pcl/common/time.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl/visualization/point_cloud_handlers.h>
#include <pcl/visualization/common/common.h>
Expand All @@ -47,6 +47,9 @@
#include <pcl/filters/filter.h>
#include "boost.h"

#include <vtkRenderer.h>
#include <vtkRenderWindow.h>
#include <vtkCubeSource.h>
//=============================
// Displaying cubes is very long!
// so we limit their numbers.
Expand Down
5 changes: 4 additions & 1 deletion tools/voxel_grid_occlusion_estimation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,10 @@
#include <pcl/common/transforms.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl/filters/voxel_grid_occlusion_estimation.h>

#include <vtkCubeSource.h>
#include <vtkRenderer.h>
#include <vtkRenderWindow.h>
#include <vtkRenderWindowInteractor.h>
#include <vtkLine.h>

using namespace pcl;
Expand Down
1 change: 1 addition & 0 deletions visualization/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ if(build)
src/common/common.cpp
src/common/io.cpp
src/common/shapes.cpp
src/common/ren_win_interact_map.cpp
src/cloud_viewer.cpp
src/image_viewer.cpp
src/window.cpp
Expand Down
4 changes: 2 additions & 2 deletions visualization/include/pcl/visualization/area_picking_event.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
*
* Point Cloud Library (PCL) - www.pointclouds.org
* Copyright (c) 2010-2011, Willow Garage, Inc.
* Copyright (c) 2012-, Open Perception, Inc.
*
* All rights reserved.
*
Expand All @@ -16,7 +17,7 @@
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage, Inc. nor the names of its
* * Neither the name of the copyright holder(s) nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
Expand All @@ -33,7 +34,6 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
* $Id: $
*/

#ifndef PCL_VISUALIZATION_AREA_PICKING_EVENT_H_
Expand Down
3 changes: 0 additions & 3 deletions visualization/include/pcl/visualization/cloud_viewer.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,10 +37,7 @@
#define PCL_CLOUD_VIEWER_H_

#include <pcl/visualization/pcl_visualizer.h> //pcl vis
#include <pcl/point_cloud.h> //basic pcl includes
#include <pcl/point_types.h>

#include <pcl/visualization/boost.h>
#include <string>

namespace pcl
Expand Down
8 changes: 5 additions & 3 deletions visualization/include/pcl/visualization/common/actor_map.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,12 @@

#include <pcl/visualization/point_cloud_handlers.h>
#include <vector>
#include <vtkLODActor.h>
#include <vtkSmartPointer.h>
#include <sensor_msgs/PointCloud2.h>
#include <pcl/visualization/boost.h>
#include <boost/unordered_map.hpp>

template <typename T> class vtkSmartPointer;
class vtkLODActor;
class vtkProp;

namespace pcl
{
Expand Down
3 changes: 2 additions & 1 deletion visualization/include/pcl/visualization/common/common.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,12 +42,13 @@
#endif

#include <pcl/pcl_macros.h>
#include <pcl/point_types.h>
#include <pcl/visualization/eigen.h>
#include <vtkMatrix4x4.h>

namespace pcl
{
class RGB;

namespace visualization
{
/** \brief Get (good) random values for R/G/B.
Expand Down
11 changes: 9 additions & 2 deletions visualization/include/pcl/visualization/common/impl/shapes.hpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,10 @@
/*
* Software License Agreement (BSD License)
*
* Point Cloud Library (PCL) - www.pointclouds.org
* Copyright (c) 2010, Willow Garage, Inc.
* Copyright (c) 2012-, Open Perception, Inc.
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
Expand Down Expand Up @@ -31,10 +34,14 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
* $Id$
*
*/

#pragma once
#include <vtkSmartPointer.h>
#include <vtkPoints.h>
#include <vtkPolygon.h>
#include <vtkUnstructuredGrid.h>

////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointT> vtkSmartPointer<vtkDataSet>
pcl::visualization::createPolygon (const typename pcl::PointCloud<PointT>::ConstPtr &cloud)
Expand Down
10 changes: 6 additions & 4 deletions visualization/include/pcl/visualization/common/io.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,10 @@
/*
* Software License Agreement (BSD License)
*
* Point Cloud Library (PCL) - www.pointclouds.org
* Copyright (c) 2010, Willow Garage, Inc.
* Copyright (c) 2012-, Open Perception, Inc.
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
Expand All @@ -14,7 +17,7 @@
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage, Inc. nor the names of its
* * Neither the name of the copyright holder(s) nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
Expand All @@ -31,17 +34,16 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
* $Id$
*
*/
#ifndef PCL_PCL_VISUALIZER_COMMON_IO_H_
#define PCL_PCL_VISUALIZER_COMMON_IO_H_

#include <pcl/visualization/common/actor_map.h>
#include <pcl/visualization/vtk.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/console/print.h>

class vtkPolyData;

namespace pcl
{
namespace visualization
Expand Down
Loading

0 comments on commit aff4fe9

Please sign in to comment.