$search

object_manipulator::PlaceExecutor Class Reference

Functionality for placing a grasped object at a given location. More...

#include <place_executor.h>

Inheritance diagram for object_manipulator::PlaceExecutor:
Inheritance graph
[legend]

List of all members.

Public Member Functions

object_manipulation_msgs::PlaceLocationResult place (const object_manipulation_msgs::PlaceGoal &place_goal, const geometry_msgs::PoseStamped &place_location)
 Places a grasped object at a specified location.
 PlaceExecutor (GraspMarkerPublisher *marker_publisher)
object_manipulation_msgs::PlaceLocationResult Result (int result_code, bool continuation)

Protected Member Functions

geometry_msgs::PoseStamped computeGripperPose (geometry_msgs::PoseStamped place_location, geometry_msgs::Pose grasp_pose, std::string frame_id)
 Computes the gripper pose for a desired object place location.
bool constraintsUnderstandable (const motion_planning_msgs::Constraints &constraints)
 Checks if the constraints are of the type that we can handle for the moment.
virtual
object_manipulation_msgs::PlaceLocationResult 
placeApproach (const object_manipulation_msgs::PlaceGoal &place_goal, const geometry_msgs::PoseStamped &place_location)
 Goes from the pre-place location to the place location.
object_manipulation_msgs::PlaceLocationResult prepareInterpolatedTrajectories (const object_manipulation_msgs::PlaceGoal &place_goal, const geometry_msgs::PoseStamped &place_location)
 Computes interpolated trajectories for both place and retreat.
object_manipulation_msgs::PlaceLocationResult retreat (const object_manipulation_msgs::PlaceGoal &place_goal)
 Moves the gripper "back"; called after placing is done.

Protected Attributes

tf::TransformListener listener_
 Transform listener.
int marker_id_
 Id of published marker, if any.
GraspMarkerPublishermarker_publisher_
 Publisher for markers, or NULL if markers are not to be published.
trajectory_msgs::JointTrajectory place_trajectory_
 The interpolated trajectory used to place object.
trajectory_msgs::JointTrajectory retreat_trajectory_
 The interpolated trajectory used to retreat after place.

Detailed Description

Functionality for placing a grasped object at a given location.

As a mirror image of the classes that offer grasping functionality, placing implies:

This class will first compute that both place and retreat interpolated trajectories are possible, then proceed to execute the place trajectory.

Definition at line 60 of file place_executor.h.


Constructor & Destructor Documentation

object_manipulator::PlaceExecutor::PlaceExecutor ( GraspMarkerPublisher marker_publisher  )  [inline]

Definition at line 109 of file place_executor.h.


Member Function Documentation

geometry_msgs::PoseStamped object_manipulator::PlaceExecutor::computeGripperPose ( geometry_msgs::PoseStamped  place_location,
geometry_msgs::Pose  grasp_pose,
std::string  frame_id 
) [protected]

Computes the gripper pose for a desired object place location.

Definition at line 47 of file place_executor.cpp.

bool object_manipulator::PlaceExecutor::constraintsUnderstandable ( const motion_planning_msgs::Constraints &  constraints  )  [protected]

Checks if the constraints are of the type that we can handle for the moment.

Right now we can only deal with a single orientation constraint. This function checks if the constraints have additional stuff inside that we can not deal with.

Definition at line 420 of file place_executor.cpp.

PlaceLocationResult object_manipulator::PlaceExecutor::place ( const object_manipulation_msgs::PlaceGoal &  place_goal,
const geometry_msgs::PoseStamped place_location 
)

Places a grasped object at a specified location.

  • compute gripper pose for placing at the desired location
    • computes if both place and retreat trajectories are possible
    • calls move arm to get to pre-place pose
    • executes place interpolated trajectory

place_padding is how much the placed object should be padded by when deciding if the place location is feasible or not. It does not affect the padding for moving to the place location.

Definition at line 323 of file place_executor.cpp.

PlaceLocationResult object_manipulator::PlaceExecutor::placeApproach ( const object_manipulation_msgs::PlaceGoal &  place_goal,
const geometry_msgs::PoseStamped place_location 
) [protected, virtual]

Goes from the pre-place location to the place location.

In the default implementation, this simply executes the interpolated trajectory from pre-place to place that has already been computed by prepareInterpolatedTrajectories(...). Therefore, this must always be called after prepareInterpolatedTrajectories(...) has already been called. In general this should not be called directly, but rather as a step in the complete place(...) function.

Reimplemented in object_manipulator::ReactivePlaceExecutor.

Definition at line 306 of file place_executor.cpp.

PlaceLocationResult object_manipulator::PlaceExecutor::prepareInterpolatedTrajectories ( const object_manipulation_msgs::PlaceGoal &  place_goal,
const geometry_msgs::PoseStamped place_location 
) [protected]

Computes interpolated trajectories for both place and retreat.

Definition at line 148 of file place_executor.cpp.

object_manipulation_msgs::PlaceLocationResult object_manipulator::PlaceExecutor::Result ( int  result_code,
bool  continuation 
) [inline]

Definition at line 63 of file place_executor.h.

PlaceLocationResult object_manipulator::PlaceExecutor::retreat ( const object_manipulation_msgs::PlaceGoal &  place_goal  )  [protected]

Moves the gripper "back"; called after placing is done.

This function will re-compute the trajectory to retreat. Note that, before we even begun placing, we did compute a retreat trajectory, so we could maybe use that one. However, we are assuming that maybe the placing trajectory did not leave us precisely in the desired spot, so maybe that retreat trajectory is no longer valid.

Here we attempt to re-compute a retreat trajectory, by disabling contact between the gripper and the target object. We also disable collision between the gripper and the table, as we assume a retreat trajectory can never bring the gripper in collision with the table (or if it does, the wrist will hit too and we'll catch it). We then execute this trajectory however many points it has.

The fact that a retreat trajectory was found before even placing should make it very likely (but not 100% sure) that we will find one now as well.

Definition at line 107 of file place_executor.cpp.


Member Data Documentation

Transform listener.

Definition at line 84 of file place_executor.h.

Id of published marker, if any.

Definition at line 75 of file place_executor.h.

Publisher for markers, or NULL if markers are not to be published.

Definition at line 72 of file place_executor.h.

The interpolated trajectory used to place object.

Definition at line 78 of file place_executor.h.

The interpolated trajectory used to retreat after place.

Definition at line 81 of file place_executor.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