Public Member Functions | |
| void | callback (const sensor_msgs::ImageConstPtr &msg_ptr) |
| void | cloud_callback () |
| void | color_segment_callback () |
| int | pnpoly (int npol, std::vector< std::vector< int > > poly_vec, int x, int y) |
| void | pt_callback () |
| bool | reset_cb (UI_segment_object::None_Bool::Request ®, UI_segment_object::None_Bool::Response &res) |
| bool | save_image (UI_segment_object::Save::Request ®, UI_segment_object::Save::Response &res) |
| UI (ros::NodeHandle &nh) | |
| ~UI () | |
Static Public Member Functions | |
| static void | mouse_callback (int event, int x, int y, int flags, void *param) |
Public Attributes | |
| ros::ServiceServer | reset_service |
| ros::ServiceServer | save_img |
Protected Attributes | |
| sensor_msgs::CvBridge | bridge_ |
| IplImage * | cv_image |
| int | height |
| image_transport::Subscriber | image_sub_ |
| image_transport::ImageTransport | it_ |
| ros::NodeHandle | nh_ |
| int | width |
Definition at line 72 of file segment_object_node.cpp.
| UI::UI | ( | ros::NodeHandle & | nh | ) |
Definition at line 101 of file segment_object_node.cpp.
| UI::~UI | ( | ) |
Definition at line 115 of file segment_object_node.cpp.
| void UI::callback | ( | const sensor_msgs::ImageConstPtr & | msg_ptr | ) |
Definition at line 228 of file segment_object_node.cpp.
| void UI::cloud_callback | ( | ) |
Definition at line 233 of file segment_object_node.cpp.
| void UI::color_segment_callback | ( | ) |
Definition at line 166 of file segment_object_node.cpp.
| void UI::mouse_callback | ( | int | event, |
| int | x, | ||
| int | y, | ||
| int | flags, | ||
| void * | param | ||
| ) | [static] |
Definition at line 133 of file segment_object_node.cpp.
| int UI::pnpoly | ( | int | npol, |
| std::vector< std::vector< int > > | poly_vec, | ||
| int | x, | ||
| int | y | ||
| ) |
Definition at line 290 of file segment_object_node.cpp.
| void UI::pt_callback | ( | ) |
Definition at line 200 of file segment_object_node.cpp.
| bool UI::reset_cb | ( | UI_segment_object::None_Bool::Request & | reg, |
| UI_segment_object::None_Bool::Response & | res | ||
| ) |
Definition at line 120 of file segment_object_node.cpp.
| bool UI::save_image | ( | UI_segment_object::Save::Request & | reg, |
| UI_segment_object::Save::Response & | res | ||
| ) |
Definition at line 303 of file segment_object_node.cpp.
sensor_msgs::CvBridge UI::bridge_ [protected] |
Definition at line 92 of file segment_object_node.cpp.
IplImage* UI::cv_image [protected] |
Definition at line 94 of file segment_object_node.cpp.
int UI::height [protected] |
Definition at line 95 of file segment_object_node.cpp.
image_transport::Subscriber UI::image_sub_ [protected] |
Definition at line 93 of file segment_object_node.cpp.
image_transport::ImageTransport UI::it_ [protected] |
Definition at line 91 of file segment_object_node.cpp.
ros::NodeHandle UI::nh_ [protected] |
Definition at line 90 of file segment_object_node.cpp.
Definition at line 86 of file segment_object_node.cpp.
Definition at line 87 of file segment_object_node.cpp.
int UI::width [protected] |
Definition at line 96 of file segment_object_node.cpp.