Public Member Functions | |
vm::Marker | makeBox (vm::InteractiveMarker &msg, btVector3 min_bound, btVector3 max_bound) |
void | makeSizeHandles () |
PointCouldSelector (boost::shared_ptr< interactive_markers::InteractiveMarkerServer > server, std::vector< btVector3 > &points) | |
void | processAxisFeedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
void | updateBox () |
void | updatePointCloud (std::string name, std_msgs::ColorRGBA color, std::vector< btVector3 > &points) |
void | updatePointClouds () |
void | updateSizeHandles () |
Private Attributes | |
btVector3 | max_sel_ |
btVector3 | min_sel_ |
std::vector< btVector3 > | points_ |
vm::InteractiveMarker | sel_points_marker_ |
boost::shared_ptr < interactive_markers::InteractiveMarkerServer > | server_ |
vm::InteractiveMarker | unsel_points_marker_ |
Definition at line 43 of file selection.cpp.
PointCouldSelector::PointCouldSelector | ( | boost::shared_ptr< interactive_markers::InteractiveMarkerServer > | server, |
std::vector< btVector3 > & | points | ||
) | [inline] |
Definition at line 46 of file selection.cpp.
vm::Marker PointCouldSelector::makeBox | ( | vm::InteractiveMarker & | msg, |
btVector3 | min_bound, | ||
btVector3 | max_bound | ||
) | [inline] |
Definition at line 84 of file selection.cpp.
void PointCouldSelector::makeSizeHandles | ( | ) | [inline] |
Definition at line 188 of file selection.cpp.
void PointCouldSelector::processAxisFeedback | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [inline] |
Definition at line 59 of file selection.cpp.
void PointCouldSelector::updateBox | ( | ) | [inline] |
Definition at line 104 of file selection.cpp.
void PointCouldSelector::updatePointCloud | ( | std::string | name, |
std_msgs::ColorRGBA | color, | ||
std::vector< btVector3 > & | points | ||
) | [inline] |
Definition at line 117 of file selection.cpp.
void PointCouldSelector::updatePointClouds | ( | ) | [inline] |
Definition at line 153 of file selection.cpp.
void PointCouldSelector::updateSizeHandles | ( | ) | [inline] |
Definition at line 244 of file selection.cpp.
btVector3 PointCouldSelector::max_sel_ [private] |
Definition at line 283 of file selection.cpp.
btVector3 PointCouldSelector::min_sel_ [private] |
Definition at line 283 of file selection.cpp.
std::vector<btVector3> PointCouldSelector::points_ [private] |
Definition at line 284 of file selection.cpp.
vm::InteractiveMarker PointCouldSelector::sel_points_marker_ [private] |
Definition at line 286 of file selection.cpp.
boost::shared_ptr<interactive_markers::InteractiveMarkerServer> PointCouldSelector::server_ [private] |
Definition at line 281 of file selection.cpp.
vm::InteractiveMarker PointCouldSelector::unsel_points_marker_ [private] |
Definition at line 287 of file selection.cpp.