Converts GraspHandPostureExecution goals or queries into controller commands for the PR2 or LCG grippers. More...
Public Member Functions | |
PR2GripperGraspController () | |
~PR2GripperGraspController () | |
Private Member Functions | |
void | executeCB (const object_manipulation_msgs::GraspHandPostureExecutionGoalConstPtr &goal) |
bool | getGripperValue (double &value) |
Returns the current value of the gripper joint. | |
double | jointToGap (double jointValue) |
Given a value of a gripper joint, converts that to a value of the gap between the fingers. | |
bool | serviceCallback (object_manipulation_msgs::GraspStatus::Request &request, object_manipulation_msgs::GraspStatus::Response &response) |
Private Attributes | |
actionlib::SimpleActionServer < object_manipulation_msgs::GraspHandPostureExecutionAction > * | action_server_ |
Action server for the grasp poture action. | |
actionlib::SimpleActionClient < pr2_controllers_msgs::Pr2GripperCommandAction > * | gripper_action_client_ |
Action client for moving the PR2 gripper. | |
double | gripper_closed_gap_value_ |
Gap value for gripper fully closed. | |
double | gripper_max_effort_ |
Max effort used when achieving a position (e.g. pre-grasp or release) without epxecting an object. | |
double | gripper_object_presence_threshold_ |
A value of [rl]_gripper_joint below this indicates there is nothing inside the gripper. | |
double | gripper_open_gap_value_ |
Gap value for gripper fully open. | |
std::string | gripper_type_ |
The type of gripper, for now "pr2" or "lcg". | |
std::string | gripper_virtual_joint_name_ |
The name of the virtual joint of the gripper. | |
ros::NodeHandle | priv_nh_ |
The private namespace node handle. | |
ros::ServiceServer | query_srv_ |
Server for the posture query service. | |
ros::NodeHandle | root_nh_ |
The root namespace node handle. | |
bool | sim_ |
Whether we are in simulation or on a real robot. | |
double | sim_wait_ |
How long we wait for the gripper to settle in simulation. | |
Static Private Attributes | |
static const double | DEFAULT_GRIPPER_CLOSED = 0.0 |
Default gap value for gripper fully closed. | |
static const double | DEFAULT_GRIPPER_MAX_EFFORT = 100 |
Default max effort for achieving a position. | |
static const double | DEFAULT_GRIPPER_OBJECT_PRESENCE_THRESHOLD = 0.0021 |
Default value in case this parameter is not in the launch file. | |
static const double | DEFAULT_GRIPPER_OPEN = 0.086 |
Default gap value for gripper fully open. |
Converts GraspHandPostureExecution goals or queries into controller commands for the PR2 or LCG grippers.
GraspHandPostureExecution reasons in terms of joint values, while the PR2 gripper (and for now the LCG) controllers reason in terms of gap between the fingers. This node makes the translation.
For both grippers, only looks at the first joint value in the grasp, and uses it to convert to a gap value.
Definition at line 54 of file pr2_gripper_grasp_controller.cpp.
PR2GripperGraspController::PR2GripperGraspController | ( | ) | [inline] |
Definition at line 288 of file pr2_gripper_grasp_controller.cpp.
Definition at line 330 of file pr2_gripper_grasp_controller.cpp.
void PR2GripperGraspController::executeCB | ( | const object_manipulation_msgs::GraspHandPostureExecutionGoalConstPtr & | goal | ) | [inline, private] |
Definition at line 151 of file pr2_gripper_grasp_controller.cpp.
bool PR2GripperGraspController::getGripperValue | ( | double & | value | ) | [inline, private] |
Returns the current value of the gripper joint.
Definition at line 110 of file pr2_gripper_grasp_controller.cpp.
double PR2GripperGraspController::jointToGap | ( | double | jointValue | ) | [inline, private] |
Given a value of a gripper joint, converts that to a value of the gap between the fingers.
This is different for the PR2 gripper and LCG
Definition at line 144 of file pr2_gripper_grasp_controller.cpp.
bool PR2GripperGraspController::serviceCallback | ( | object_manipulation_msgs::GraspStatus::Request & | request, |
object_manipulation_msgs::GraspStatus::Response & | response | ||
) | [inline, private] |
Definition at line 264 of file pr2_gripper_grasp_controller.cpp.
actionlib::SimpleActionServer<object_manipulation_msgs::GraspHandPostureExecutionAction>* PR2GripperGraspController::action_server_ [private] |
Action server for the grasp poture action.
Definition at line 68 of file pr2_gripper_grasp_controller.cpp.
const double PR2GripperGraspController::DEFAULT_GRIPPER_CLOSED = 0.0 [static, private] |
Default gap value for gripper fully closed.
Definition at line 92 of file pr2_gripper_grasp_controller.cpp.
const double PR2GripperGraspController::DEFAULT_GRIPPER_MAX_EFFORT = 100 [static, private] |
Default max effort for achieving a position.
Definition at line 102 of file pr2_gripper_grasp_controller.cpp.
const double PR2GripperGraspController::DEFAULT_GRIPPER_OBJECT_PRESENCE_THRESHOLD = 0.0021 [static, private] |
Default value in case this parameter is not in the launch file.
Definition at line 97 of file pr2_gripper_grasp_controller.cpp.
const double PR2GripperGraspController::DEFAULT_GRIPPER_OPEN = 0.086 [static, private] |
Default gap value for gripper fully open.
Definition at line 87 of file pr2_gripper_grasp_controller.cpp.
actionlib::SimpleActionClient<pr2_controllers_msgs::Pr2GripperCommandAction>* PR2GripperGraspController::gripper_action_client_ [private] |
Action client for moving the PR2 gripper.
Definition at line 65 of file pr2_gripper_grasp_controller.cpp.
double PR2GripperGraspController::gripper_closed_gap_value_ [private] |
Gap value for gripper fully closed.
Definition at line 90 of file pr2_gripper_grasp_controller.cpp.
double PR2GripperGraspController::gripper_max_effort_ [private] |
Max effort used when achieving a position (e.g. pre-grasp or release) without epxecting an object.
Definition at line 100 of file pr2_gripper_grasp_controller.cpp.
double PR2GripperGraspController::gripper_object_presence_threshold_ [private] |
A value of [rl]_gripper_joint below this indicates there is nothing inside the gripper.
Definition at line 95 of file pr2_gripper_grasp_controller.cpp.
double PR2GripperGraspController::gripper_open_gap_value_ [private] |
Gap value for gripper fully open.
Definition at line 85 of file pr2_gripper_grasp_controller.cpp.
std::string PR2GripperGraspController::gripper_type_ [private] |
The type of gripper, for now "pr2" or "lcg".
Definition at line 105 of file pr2_gripper_grasp_controller.cpp.
std::string PR2GripperGraspController::gripper_virtual_joint_name_ [private] |
The name of the virtual joint of the gripper.
Definition at line 74 of file pr2_gripper_grasp_controller.cpp.
The private namespace node handle.
Definition at line 62 of file pr2_gripper_grasp_controller.cpp.
Server for the posture query service.
Definition at line 71 of file pr2_gripper_grasp_controller.cpp.
The root namespace node handle.
Definition at line 59 of file pr2_gripper_grasp_controller.cpp.
bool PR2GripperGraspController::sim_ [private] |
Whether we are in simulation or on a real robot.
Definition at line 77 of file pr2_gripper_grasp_controller.cpp.
double PR2GripperGraspController::sim_wait_ [private] |
How long we wait for the gripper to settle in simulation.
Definition at line 80 of file pr2_gripper_grasp_controller.cpp.