#include <SurfaceSmootherNode.h>
Public Member Functions | |
| virtual void | colorMesh (pcl::PolygonMesh &mesh) |
| virtual void | generateMesh () |
| virtual void | measurementCallback (const sensor_msgs::PointCloud2ConstPtr &pc_msg) |
| virtual void | orientNormalsInMesh (pcl::PolygonMesh &mesh) |
| virtual void | ReadRosBag () |
| SurfaceSmootherNode () | |
| virtual | ~SurfaceSmootherNode () |
Protected Member Functions | |
| template<class T > | |
| bool | getROSParameter (std::string param_name, T ¶m_container) |
Protected Attributes | |
| SRPointCloud::Ptr | _current_pc |
| SRPointCloud::Ptr | _current_pc_copy |
| ros::NodeHandle | _node_handle |
| ros::Subscriber | _pc_subscriber |
Definition at line 120 of file SurfaceSmootherNode.h.
Constructor
Definition at line 73 of file SurfaceSmootherNode.cpp.
| SurfaceSmootherNode::~SurfaceSmootherNode | ( | ) | [virtual] |
Destructor
Definition at line 84 of file SurfaceSmootherNode.cpp.
| void SurfaceSmootherNode::colorMesh | ( | pcl::PolygonMesh & | mesh | ) | [virtual] |
Definition at line 633 of file SurfaceSmootherNode.cpp.
| void SurfaceSmootherNode::generateMesh | ( | ) | [virtual] |
Definition at line 106 of file SurfaceSmootherNode.cpp.
| bool omip::SurfaceSmootherNode::getROSParameter | ( | std::string | param_name, |
| T & | param_container | ||
| ) | [inline, protected] |
Definition at line 156 of file SurfaceSmootherNode.h.
| void SurfaceSmootherNode::measurementCallback | ( | const sensor_msgs::PointCloud2ConstPtr & | pc_msg | ) | [virtual] |
Definition at line 89 of file SurfaceSmootherNode.cpp.
| void SurfaceSmootherNode::orientNormalsInMesh | ( | pcl::PolygonMesh & | mesh | ) | [virtual] |
Definition at line 831 of file SurfaceSmootherNode.cpp.
| void SurfaceSmootherNode::ReadRosBag | ( | ) | [virtual] |
Definition at line 100 of file SurfaceSmootherNode.cpp.
SRPointCloud::Ptr omip::SurfaceSmootherNode::_current_pc [protected] |
Definition at line 152 of file SurfaceSmootherNode.h.
SRPointCloud::Ptr omip::SurfaceSmootherNode::_current_pc_copy [protected] |
Definition at line 153 of file SurfaceSmootherNode.h.
Definition at line 148 of file SurfaceSmootherNode.h.
Definition at line 150 of file SurfaceSmootherNode.h.