Public Member Functions | |
| vm::Marker | makeBox (vm::InteractiveMarker &msg, tf::Vector3 min_bound, tf::Vector3 max_bound) |
| void | makeSizeHandles () |
| PointCouldSelector (boost::shared_ptr< interactive_markers::InteractiveMarkerServer > server, std::vector< tf::Vector3 > &points) | |
| void | processAxisFeedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| void | updateBox () |
| void | updatePointCloud (std::string name, std_msgs::ColorRGBA color, std::vector< tf::Vector3 > &points) |
| void | updatePointClouds () |
| void | updateSizeHandles () |
Private Attributes | |
| tf::Vector3 | max_sel_ |
| tf::Vector3 | min_sel_ |
| std::vector< tf::Vector3 > | points_ |
| vm::InteractiveMarker | sel_points_marker_ |
| boost::shared_ptr < interactive_markers::InteractiveMarkerServer > | server_ |
| vm::InteractiveMarker | unsel_points_marker_ |
Definition at line 52 of file selection.cpp.
| PointCouldSelector::PointCouldSelector | ( | boost::shared_ptr< interactive_markers::InteractiveMarkerServer > | server, |
| std::vector< tf::Vector3 > & | points | ||
| ) | [inline] |
Definition at line 55 of file selection.cpp.
| vm::Marker PointCouldSelector::makeBox | ( | vm::InteractiveMarker & | msg, |
| tf::Vector3 | min_bound, | ||
| tf::Vector3 | max_bound | ||
| ) | [inline] |
Definition at line 93 of file selection.cpp.
| void PointCouldSelector::makeSizeHandles | ( | ) | [inline] |
Definition at line 197 of file selection.cpp.
| void PointCouldSelector::processAxisFeedback | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [inline] |
Definition at line 68 of file selection.cpp.
| void PointCouldSelector::updateBox | ( | ) | [inline] |
Definition at line 113 of file selection.cpp.
| void PointCouldSelector::updatePointCloud | ( | std::string | name, |
| std_msgs::ColorRGBA | color, | ||
| std::vector< tf::Vector3 > & | points | ||
| ) | [inline] |
Definition at line 126 of file selection.cpp.
| void PointCouldSelector::updatePointClouds | ( | ) | [inline] |
Definition at line 162 of file selection.cpp.
| void PointCouldSelector::updateSizeHandles | ( | ) | [inline] |
Definition at line 253 of file selection.cpp.
tf::Vector3 PointCouldSelector::max_sel_ [private] |
Definition at line 292 of file selection.cpp.
tf::Vector3 PointCouldSelector::min_sel_ [private] |
Definition at line 292 of file selection.cpp.
std::vector<tf::Vector3> PointCouldSelector::points_ [private] |
Definition at line 293 of file selection.cpp.
vm::InteractiveMarker PointCouldSelector::sel_points_marker_ [private] |
Definition at line 295 of file selection.cpp.
boost::shared_ptr<interactive_markers::InteractiveMarkerServer> PointCouldSelector::server_ [private] |
Definition at line 290 of file selection.cpp.
vm::InteractiveMarker PointCouldSelector::unsel_points_marker_ [private] |
Definition at line 296 of file selection.cpp.