#include <interactive_manipulation_frontend.h>

Public Member Functions | |
| InteractiveManipulationFrontend (wxWindow *parent, rviz::VisualizationManager *manager) | |
| void | setAdvancedOptions (IMGUIAdvancedOptions ago) |
| void | update () |
| ~InteractiveManipulationFrontend () | |
Protected Member Functions | |
| virtual void | advancedOptionsClicked (wxCommandEvent &event) |
| virtual void | armGoButtonClicked (wxCommandEvent &event) |
| virtual void | cancelButtonClicked (wxCommandEvent &event) |
| void | feedbackCallback (const IMGUIFeedbackConstPtr &feedback) |
| IMGUIOptions | getDialogOptions () |
| void | graspableObjectsCallback (const pr2_interactive_object_detection::GraspableObjectListConstPtr &objects) |
| virtual void | graspButtonClicked (wxCommandEvent &event) |
| virtual void | gripperSliderScrollChanged (wxScrollEvent &) |
| virtual void | lookButtonClicked (wxCommandEvent &event) |
| virtual void | modelObjectClicked (wxCommandEvent &event) |
| virtual void | placeButtonClicked (wxCommandEvent &event) |
| virtual void | resetButtonClicked (wxCommandEvent &event) |
| virtual void | takeMapButtonClicked (wxCommandEvent &event) |
Protected Attributes | |
| actionlib::SimpleActionClient < IMGUIAction > * | action_client_ |
| std::string | action_name_ |
| bool | active_goal_ |
| IMGUIAdvancedOptions | adv_options_ |
| ros::Subscriber | graspable_objects_sub_ |
| bool | new_object_list_ |
| ObjectSelectionFrame * | object_selection_frame_ |
| ros::NodeHandle | priv_nh_ |
| pr2_interactive_object_detection::GraspableObjectListConstPtr | received_objects_ |
| boost::mutex | received_objects_mutex_ |
| ros::NodeHandle | root_nh_ |
| boost::mutex | status_label_mutex_ |
| std::string | status_label_text_ |
Definition at line 52 of file interactive_manipulation_frontend.h.
| pr2_interactive_manipulation::InteractiveManipulationFrontend::InteractiveManipulationFrontend | ( | wxWindow * | parent, | |
| rviz::VisualizationManager * | manager | |||
| ) |
Definition at line 38 of file interactive_manipulation_frontend.cpp.
| pr2_interactive_manipulation::InteractiveManipulationFrontend::~InteractiveManipulationFrontend | ( | ) |
Definition at line 56 of file interactive_manipulation_frontend.cpp.
| void pr2_interactive_manipulation::InteractiveManipulationFrontend::advancedOptionsClicked | ( | wxCommandEvent & | event | ) | [protected, virtual] |
Reimplemented from InteractiveManipulationFrameBase.
Definition at line 258 of file interactive_manipulation_frontend.cpp.
| void pr2_interactive_manipulation::InteractiveManipulationFrontend::armGoButtonClicked | ( | wxCommandEvent & | event | ) | [protected, virtual] |
Reimplemented from InteractiveManipulationFrameBase.
Definition at line 218 of file interactive_manipulation_frontend.cpp.
| void pr2_interactive_manipulation::InteractiveManipulationFrontend::cancelButtonClicked | ( | wxCommandEvent & | event | ) | [protected, virtual] |
Reimplemented from InteractiveManipulationFrameBase.
Definition at line 161 of file interactive_manipulation_frontend.cpp.
| void pr2_interactive_manipulation::InteractiveManipulationFrontend::feedbackCallback | ( | const IMGUIFeedbackConstPtr & | feedback | ) | [protected] |
Definition at line 146 of file interactive_manipulation_frontend.cpp.
| IMGUIOptions pr2_interactive_manipulation::InteractiveManipulationFrontend::getDialogOptions | ( | ) | [protected] |
Definition at line 265 of file interactive_manipulation_frontend.cpp.
| void pr2_interactive_manipulation::InteractiveManipulationFrontend::graspableObjectsCallback | ( | const pr2_interactive_object_detection::GraspableObjectListConstPtr & | objects | ) | [protected] |
Definition at line 153 of file interactive_manipulation_frontend.cpp.
| void pr2_interactive_manipulation::InteractiveManipulationFrontend::graspButtonClicked | ( | wxCommandEvent & | event | ) | [protected, virtual] |
Reimplemented from InteractiveManipulationFrameBase.
Definition at line 166 of file interactive_manipulation_frontend.cpp.
| void pr2_interactive_manipulation::InteractiveManipulationFrontend::gripperSliderScrollChanged | ( | wxScrollEvent & | ) | [protected, virtual] |
Reimplemented from InteractiveManipulationFrameBase.
Definition at line 248 of file interactive_manipulation_frontend.cpp.
| void pr2_interactive_manipulation::InteractiveManipulationFrontend::lookButtonClicked | ( | wxCommandEvent & | event | ) | [protected, virtual] |
Reimplemented from InteractiveManipulationFrameBase.
Definition at line 228 of file interactive_manipulation_frontend.cpp.
| void pr2_interactive_manipulation::InteractiveManipulationFrontend::modelObjectClicked | ( | wxCommandEvent & | event | ) | [protected, virtual] |
Reimplemented from InteractiveManipulationFrameBase.
Definition at line 238 of file interactive_manipulation_frontend.cpp.
| void pr2_interactive_manipulation::InteractiveManipulationFrontend::placeButtonClicked | ( | wxCommandEvent & | event | ) | [protected, virtual] |
Reimplemented from InteractiveManipulationFrameBase.
Definition at line 188 of file interactive_manipulation_frontend.cpp.
| void pr2_interactive_manipulation::InteractiveManipulationFrontend::resetButtonClicked | ( | wxCommandEvent & | event | ) | [protected, virtual] |
Reimplemented from InteractiveManipulationFrameBase.
Definition at line 208 of file interactive_manipulation_frontend.cpp.
| void pr2_interactive_manipulation::InteractiveManipulationFrontend::setAdvancedOptions | ( | IMGUIAdvancedOptions | ago | ) | [inline] |
Definition at line 61 of file interactive_manipulation_frontend.h.
| void pr2_interactive_manipulation::InteractiveManipulationFrontend::takeMapButtonClicked | ( | wxCommandEvent & | event | ) | [protected, virtual] |
Reimplemented from InteractiveManipulationFrameBase.
Definition at line 198 of file interactive_manipulation_frontend.cpp.
| void pr2_interactive_manipulation::InteractiveManipulationFrontend::update | ( | ) |
Definition at line 68 of file interactive_manipulation_frontend.cpp.
actionlib::SimpleActionClient<IMGUIAction>* pr2_interactive_manipulation::InteractiveManipulationFrontend::action_client_ [protected] |
Definition at line 100 of file interactive_manipulation_frontend.h.
std::string pr2_interactive_manipulation::InteractiveManipulationFrontend::action_name_ [protected] |
Definition at line 102 of file interactive_manipulation_frontend.h.
Definition at line 110 of file interactive_manipulation_frontend.h.
IMGUIAdvancedOptions pr2_interactive_manipulation::InteractiveManipulationFrontend::adv_options_ [protected] |
Definition at line 108 of file interactive_manipulation_frontend.h.
ros::Subscriber pr2_interactive_manipulation::InteractiveManipulationFrontend::graspable_objects_sub_ [protected] |
Definition at line 95 of file interactive_manipulation_frontend.h.
Definition at line 98 of file interactive_manipulation_frontend.h.
ObjectSelectionFrame* pr2_interactive_manipulation::InteractiveManipulationFrontend::object_selection_frame_ [protected] |
Definition at line 112 of file interactive_manipulation_frontend.h.
ros::NodeHandle pr2_interactive_manipulation::InteractiveManipulationFrontend::priv_nh_ [protected] |
Definition at line 93 of file interactive_manipulation_frontend.h.
pr2_interactive_object_detection::GraspableObjectListConstPtr pr2_interactive_manipulation::InteractiveManipulationFrontend::received_objects_ [protected] |
Definition at line 96 of file interactive_manipulation_frontend.h.
boost::mutex pr2_interactive_manipulation::InteractiveManipulationFrontend::received_objects_mutex_ [protected] |
Definition at line 97 of file interactive_manipulation_frontend.h.
ros::NodeHandle pr2_interactive_manipulation::InteractiveManipulationFrontend::root_nh_ [protected] |
Definition at line 91 of file interactive_manipulation_frontend.h.
boost::mutex pr2_interactive_manipulation::InteractiveManipulationFrontend::status_label_mutex_ [protected] |
Definition at line 106 of file interactive_manipulation_frontend.h.
std::string pr2_interactive_manipulation::InteractiveManipulationFrontend::status_label_text_ [protected] |
Definition at line 104 of file interactive_manipulation_frontend.h.