#include <interactive_object_detection_frame.h>
Public Member Functions | |
InteractiveObjectDetectionFrame (InteractiveObjectDetectionDisplay *display, wxWindow *parent) | |
void | update () |
~InteractiveObjectDetectionFrame () | |
Protected Member Functions | |
void | cancelButtonClicked (wxCommandEvent &event) |
virtual void | detButtonClicked (wxCommandEvent &event) |
void | executeRequest (int8_t request, bool interactive) |
virtual void | recButtonClicked (wxCommandEvent &event) |
void | requestUserCommand (int8_t request, bool interactive) |
virtual void | segButtonClicked (wxCommandEvent &event) |
void | userCmdActive () |
void | userCmdDone (const actionlib::SimpleClientGoalState &state, const pr2_interactive_object_detection::UserCommandResultConstPtr &result) |
void | userCmdFeedback (const pr2_interactive_object_detection::UserCommandFeedbackConstPtr &feedback) |
Protected Attributes | |
bool | action_requested_ |
std::string | det_status_ |
boost::thread * | executing_thread_ |
boost::mutex | mutex_ |
ros::NodeHandle | priv_nh_ |
std::string | rec_status_ |
ros::NodeHandle | root_nh_ |
std::string | seg_status_ |
std::string | status_ |
actionlib::SimpleActionClient < pr2_interactive_object_detection::UserCommandAction > | user_cmd_action_client_ |
UserCommandGoal | user_command_goal_ |
Definition at line 43 of file interactive_object_detection_frame.h.
pr2_interactive_object_detection::InteractiveObjectDetectionFrame::InteractiveObjectDetectionFrame | ( | InteractiveObjectDetectionDisplay * | display, | |
wxWindow * | parent | |||
) |
Definition at line 40 of file interactive_object_detection_frame.cpp.
pr2_interactive_object_detection::InteractiveObjectDetectionFrame::~InteractiveObjectDetectionFrame | ( | ) |
Definition at line 51 of file interactive_object_detection_frame.cpp.
void pr2_interactive_object_detection::InteractiveObjectDetectionFrame::cancelButtonClicked | ( | wxCommandEvent & | event | ) | [protected, virtual] |
Reimplemented from InteractiveObjectDetectionFrameBase.
Definition at line 163 of file interactive_object_detection_frame.cpp.
void pr2_interactive_object_detection::InteractiveObjectDetectionFrame::detButtonClicked | ( | wxCommandEvent & | event | ) | [protected, virtual] |
Reimplemented from InteractiveObjectDetectionFrameBase.
Definition at line 219 of file interactive_object_detection_frame.cpp.
void pr2_interactive_object_detection::InteractiveObjectDetectionFrame::executeRequest | ( | int8_t | request, | |
bool | interactive | |||
) | [protected] |
Definition at line 173 of file interactive_object_detection_frame.cpp.
void pr2_interactive_object_detection::InteractiveObjectDetectionFrame::recButtonClicked | ( | wxCommandEvent & | event | ) | [protected, virtual] |
Reimplemented from InteractiveObjectDetectionFrameBase.
Definition at line 212 of file interactive_object_detection_frame.cpp.
void pr2_interactive_object_detection::InteractiveObjectDetectionFrame::requestUserCommand | ( | int8_t | request, | |
bool | interactive | |||
) | [protected] |
Definition at line 67 of file interactive_object_detection_frame.cpp.
void pr2_interactive_object_detection::InteractiveObjectDetectionFrame::segButtonClicked | ( | wxCommandEvent & | event | ) | [protected, virtual] |
Reimplemented from InteractiveObjectDetectionFrameBase.
Definition at line 204 of file interactive_object_detection_frame.cpp.
void pr2_interactive_object_detection::InteractiveObjectDetectionFrame::update | ( | ) |
Definition at line 88 of file interactive_object_detection_frame.cpp.
void pr2_interactive_object_detection::InteractiveObjectDetectionFrame::userCmdActive | ( | ) | [protected] |
Definition at line 145 of file interactive_object_detection_frame.cpp.
void pr2_interactive_object_detection::InteractiveObjectDetectionFrame::userCmdDone | ( | const actionlib::SimpleClientGoalState & | state, | |
const pr2_interactive_object_detection::UserCommandResultConstPtr & | result | |||
) | [protected] |
Definition at line 118 of file interactive_object_detection_frame.cpp.
void pr2_interactive_object_detection::InteractiveObjectDetectionFrame::userCmdFeedback | ( | const pr2_interactive_object_detection::UserCommandFeedbackConstPtr & | feedback | ) | [protected] |
Definition at line 152 of file interactive_object_detection_frame.cpp.
bool pr2_interactive_object_detection::InteractiveObjectDetectionFrame::action_requested_ [protected] |
Definition at line 78 of file interactive_object_detection_frame.h.
std::string pr2_interactive_object_detection::InteractiveObjectDetectionFrame::det_status_ [protected] |
Definition at line 88 of file interactive_object_detection_frame.h.
boost::thread* pr2_interactive_object_detection::InteractiveObjectDetectionFrame::executing_thread_ [protected] |
Definition at line 94 of file interactive_object_detection_frame.h.
boost::mutex pr2_interactive_object_detection::InteractiveObjectDetectionFrame::mutex_ [protected] |
Definition at line 92 of file interactive_object_detection_frame.h.
ros::NodeHandle pr2_interactive_object_detection::InteractiveObjectDetectionFrame::priv_nh_ [protected] |
Definition at line 82 of file interactive_object_detection_frame.h.
std::string pr2_interactive_object_detection::InteractiveObjectDetectionFrame::rec_status_ [protected] |
Definition at line 87 of file interactive_object_detection_frame.h.
ros::NodeHandle pr2_interactive_object_detection::InteractiveObjectDetectionFrame::root_nh_ [protected] |
Definition at line 81 of file interactive_object_detection_frame.h.
std::string pr2_interactive_object_detection::InteractiveObjectDetectionFrame::seg_status_ [protected] |
Definition at line 86 of file interactive_object_detection_frame.h.
std::string pr2_interactive_object_detection::InteractiveObjectDetectionFrame::status_ [protected] |
Definition at line 84 of file interactive_object_detection_frame.h.
actionlib::SimpleActionClient<pr2_interactive_object_detection::UserCommandAction> pr2_interactive_object_detection::InteractiveObjectDetectionFrame::user_cmd_action_client_ [protected] |
Definition at line 76 of file interactive_object_detection_frame.h.
UserCommandGoal pr2_interactive_object_detection::InteractiveObjectDetectionFrame::user_command_goal_ [protected] |
Definition at line 90 of file interactive_object_detection_frame.h.