#include <gripper_controller.h>
Public Member Functions | |
bool | commandGripperValue (std::string arm_name, double value) |
Sends a command to the gripper action, does not wait for result. | |
double | getGripperClosedGap (std::string arm_name) const |
Gets the gap value for a closed gripper. | |
double | getGripperOpenGap (std::string arm_name) const |
Gets the gap value for an open gripper. | |
bool | getGripperValue (std::string arm_name, double &value) |
Returns the current value of the gripper joint. | |
GripperController () | |
~GripperController () | |
Private Member Functions | |
double | jointToGap (double jointValue) |
Given a value of a gripper joint, converts that to a value of the gap between the fingers. | |
std::string | virtualJointName (std::string arm_name) |
Gets the virtual gripper joint name for the given arm. | |
Private Attributes | |
object_manipulator::MultiArmActionWrapper < pr2_controllers_msgs::Pr2GripperCommandAction > | gripper_action_client_ |
The gripper command action. | |
double | l_gripper_closed_gap_value_ |
Gap value for gripper fully closed. | |
double | l_gripper_max_effort_ |
Max effort used when achieving a position (e.g. pre-grasp or release) without epxecting an object. | |
double | l_gripper_open_gap_value_ |
Gap value for gripper fully open. | |
std::string | l_gripper_type_ |
The type of gripper, for now "pr2" or "lcg". | |
ros::NodeHandle | priv_nh_ |
The private namespace node handle. | |
double | r_gripper_closed_gap_value_ |
double | r_gripper_max_effort_ |
double | r_gripper_open_gap_value_ |
std::string | r_gripper_type_ |
ros::NodeHandle | root_nh_ |
The root namespace node handle. |
Definition at line 47 of file gripper_controller.h.
Definition at line 38 of file gripper_controller.cpp.
Definition at line 54 of file gripper_controller.cpp.
bool pr2_wrappers::GripperController::commandGripperValue | ( | std::string | arm_name, |
double | value | ||
) |
Sends a command to the gripper action, does not wait for result.
Definition at line 96 of file gripper_controller.cpp.
double pr2_wrappers::GripperController::getGripperClosedGap | ( | std::string | arm_name | ) | const [inline] |
Gets the gap value for a closed gripper.
Definition at line 105 of file gripper_controller.h.
double pr2_wrappers::GripperController::getGripperOpenGap | ( | std::string | arm_name | ) | const [inline] |
Gets the gap value for an open gripper.
Definition at line 98 of file gripper_controller.h.
bool pr2_wrappers::GripperController::getGripperValue | ( | std::string | arm_name, |
double & | value | ||
) |
Returns the current value of the gripper joint.
Definition at line 64 of file gripper_controller.cpp.
double pr2_wrappers::GripperController::jointToGap | ( | double | jointValue | ) | [private] |
Given a value of a gripper joint, converts that to a value of the gap between the fingers.
std::string pr2_wrappers::GripperController::virtualJointName | ( | std::string | arm_name | ) | [private] |
Gets the virtual gripper joint name for the given arm.
Definition at line 58 of file gripper_controller.cpp.
object_manipulator::MultiArmActionWrapper<pr2_controllers_msgs::Pr2GripperCommandAction> pr2_wrappers::GripperController::gripper_action_client_ [private] |
The gripper command action.
Definition at line 58 of file gripper_controller.h.
double pr2_wrappers::GripperController::l_gripper_closed_gap_value_ [private] |
Gap value for gripper fully closed.
Definition at line 71 of file gripper_controller.h.
double pr2_wrappers::GripperController::l_gripper_max_effort_ [private] |
Max effort used when achieving a position (e.g. pre-grasp or release) without epxecting an object.
Definition at line 75 of file gripper_controller.h.
double pr2_wrappers::GripperController::l_gripper_open_gap_value_ [private] |
Gap value for gripper fully open.
Definition at line 67 of file gripper_controller.h.
std::string pr2_wrappers::GripperController::l_gripper_type_ [private] |
The type of gripper, for now "pr2" or "lcg".
Definition at line 79 of file gripper_controller.h.
The private namespace node handle.
Definition at line 55 of file gripper_controller.h.
double pr2_wrappers::GripperController::r_gripper_closed_gap_value_ [private] |
Definition at line 72 of file gripper_controller.h.
double pr2_wrappers::GripperController::r_gripper_max_effort_ [private] |
Definition at line 76 of file gripper_controller.h.
double pr2_wrappers::GripperController::r_gripper_open_gap_value_ [private] |
Definition at line 68 of file gripper_controller.h.
std::string pr2_wrappers::GripperController::r_gripper_type_ [private] |
Definition at line 80 of file gripper_controller.h.
The root namespace node handle.
Definition at line 52 of file gripper_controller.h.