pr2_interactive_manipulation::ObjectSelectionFrame Class Reference

#include <object_selection_frame.h>

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

List of all members.

Public Types

enum  ActionState { IDLE, ACTIVE, ACCEPTED, CANCELED }

Public Member Functions

unsigned int getSelectedObject ()
ActionState getState ()
 ObjectSelectionFrame (rviz::VisualizationManager *visualization_manager, wxWindow *parent)
void onRenderWindowMouseEvents (wxMouseEvent &event)
void setData (pr2_interactive_object_detection::GraspableObjectListConstPtr received_objects)
void setState (ActionState state)
void update ()
virtual ~ObjectSelectionFrame ()

Protected Member Functions

virtual void acceptButtonClicked (wxCommandEvent &)
void addCluster (int object_index, const sensor_msgs::PointCloud &cluster)
void addMesh (int object_index, const geometric_shapes_msgs::Shape &mesh, const geometry_msgs::Pose &pose)
virtual void cancelButtonClicked (wxCommandEvent &)
void cleanupAndHide ()
void createMaterials ()
void createRenderPanel (rviz::VisualizationManager *visualization_manager)

Protected Attributes

ActionState action_state_
rviz_interaction_tools::ImageOverlay * image_overlay_
std::map< unsigned,
boost::shared_ptr
< rviz_interaction_tools::MeshObject > > 
meshes_
Ogre::RaySceneQuery * ray_scene_query_
rviz::RenderPanel * render_panel_
Ogre::SceneManager * scene_manager_
Ogre::SceneNode * scene_root_
unsigned int selected_object_

Detailed Description

Definition at line 66 of file object_selection_frame.h.


Member Enumeration Documentation

Enumerator:
IDLE 
ACTIVE 
ACCEPTED 
CANCELED 

Definition at line 70 of file object_selection_frame.h.


Constructor & Destructor Documentation

pr2_interactive_manipulation::ObjectSelectionFrame::ObjectSelectionFrame ( rviz::VisualizationManager *  visualization_manager,
wxWindow *  parent 
)

Definition at line 64 of file object_selection_frame.cpp.

pr2_interactive_manipulation::ObjectSelectionFrame::~ObjectSelectionFrame (  )  [virtual]

Definition at line 89 of file object_selection_frame.cpp.


Member Function Documentation

void pr2_interactive_manipulation::ObjectSelectionFrame::acceptButtonClicked ( wxCommandEvent &   )  [protected, virtual]

Reimplemented from ObjectSelectionFrameBase.

Definition at line 354 of file object_selection_frame.cpp.

void pr2_interactive_manipulation::ObjectSelectionFrame::addCluster ( int  object_index,
const sensor_msgs::PointCloud &  cluster 
) [protected]

Definition at line 230 of file object_selection_frame.cpp.

void pr2_interactive_manipulation::ObjectSelectionFrame::addMesh ( int  object_index,
const geometric_shapes_msgs::Shape &  mesh,
const geometry_msgs::Pose &  pose 
) [protected]

Definition at line 248 of file object_selection_frame.cpp.

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

Reimplemented from ObjectSelectionFrameBase.

Definition at line 361 of file object_selection_frame.cpp.

void pr2_interactive_manipulation::ObjectSelectionFrame::cleanupAndHide (  )  [protected]

Definition at line 102 of file object_selection_frame.cpp.

void pr2_interactive_manipulation::ObjectSelectionFrame::createMaterials (  )  [protected]

Definition at line 144 of file object_selection_frame.cpp.

void pr2_interactive_manipulation::ObjectSelectionFrame::createRenderPanel ( rviz::VisualizationManager *  visualization_manager  )  [protected]

Definition at line 110 of file object_selection_frame.cpp.

unsigned int pr2_interactive_manipulation::ObjectSelectionFrame::getSelectedObject (  )  [inline]

Definition at line 87 of file object_selection_frame.h.

ActionState pr2_interactive_manipulation::ObjectSelectionFrame::getState (  )  [inline]

Definition at line 83 of file object_selection_frame.h.

void pr2_interactive_manipulation::ObjectSelectionFrame::onRenderWindowMouseEvents ( wxMouseEvent &  event  ) 

Definition at line 282 of file object_selection_frame.cpp.

void pr2_interactive_manipulation::ObjectSelectionFrame::setData ( pr2_interactive_object_detection::GraspableObjectListConstPtr  received_objects  ) 

Definition at line 195 of file object_selection_frame.cpp.

void pr2_interactive_manipulation::ObjectSelectionFrame::setState ( ActionState  state  )  [inline]

Definition at line 85 of file object_selection_frame.h.

void pr2_interactive_manipulation::ObjectSelectionFrame::update (  ) 

Definition at line 276 of file object_selection_frame.cpp.


Member Data Documentation

Definition at line 126 of file object_selection_frame.h.

rviz_interaction_tools::ImageOverlay* pr2_interactive_manipulation::ObjectSelectionFrame::image_overlay_ [protected]

Definition at line 119 of file object_selection_frame.h.

std::map< unsigned, boost::shared_ptr<rviz_interaction_tools::MeshObject> > pr2_interactive_manipulation::ObjectSelectionFrame::meshes_ [protected]

Definition at line 122 of file object_selection_frame.h.

Definition at line 116 of file object_selection_frame.h.

Definition at line 111 of file object_selection_frame.h.

Definition at line 112 of file object_selection_frame.h.

Definition at line 113 of file object_selection_frame.h.

Definition at line 124 of file object_selection_frame.h.


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


pr2_interactive_manipulation
Author(s): Matei Ciocarlie
autogenerated on Fri Jan 11 09:11:09 2013