Private Member Functions
object_manipulator::StandardPlacePerformer Class Reference

#include <descend_retreat_place.h>

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

List of all members.

Private Member Functions

bool constraintsUnderstandable (const arm_navigation_msgs::Constraints &constraints)
 Checks if the constraints are of the type that we can handle for the moment.
virtual void performPlace (const object_manipulation_msgs::PlaceGoal &place_goal, const geometry_msgs::PoseStamped &place_location, PlaceExecutionInfo &execution_info)
 Attempts to perform a single place location.
virtual
object_manipulation_msgs::PlaceLocationResult 
placeApproach (const object_manipulation_msgs::PlaceGoal &place_goal, const PlaceExecutionInfo &execution_info)
 Goes from the pre-place location to the place location.
object_manipulation_msgs::PlaceLocationResult retreat (const object_manipulation_msgs::PlaceGoal &place_goal)
 Moves the gripper "back"; called after placing is done.

Detailed Description

Definition at line 174 of file descend_retreat_place.h.


Member Function Documentation

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 425 of file descend_retreat_place.cpp.

void object_manipulator::StandardPlacePerformer::performPlace ( const object_manipulation_msgs::PlaceGoal place_goal,
const geometry_msgs::PoseStamped &  place_location,
PlaceExecutionInfo execution_info 
) [private, virtual]

Attempts to perform a single place location.

Implements object_manipulator::PlacePerformer.

Definition at line 338 of file descend_retreat_place.cpp.

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 a place tester.

Reimplemented in object_manipulator::ReactivePlacePerformer.

Definition at line 330 of file descend_retreat_place.cpp.

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 280 of file descend_retreat_place.cpp.


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


object_manipulator
Author(s): Matei Ciocarlie and Kaijen Hsiao
autogenerated on Mon Oct 6 2014 02:59:51