Uses an interpolated IK approach from pregrasp to final grasp. More...
#include <grasp_executor_with_approach.h>
Public Member Functions | |
GraspExecutorWithApproach (GraspMarkerPublisher *pub) | |
Also adds a grasp marker at the pre-grasp location. | |
virtual object_manipulation_msgs::GraspResult | retreat (const object_manipulation_msgs::PickupGoal &pickup_goal) |
Retreats along the gripper approach direction. | |
Protected Member Functions | |
virtual motion_planning_msgs::OrderedCollisionOperations | collisionOperationsForGrasp (const object_manipulation_msgs::PickupGoal &pickup_goal) |
Collision operations to be used when planning the grasp motion. | |
virtual object_manipulation_msgs::GraspResult | executeGrasp (const object_manipulation_msgs::PickupGoal &pickup_goal, const object_manipulation_msgs::Grasp &grasp) |
Uses move_arm to get to pre-grasp, then executes the interpolated IK grasp path and lift path. | |
object_manipulation_msgs::GraspResult | getInterpolatedIKForGrasp (const object_manipulation_msgs::PickupGoal &pickup_goal, const object_manipulation_msgs::Grasp &grasp, trajectory_msgs::JointTrajectory &grasp_trajectory) |
Computes an interpolated IK trajectory between pre_grasp and grasp and checks if it has enough points. | |
virtual std::vector < motion_planning_msgs::LinkPadding > | linkPaddingForGrasp (const object_manipulation_msgs::PickupGoal &pickup_goal) |
Dynamic link padding to be used for grasp operation. | |
virtual object_manipulation_msgs::GraspResult | prepareGrasp (const object_manipulation_msgs::PickupGoal &pickup_goal, const object_manipulation_msgs::Grasp &grasp) |
Computes IK for the pre-grasp and interpolated IK from pre-grasp to grasp and from grasp to lift. | |
Protected Attributes | |
trajectory_msgs::JointTrajectory | interpolated_grasp_trajectory_ |
The result of interpolated IK from pre-grasp to grasp. |
Uses an interpolated IK approach from pregrasp to final grasp.
Initial check consists of IK for the pre-grasp, followed by generation of an interpolated IK path from pre-grasp to grasp. This is then followed by computation of an interpolated IK path from grasp to lift.
Execution consists of using move arm to go to the pre-grasp, then execution of the interpolated IK paths for grasp. Lift is executed separately, called from the higher level executor.
Note that we do not use the pre-grasp from the database directly; rather, the pre-grasp is obtained by backing up the grasp by a pre-defined amount. This allows us more flexibility in choosing the pre-grasp. However, we can no longer always assume the pre-grasp is collision free, which we could if we used the pre-grasp from the database directly.
In the most recent database version, the pre-grasp was obtained by backing up 10 cm, so we know at least that that is not colliding with the object.
Definition at line 60 of file grasp_executor_with_approach.h.
object_manipulator::GraspExecutorWithApproach::GraspExecutorWithApproach | ( | GraspMarkerPublisher * | pub | ) | [inline] |
Also adds a grasp marker at the pre-grasp location.
Definition at line 71 of file grasp_executor_with_approach.h.
motion_planning_msgs::OrderedCollisionOperations object_manipulator::GraspExecutorWithApproach::collisionOperationsForGrasp | ( | const object_manipulation_msgs::PickupGoal & | pickup_goal | ) | [protected, virtual] |
Collision operations to be used when planning the grasp motion.
Disable collisions between end-effector and target
Definition at line 50 of file grasp_executor_with_approach.cpp.
GraspResult object_manipulator::GraspExecutorWithApproach::executeGrasp | ( | const object_manipulation_msgs::PickupGoal & | pickup_goal, | |
const object_manipulation_msgs::Grasp & | grasp | |||
) | [protected, virtual] |
Uses move_arm to get to pre-grasp, then executes the interpolated IK grasp path and lift path.
Implements object_manipulator::GraspExecutor.
Reimplemented in object_manipulator::ReactiveGraspExecutor.
Definition at line 182 of file grasp_executor_with_approach.cpp.
GraspResult object_manipulator::GraspExecutorWithApproach::getInterpolatedIKForGrasp | ( | const object_manipulation_msgs::PickupGoal & | pickup_goal, | |
const object_manipulation_msgs::Grasp & | grasp, | |||
trajectory_msgs::JointTrajectory & | grasp_trajectory | |||
) | [protected] |
Computes an interpolated IK trajectory between pre_grasp and grasp and checks if it has enough points.
Definition at line 87 of file grasp_executor_with_approach.cpp.
std::vector< motion_planning_msgs::LinkPadding > object_manipulator::GraspExecutorWithApproach::linkPaddingForGrasp | ( | const object_manipulation_msgs::PickupGoal & | pickup_goal | ) | [protected, virtual] |
Dynamic link padding to be used for grasp operation.
Zero padding on fingertip links
Definition at line 80 of file grasp_executor_with_approach.cpp.
GraspResult object_manipulator::GraspExecutorWithApproach::prepareGrasp | ( | const object_manipulation_msgs::PickupGoal & | pickup_goal, | |
const object_manipulation_msgs::Grasp & | grasp | |||
) | [protected, virtual] |
Computes IK for the pre-grasp and interpolated IK from pre-grasp to grasp and from grasp to lift.
Implements object_manipulator::GraspExecutor.
Definition at line 154 of file grasp_executor_with_approach.cpp.
GraspResult object_manipulator::GraspExecutorWithApproach::retreat | ( | const object_manipulation_msgs::PickupGoal & | pickup_goal | ) | [virtual] |
Retreats along the gripper approach direction.
Retreats by the actual length of the pre-grasp to grasp trajectory (if any), or by the desired length of that path, if no path exists. Disables collision between gripper and object as well as table.
Reimplemented from object_manipulator::GraspExecutor.
Definition at line 218 of file grasp_executor_with_approach.cpp.
trajectory_msgs::JointTrajectory object_manipulator::GraspExecutorWithApproach::interpolated_grasp_trajectory_ [protected] |
The result of interpolated IK from pre-grasp to grasp.
Definition at line 43 of file grasp_executor_with_approach.h.