Public Member Functions | Private Attributes
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

void graspFeedback (actionlib::SimpleActionServer< object_manipulation_msgs::PickupAction > *action_server, size_t tested_grasps, size_t current_grasp)
 Provides feedback on the currently tested list of grasps.
void graspPlanningDoneCallback (const actionlib::SimpleClientGoalState &state, const object_manipulation_msgs::GraspPlanningResultConstPtr &result)
 Saves the grasps provided as result by planning action.
void graspPlanningFeedbackCallback (const object_manipulation_msgs::GraspPlanningFeedbackConstPtr &feedback)
 Saves the grasps provided as feedback by planning action.
 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.
void placeFeedback (actionlib::SimpleActionServer< object_manipulation_msgs::PlaceAction > *action_server, size_t tested_places, size_t total_places, size_t current_place)
 Provides feedback on the currently tested list of places.
 ~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 probabilistic grasp planning.
GraspContainer grasp_container_
 A thread safe place to hold grasps returned by the planning action as feedback.
GraspExecutorWithApproachgrasp_executor_with_approach_
 Instance of the grasp executor with approach.
MultiArmActionWrapper
< object_manipulation_msgs::GraspPlanningAction
grasp_planning_actions_
 Wrapper for multiple grasp planning services with different names.
GraspTesterFastgrasp_tester_fast_
GraspTestergrasp_tester_with_approach_
std::string kinematics_plugin_name_
 Name of the kinematics plugin used for fast grasp/place testing.
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.
GraspPerformerreactive_grasp_performer_
ReactivePlaceExecutorreactive_place_executor_
 Instance of the executor used for reactive placing of objects.
PlacePerformerreactive_place_performer_
ros::NodeHandle root_nh_
 The root ROS node handle.
GraspPerformerstandard_grasp_performer_
PlacePerformerstandard_place_performer_
PlaceTesterstandard_place_tester_
UnsafeGraspExecutorunsafe_grasp_executor_
 Instance of the executor used for grasping without considering collisions.
GraspPerformerunsafe_grasp_performer_
GraspTesterunsafe_grasp_tester_
bool use_probabilistic_planner_

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 127 of file object_manipulator.h.


Constructor & Destructor Documentation

Initializes ros clients as needed.

Definition at line 80 of file object_manipulator.cpp.

Definition at line 139 of file object_manipulator.cpp.


Member Function Documentation

void object_manipulator::ObjectManipulator::graspFeedback ( actionlib::SimpleActionServer< object_manipulation_msgs::PickupAction > *  action_server,
size_t  tested_grasps,
size_t  current_grasp 
)

Provides feedback on the currently tested list of grasps.

Definition at line 163 of file object_manipulator.cpp.

Saves the grasps provided as result by planning action.

Definition at line 180 of file object_manipulator.cpp.

Saves the grasps provided as feedback by planning action.

Definition at line 173 of file object_manipulator.cpp.

Attempts to grasp the specified object.

Definition at line 194 of file object_manipulator.cpp.

Attempts to place the specified object.

Definition at line 436 of file object_manipulator.cpp.

void object_manipulator::ObjectManipulator::placeFeedback ( actionlib::SimpleActionServer< object_manipulation_msgs::PlaceAction > *  action_server,
size_t  tested_places,
size_t  total_places,
size_t  current_place 
)

Provides feedback on the currently tested list of places.

Definition at line 426 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 179 of file object_manipulator.h.

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

Definition at line 176 of file object_manipulator.h.

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

Definition at line 182 of file object_manipulator.h.

A thread safe place to hold grasps returned by the planning action as feedback.

Definition at line 186 of file object_manipulator.h.

Instance of the grasp executor with approach.

Definition at line 161 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 139 of file object_manipulator.h.

Definition at line 152 of file object_manipulator.h.

Definition at line 150 of file object_manipulator.h.

Name of the kinematics plugin used for fast grasp/place testing.

Definition at line 148 of file object_manipulator.h.

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

Definition at line 142 of file object_manipulator.h.

Instance of the executor used for placing objects.

Definition at line 170 of file object_manipulator.h.

The private ROS node handle.

Definition at line 131 of file object_manipulator.h.

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

Definition at line 145 of file object_manipulator.h.

Instance of the reactive grasp executor.

Definition at line 164 of file object_manipulator.h.

Definition at line 154 of file object_manipulator.h.

Instance of the executor used for reactive placing of objects.

Definition at line 173 of file object_manipulator.h.

Definition at line 158 of file object_manipulator.h.

The root ROS node handle.

Definition at line 134 of file object_manipulator.h.

Definition at line 153 of file object_manipulator.h.

Definition at line 157 of file object_manipulator.h.

Definition at line 156 of file object_manipulator.h.

Instance of the executor used for grasping without considering collisions.

Definition at line 167 of file object_manipulator.h.

Definition at line 155 of file object_manipulator.h.

Definition at line 151 of file object_manipulator.h.

Definition at line 183 of file object_manipulator.h.


The documentation for this class was generated from the following files:


object_manipulator
Author(s): Matei Ciocarlie and Kaijen Hsiao
autogenerated on Thu Jan 2 2014 11:39:04