$search

object_manipulator::ObjectManipulator Class Reference

Oversees the grasping app; bundles together functionality in higher level calls. More...

#include <object_manipulator.h>

List of all members.

Public Member Functions

 ObjectManipulator ()
 Initializes ros clients as needed.
void pickup (const object_manipulation_msgs::PickupGoal::ConstPtr &pickup_goal, actionlib::SimpleActionServer< object_manipulation_msgs::PickupAction > *action_server)
 Attempts to grasp the specified object.
void place (const object_manipulation_msgs::PlaceGoal::ConstPtr &place_goal, actionlib::SimpleActionServer< object_manipulation_msgs::PlaceAction > *action_server)
 Attempts to place the specified object.
 ~ObjectManipulator ()

Private Attributes

std::string default_cluster_planner_
 The name of the service to be used by default for grasp planning on point cloud objects.
std::string default_database_planner_
 The name of the service to be used by default for grasp planning on database objects.
std::string default_probabilistic_planner_
 The name of the service to be used by default for grasp planning on probabilistic recognition results.
GraspExecutorWithApproachgrasp_executor_with_approach_
 Instance of the grasp executor with approach.
MultiArmServiceWrapper
< object_manipulation_msgs::GraspPlanning > 
grasp_planning_services_
 Wrapper for multiple grasp planning services with different names.
GraspMarkerPublishermarker_pub_
 Publisher for grasp markers, or NULL if publishing is disabled.
PlaceExecutorplace_executor_
 Instance of the executor used for placing objects.
ros::NodeHandle priv_nh_
 The private ROS node handle.
bool randomize_grasps_
 Whether the order in which grasps are tried should be randomized first. Debug purposes.
ReactiveGraspExecutorreactive_grasp_executor_
 Instance of the reactive grasp executor.
ReactivePlaceExecutorreactive_place_executor_
 Instance of the executor used for reactive placing of objects.
ros::NodeHandle root_nh_
 The root ROS node handle.

Detailed Description

Oversees the grasping app; bundles together functionality in higher level calls.

Also wraps the functionality in action replies, with the actual server passed in from the caller so we keep ROS instantiations somewhat separated.

Definition at line 58 of file object_manipulator.h.


Constructor & Destructor Documentation

object_manipulator::ObjectManipulator::ObjectManipulator (  ) 

Initializes ros clients as needed.

Definition at line 61 of file object_manipulator.cpp.

object_manipulator::ObjectManipulator::~ObjectManipulator (  ) 

Definition at line 88 of file object_manipulator.cpp.


Member Function Documentation

void object_manipulator::ObjectManipulator::pickup ( const object_manipulation_msgs::PickupGoal::ConstPtr &  pickup_goal,
actionlib::SimpleActionServer< object_manipulation_msgs::PickupAction > *  action_server 
)

Attempts to grasp the specified object.

void object_manipulator::ObjectManipulator::place ( const object_manipulation_msgs::PlaceGoal::ConstPtr &  place_goal,
actionlib::SimpleActionServer< object_manipulation_msgs::PlaceAction > *  action_server 
)

Attempts to place the specified object.

Definition at line 247 of file object_manipulator.cpp.


Member Data Documentation

The name of the service to be used by default for grasp planning on point cloud objects.

Definition at line 94 of file object_manipulator.h.

The name of the service to be used by default for grasp planning on database objects.

Definition at line 91 of file object_manipulator.h.

The name of the service to be used by default for grasp planning on probabilistic recognition results.

Definition at line 97 of file object_manipulator.h.

Instance of the grasp executor with approach.

Definition at line 79 of file object_manipulator.h.

Wrapper for multiple grasp planning services with different names.

Not really a wrapper for multiple arms, but a wrapper for multiple services with different names but fulfilling the same task.

Definition at line 70 of file object_manipulator.h.

Publisher for grasp markers, or NULL if publishing is disabled.

Definition at line 73 of file object_manipulator.h.

Instance of the executor used for placing objects.

Definition at line 85 of file object_manipulator.h.

The private ROS node handle.

Definition at line 62 of file object_manipulator.h.

Whether the order in which grasps are tried should be randomized first. Debug purposes.

Definition at line 76 of file object_manipulator.h.

Instance of the reactive grasp executor.

Definition at line 82 of file object_manipulator.h.

Instance of the executor used for reactive placing of objects.

Definition at line 88 of file object_manipulator.h.

The root ROS node handle.

Definition at line 65 of file object_manipulator.h.


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


katana_object_manipulator
Author(s): Henning Deeken
autogenerated on Thu Jan 3 13:17:59 2013