$search

pr2_interactive_manipulation::InteractiveManipulationFrontend Class Reference

#include <interactive_manipulation_frontend.h>

Inheritance diagram for pr2_interactive_manipulation::InteractiveManipulationFrontend:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 InteractiveManipulationFrontend (wxWindow *parent, rviz::VisualizationManager *manager)
void setAdvancedOptions (pr2_object_manipulation_msgs::IMGUIAdvancedOptions ago)
void update ()
 ~InteractiveManipulationFrontend ()

Public Attributes

int interface_number_
int task_number_

Protected Member Functions

virtual void advancedOptionsClicked (wxCommandEvent &event)
virtual void armGoButtonClicked (wxCommandEvent &event)
virtual void cameraFrontButtonClicked (wxCommandEvent &event)
virtual void cameraLeftButtonClicked (wxCommandEvent &event)
virtual void cameraRightButtonClicked (wxCommandEvent &event)
virtual void cameraTopButtonClicked (wxCommandEvent &event)
virtual void cancelButtonClicked (wxCommandEvent &event)
void feedbackCallback (const pr2_object_manipulation_msgs::IMGUIFeedbackConstPtr &feedback)
pr2_object_manipulation_msgs::IMGUIOptions getDialogOptions ()
virtual void graspButtonClicked (wxCommandEvent &event)
virtual void gripperSliderScrollChanged (wxScrollEvent &)
virtual void modelObjectClicked (wxCommandEvent &event)
virtual void placeButtonClicked (wxCommandEvent &event)
virtual void plannedMoveButtonClicked (wxCommandEvent &event)
void rcommanderRefresh ()
virtual void rcommandRefreshButtonClicked (wxCommandEvent &event)
virtual void rcommandRunButtonClicked (wxCommandEvent &event)
virtual void resetButtonClicked (wxCommandEvent &event)
void setCamera (std::vector< double > params)
void statusCallback (const std_msgs::StringConstPtr &status)
virtual void stopNavButtonClicked (wxCommandEvent &event)

Protected Attributes

actionlib::SimpleActionClient
< pr2_object_manipulation_msgs::IMGUIAction > * 
action_client_
std::string action_name_
pr2_object_manipulation_msgs::IMGUIAdvancedOptions adv_options_
ros::NodeHandle priv_nh_
ros::ServiceClient rcommander_action_info_client_
std::string rcommander_action_info_name_
std::string rcommander_group_name_
ros::NodeHandle root_nh_
boost::mutex status_label_mutex_
std::string status_label_text_
std::string status_name_
ros::Subscriber status_sub_
rviz::VisualizationManagervis_manager_

Detailed Description

Definition at line 53 of file interactive_manipulation_frontend.h.


Constructor & Destructor Documentation

pr2_interactive_manipulation::InteractiveManipulationFrontend::InteractiveManipulationFrontend ( wxWindow *  parent,
rviz::VisualizationManager manager 
)

Definition at line 43 of file interactive_manipulation_frontend.cpp.

pr2_interactive_manipulation::InteractiveManipulationFrontend::~InteractiveManipulationFrontend (  ) 

Definition at line 111 of file interactive_manipulation_frontend.cpp.


Member Function Documentation

void pr2_interactive_manipulation::InteractiveManipulationFrontend::advancedOptionsClicked ( wxCommandEvent &  event  )  [protected, virtual]

Reimplemented from InteractiveManipulationFrameBase.

Definition at line 276 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::armGoButtonClicked ( wxCommandEvent &  event  )  [protected, virtual]

Reimplemented from InteractiveManipulationFrameBase.

Definition at line 200 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::cameraFrontButtonClicked ( wxCommandEvent &  event  )  [protected, virtual]

Definition at line 343 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::cameraLeftButtonClicked ( wxCommandEvent &  event  )  [protected, virtual]

Definition at line 333 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::cameraRightButtonClicked ( wxCommandEvent &  event  )  [protected, virtual]

Definition at line 338 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::cameraTopButtonClicked ( wxCommandEvent &  event  )  [protected, virtual]

Definition at line 348 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::cancelButtonClicked ( wxCommandEvent &  event  )  [protected, virtual]

Reimplemented from InteractiveManipulationFrameBase.

Definition at line 150 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::feedbackCallback ( const pr2_object_manipulation_msgs::IMGUIFeedbackConstPtr feedback  )  [protected]

Definition at line 140 of file interactive_manipulation_frontend.cpp.

pr2_object_manipulation_msgs::IMGUIOptions pr2_interactive_manipulation::InteractiveManipulationFrontend::getDialogOptions (  )  [protected]

Definition at line 283 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::graspButtonClicked ( wxCommandEvent &  event  )  [protected, virtual]

Reimplemented from InteractiveManipulationFrameBase.

Definition at line 164 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::gripperSliderScrollChanged ( wxScrollEvent &   )  [protected, virtual]

Reimplemented from InteractiveManipulationFrameBase.

Definition at line 267 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::modelObjectClicked ( wxCommandEvent &  event  )  [protected, virtual]

Reimplemented from InteractiveManipulationFrameBase.

Definition at line 209 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::placeButtonClicked ( wxCommandEvent &  event  )  [protected, virtual]

Reimplemented from InteractiveManipulationFrameBase.

Definition at line 173 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::plannedMoveButtonClicked ( wxCommandEvent &  event  )  [protected, virtual]

Reimplemented from InteractiveManipulationFrameBase.

Definition at line 182 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::rcommanderRefresh (  )  [protected]

Definition at line 249 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::rcommandRefreshButtonClicked ( wxCommandEvent &  event  )  [protected, virtual]

Reimplemented from InteractiveManipulationFrameBase.

Definition at line 244 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::rcommandRunButtonClicked ( wxCommandEvent &  event  )  [protected, virtual]

Reimplemented from InteractiveManipulationFrameBase.

Definition at line 227 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::resetButtonClicked ( wxCommandEvent &  event  )  [protected, virtual]

Reimplemented from InteractiveManipulationFrameBase.

Definition at line 191 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::setAdvancedOptions ( pr2_object_manipulation_msgs::IMGUIAdvancedOptions  ago  )  [inline]

Definition at line 62 of file interactive_manipulation_frontend.h.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::setCamera ( std::vector< double >  params  )  [protected]

Definition at line 301 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::statusCallback ( const std_msgs::StringConstPtr &  status  )  [protected]

Definition at line 133 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::stopNavButtonClicked ( wxCommandEvent &  event  )  [protected, virtual]

Reimplemented from InteractiveManipulationFrameBase.

Definition at line 155 of file interactive_manipulation_frontend.cpp.

void pr2_interactive_manipulation::InteractiveManipulationFrontend::update ( void   ) 

Definition at line 122 of file interactive_manipulation_frontend.cpp.


Member Data Documentation

Definition at line 120 of file interactive_manipulation_frontend.h.

Definition at line 127 of file interactive_manipulation_frontend.h.

Definition at line 134 of file interactive_manipulation_frontend.h.

Definition at line 64 of file interactive_manipulation_frontend.h.

Definition at line 117 of file interactive_manipulation_frontend.h.

Definition at line 119 of file interactive_manipulation_frontend.h.

Definition at line 125 of file interactive_manipulation_frontend.h.

Definition at line 126 of file interactive_manipulation_frontend.h.

Definition at line 116 of file interactive_manipulation_frontend.h.

Definition at line 132 of file interactive_manipulation_frontend.h.

Definition at line 130 of file interactive_manipulation_frontend.h.

Definition at line 128 of file interactive_manipulation_frontend.h.

Definition at line 123 of file interactive_manipulation_frontend.h.

Definition at line 66 of file interactive_manipulation_frontend.h.

Definition at line 114 of file interactive_manipulation_frontend.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


pr2_interactive_manipulation
Author(s): Matei Ciocarlie, Kaijen Hsiao, Adam Leeper
autogenerated on Tue Mar 5 14:54:03 2013