Public Member Functions | |
TabletopObjectSegmenterGui () | |
~TabletopObjectSegmenterGui () | |
Private Member Functions | |
bool | assembleSensorData (object_segmentation_gui::ObjectSegmentationGuiGoal &goal, ros::Duration time_out) |
void | clearOldMarkers (std::string frame_id) |
Converts raw table detection results into a Table message type. | |
bool | segmServiceCallback (tabletop_object_detector::TabletopSegmentation::Request &request, tabletop_object_detector::TabletopSegmentation::Response &response) |
Callback for service calls. | |
Private Attributes | |
int | current_marker_id_ |
The current marker being published. | |
tf::TransformListener | listener_ |
ros::Publisher | marker_pub_ |
Publisher for markers. | |
int | num_markers_published_ |
Used to remember the number of markers we publish so we can delete them later. | |
actionlib::SimpleActionClient < object_segmentation_gui::ObjectSegmentationGuiAction > * | os_gui_action_client_ |
ros::ServiceServer | os_srv_ |
ros::NodeHandle | priv_nh_ |
Node handle in the private namespace. | |
ros::NodeHandle | root_nh_ |
The node handle. |
Definition at line 47 of file tabletop_object_segmentation_gui_node.cpp.
TabletopObjectSegmenterGui::TabletopObjectSegmenterGui | ( | ) | [inline] |
Definition at line 100 of file tabletop_object_segmentation_gui_node.cpp.
TabletopObjectSegmenterGui::~TabletopObjectSegmenterGui | ( | ) | [inline] |
Definition at line 111 of file tabletop_object_segmentation_gui_node.cpp.
bool TabletopObjectSegmenterGui::assembleSensorData | ( | object_segmentation_gui::ObjectSegmentationGuiGoal & | goal, | |
ros::Duration | time_out | |||
) | [private] |
Definition at line 171 of file tabletop_object_segmentation_gui_node.cpp.
void TabletopObjectSegmenterGui::clearOldMarkers | ( | std::string | frame_id | ) | [private] |
Converts raw table detection results into a Table message type.
Publishes rviz markers for the given tabletop clusters labels point cloud with the given labels Clears old published markers and remembers the current number of published markers
Definition at line 253 of file tabletop_object_segmentation_gui_node.cpp.
bool TabletopObjectSegmenterGui::segmServiceCallback | ( | tabletop_object_detector::TabletopSegmentation::Request & | request, | |
tabletop_object_detector::TabletopSegmentation::Response & | response | |||
) | [private] |
Callback for service calls.
Definition at line 125 of file tabletop_object_segmentation_gui_node.cpp.
int TabletopObjectSegmenterGui::current_marker_id_ [private] |
The current marker being published.
Definition at line 60 of file tabletop_object_segmentation_gui_node.cpp.
tf::TransformListener TabletopObjectSegmenterGui::listener_ [private] |
Definition at line 53 of file tabletop_object_segmentation_gui_node.cpp.
ros::Publisher TabletopObjectSegmenterGui::marker_pub_ [private] |
Publisher for markers.
Definition at line 49 of file tabletop_object_segmentation_gui_node.cpp.
int TabletopObjectSegmenterGui::num_markers_published_ [private] |
Used to remember the number of markers we publish so we can delete them later.
Definition at line 58 of file tabletop_object_segmentation_gui_node.cpp.
actionlib::SimpleActionClient<object_segmentation_gui::ObjectSegmentationGuiAction>* TabletopObjectSegmenterGui::os_gui_action_client_ [private] |
Definition at line 55 of file tabletop_object_segmentation_gui_node.cpp.
ros::ServiceServer TabletopObjectSegmenterGui::os_srv_ [private] |
Definition at line 51 of file tabletop_object_segmentation_gui_node.cpp.
ros::NodeHandle TabletopObjectSegmenterGui::priv_nh_ [private] |
Node handle in the private namespace.
Definition at line 46 of file tabletop_object_segmentation_gui_node.cpp.
ros::NodeHandle TabletopObjectSegmenterGui::root_nh_ [private] |
The node handle.
Definition at line 44 of file tabletop_object_segmentation_gui_node.cpp.