#include <interactive_marker_node.h>
| Public Member Functions | |
| std::vector < object_manipulation_msgs::GraspableObject > | getMovableObstacles () | 
| InteractiveMarkerNode () | |
| ~InteractiveMarkerNode () | |
| Private Member Functions | |
| void | processConfig (PickupConfig &config, uint32_t level) | 
| void | processGraspableObjects (const pr2_interactive_object_detection::GraspableObjectListConstPtr &objects) | 
| Private Attributes | |
| tabletop_collision_map_processing::CollisionMapInterface | collision_map_interface_ | 
| dynamic_reconfigure::Server < PickupConfig > | dyn_conf_srv_ | 
| ros::Subscriber | graspable_objects_sub_ | 
| actionlib::SimpleActionClient < pr2_object_manipulation_msgs::IMGUIAction > | im_gui_action_client_ | 
| interactive_markers::InteractiveMarkerServer | marker_server_ | 
| std::vector< boost::shared_ptr < GraspableObjectHandler > > | object_handlers_ | 
| pr2_object_manipulation_msgs::IMGUIOptions | options_ | 
| ros::NodeHandle | priv_nh_ | 
| ros::NodeHandle | root_nh_ | 
Definition at line 55 of file interactive_marker_node.h.
Definition at line 43 of file interactive_marker_node.cpp.
Definition at line 67 of file interactive_marker_node.cpp.
| std::vector< object_manipulation_msgs::GraspableObject > pr2_interactive_manipulation::InteractiveMarkerNode::getMovableObstacles | ( | ) | 
Definition at line 100 of file interactive_marker_node.cpp.
| void pr2_interactive_manipulation::InteractiveMarkerNode::processConfig | ( | PickupConfig & | config, | 
| uint32_t | level | ||
| ) |  [private] | 
Definition at line 71 of file interactive_marker_node.cpp.
| void pr2_interactive_manipulation::InteractiveMarkerNode::processGraspableObjects | ( | const pr2_interactive_object_detection::GraspableObjectListConstPtr & | objects | ) |  [private] | 
Definition at line 79 of file interactive_marker_node.cpp.
| tabletop_collision_map_processing::CollisionMapInterface pr2_interactive_manipulation::InteractiveMarkerNode::collision_map_interface_  [private] | 
Definition at line 85 of file interactive_marker_node.h.
| dynamic_reconfigure::Server<PickupConfig> pr2_interactive_manipulation::InteractiveMarkerNode::dyn_conf_srv_  [private] | 
Definition at line 83 of file interactive_marker_node.h.
| ros::Subscriber pr2_interactive_manipulation::InteractiveMarkerNode::graspable_objects_sub_  [private] | 
Definition at line 73 of file interactive_marker_node.h.
| actionlib::SimpleActionClient<pr2_object_manipulation_msgs::IMGUIAction> pr2_interactive_manipulation::InteractiveMarkerNode::im_gui_action_client_  [private] | 
Definition at line 75 of file interactive_marker_node.h.
| interactive_markers::InteractiveMarkerServer pr2_interactive_manipulation::InteractiveMarkerNode::marker_server_  [private] | 
Definition at line 77 of file interactive_marker_node.h.
| std::vector< boost::shared_ptr<GraspableObjectHandler> > pr2_interactive_manipulation::InteractiveMarkerNode::object_handlers_  [private] | 
Definition at line 79 of file interactive_marker_node.h.
| pr2_object_manipulation_msgs::IMGUIOptions pr2_interactive_manipulation::InteractiveMarkerNode::options_  [private] | 
Definition at line 81 of file interactive_marker_node.h.
Definition at line 71 of file interactive_marker_node.h.
Definition at line 70 of file interactive_marker_node.h.