Simplest grasp executor, using only final grasp information. More...
#include <simple_grasp_executor.h>
Public Member Functions | |
SimpleGraspExecutor (GraspMarkerPublisher *pub) | |
Also adds a marker at the final grasp. | |
Private Member Functions | |
virtual object_manipulation_msgs::GraspResult | executeGrasp (const object_manipulation_msgs::PickupGoal &pickup_goal, const object_manipulation_msgs::Grasp &grasp) |
Sends the IK result of prepareGrasp() to move_arm, then executes lift trajectory. | |
virtual object_manipulation_msgs::GraspResult | prepareGrasp (const object_manipulation_msgs::PickupGoal &pickup_goal, const object_manipulation_msgs::Grasp &grasp) |
Calls IK on the final grasp pose. | |
Private Attributes | |
kinematics_msgs::GetConstraintAwarePositionIK::Response | ik_response_ |
The inverse kinematics solution for the final grasp. |
Simplest grasp executor, using only final grasp information.
The initial check consists of calling IK on the final grasp to see if a valid IK solution exists, then cheking interpolated IK to see if the object can be lifted. Execution then consists of passing along the IK solution to move_arm, followed by the lift trajectory.
Definition at line 49 of file simple_grasp_executor.h.
object_manipulator::SimpleGraspExecutor::SimpleGraspExecutor | ( | GraspMarkerPublisher * | pub | ) | [inline] |
Also adds a marker at the final grasp.
Definition at line 66 of file simple_grasp_executor.h.
GraspResult object_manipulator::SimpleGraspExecutor::executeGrasp | ( | const object_manipulation_msgs::PickupGoal & | pickup_goal, | |
const object_manipulation_msgs::Grasp & | grasp | |||
) | [private, virtual] |
Sends the IK result of prepareGrasp() to move_arm, then executes lift trajectory.
Implements object_manipulator::GraspExecutor.
Definition at line 76 of file simple_grasp_executor.cpp.
GraspResult object_manipulator::SimpleGraspExecutor::prepareGrasp | ( | const object_manipulation_msgs::PickupGoal & | pickup_goal, | |
const object_manipulation_msgs::Grasp & | grasp | |||
) | [private, virtual] |
Calls IK on the final grasp pose.
Implements object_manipulator::GraspExecutor.
Definition at line 44 of file simple_grasp_executor.cpp.
kinematics_msgs::GetConstraintAwarePositionIK::Response object_manipulator::SimpleGraspExecutor::ik_response_ [private] |
The inverse kinematics solution for the final grasp.
Definition at line 53 of file simple_grasp_executor.h.