#include <ShapeRecPlotter.h>
Public Member Functions | |
| virtual void | InputPCmeasurementCallback (const sensor_msgs::PointCloud2ConstPtr &pc_msg) |
| void | plotShape () |
| ShapeRecPlotter () | |
| virtual | ~ShapeRecPlotter () |
Protected Member Functions | |
| template<class T > | |
| bool | getROSParameter (std::string param_name, T ¶m_container) |
Protected Attributes | |
| SRPointCloud::Ptr | _current_pc |
| ros::NodeHandle | _node_handle |
| ros::Publisher | _pc_publisher |
| ros::Subscriber | _pc_subscriber |
| tf::TransformListener * | _tf_listener |
Definition at line 122 of file ShapeRecPlotter.h.
Constructor
Definition at line 79 of file ShapeRecPlotter.cpp.
| ShapeRecPlotter::~ShapeRecPlotter | ( | ) | [virtual] |
Destructor
Definition at line 98 of file ShapeRecPlotter.cpp.
| bool omip::ShapeRecPlotter::getROSParameter | ( | std::string | param_name, |
| T & | param_container | ||
| ) | [inline, protected] |
Definition at line 156 of file ShapeRecPlotter.h.
| void ShapeRecPlotter::InputPCmeasurementCallback | ( | const sensor_msgs::PointCloud2ConstPtr & | pc_msg | ) | [virtual] |
Definition at line 175 of file ShapeRecPlotter.cpp.
| void ShapeRecPlotter::plotShape | ( | ) |
Definition at line 102 of file ShapeRecPlotter.cpp.
SRPointCloud::Ptr omip::ShapeRecPlotter::_current_pc [protected] |
Definition at line 150 of file ShapeRecPlotter.h.
ros::NodeHandle omip::ShapeRecPlotter::_node_handle [protected] |
Definition at line 144 of file ShapeRecPlotter.h.
ros::Publisher omip::ShapeRecPlotter::_pc_publisher [protected] |
Definition at line 148 of file ShapeRecPlotter.h.
ros::Subscriber omip::ShapeRecPlotter::_pc_subscriber [protected] |
Definition at line 146 of file ShapeRecPlotter.h.
tf::TransformListener* omip::ShapeRecPlotter::_tf_listener [protected] |
Definition at line 152 of file ShapeRecPlotter.h.