#include <table_marker.h>
Public Member Functions | |
void | createInteractiveMarkerForTable () |
Publish interactive markers for a table detected by table_extractiion node using interactive marker server. | |
void | createMarkerforTable (visualization_msgs::InteractiveMarkerControl &im_ctrl) |
Create marker for the table and add it to the interactive marker control. | |
void | createTableMenu () |
Create menu entries for each table. | |
void | MoveToTheTable (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
feedback callback for Move to this table menu entry | |
TPPLPoint | msgToPoint2DforTable (const pcl::PointXYZ &point) |
Create menu entries for each shape. | |
void | tableFeedbackCallback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
callback function when there is a mouse click on interactive marker | |
TableMarker (boost::shared_ptr< interactive_markers::InteractiveMarkerServer > server, cob_3d_mapping_msgs::Shape &table, int ctr) | |
~TableMarker () | |
Protected Attributes | |
ros::Publisher | goal_pub_ |
int | id_ |
visualization_msgs::InteractiveMarkerControl | im_ctrl |
ros::NodeHandle | nh_ |
cob_3d_mapping_msgs::Shape | table_ |
boost::shared_ptr < interactive_markers::InteractiveMarkerServer > | table_im_server_ |
visualization_msgs::InteractiveMarker | table_int_marker_ |
visualization_msgs::Marker | table_marker_ |
interactive_markers::MenuHandler | table_menu_handler_ |
Eigen::Affine3f | transformation_ |
Eigen::Affine3f | transformation_inv_ |
Definition at line 110 of file table_marker.h.
TableMarker::TableMarker | ( | boost::shared_ptr< interactive_markers::InteractiveMarkerServer > | server, |
cob_3d_mapping_msgs::Shape & | table, | ||
int | ctr | ||
) |
Definition at line 62 of file table_marker.cpp.
TableMarker::~TableMarker | ( | ) | [inline] |
Definition at line 117 of file table_marker.h.
Publish interactive markers for a table detected by table_extractiion node using interactive marker server.
Definition at line 76 of file table_marker.cpp.
void TableMarker::createMarkerforTable | ( | visualization_msgs::InteractiveMarkerControl & | im_ctrl | ) |
Create marker for the table and add it to the interactive marker control.
[in] | triangle_list | triangulated list of poly points |
[in] | im_ctrl | interactive marker control |
Definition at line 110 of file table_marker.cpp.
void TableMarker::createTableMenu | ( | ) |
Create menu entries for each table.
Definition at line 220 of file table_marker.cpp.
void TableMarker::MoveToTheTable | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) |
feedback callback for Move to this table menu entry
[in] | feedback | feedback from rviz when Move to this table menu entry of a detected table is chosen |
Definition at line 229 of file table_marker.cpp.
TPPLPoint TableMarker::msgToPoint2DforTable | ( | const pcl::PointXYZ & | point | ) |
Create menu entries for each shape.
[in] | point | 3D point to be transformed |
[out] | transformed | 2D TPPLPoint |
Definition at line 204 of file table_marker.cpp.
void TableMarker::tableFeedbackCallback | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) |
callback function when there is a mouse click on interactive marker
[in] | feedback | feedback from rviz when there is a mouse click on interactive marker |
Definition at line 215 of file table_marker.cpp.
ros::Publisher TableMarker::goal_pub_ [protected] |
Definition at line 163 of file table_marker.h.
int TableMarker::id_ [protected] |
Definition at line 173 of file table_marker.h.
visualization_msgs::InteractiveMarkerControl TableMarker::im_ctrl [protected] |
Definition at line 166 of file table_marker.h.
ros::NodeHandle TableMarker::nh_ [protected] |
Definition at line 159 of file table_marker.h.
cob_3d_mapping_msgs::Shape TableMarker::table_ [protected] |
Definition at line 161 of file table_marker.h.
boost::shared_ptr<interactive_markers::InteractiveMarkerServer> TableMarker::table_im_server_ [protected] |
Definition at line 167 of file table_marker.h.
visualization_msgs::InteractiveMarker TableMarker::table_int_marker_ [protected] |
Definition at line 156 of file table_marker.h.
visualization_msgs::Marker TableMarker::table_marker_ [protected] |
Definition at line 157 of file table_marker.h.
Definition at line 168 of file table_marker.h.
Eigen::Affine3f TableMarker::transformation_ [protected] |
Definition at line 170 of file table_marker.h.
Eigen::Affine3f TableMarker::transformation_inv_ [protected] |
Definition at line 171 of file table_marker.h.