#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. | |
| bool | getGripperValue (std::string arm_name, double &value) |
| Returns the current value of the gripper joint. | |
| GripperController () | |
| ~GripperController () | |
Static Public Attributes | |
| static const double | GRIPPER_CLOSED = 0.0 |
| Consts for gripper fully open or fully closed for gripper controller. | |
| static const double | GRIPPER_OPEN = 0.086 |
| Consts for gripper fully open or fully closed for gripper controller. | |
Private Member Functions | |
| 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. | |
| ros::NodeHandle | priv_nh_ |
| The private namespace node handle. | |
| ros::NodeHandle | root_nh_ |
| The root namespace node handle. | |
Definition at line 44 of file gripper_controller.h.
| pr2_interactive_manipulation::GripperController::GripperController | ( | ) |
Definition at line 44 of file gripper_controller.cpp.
| pr2_interactive_manipulation::GripperController::~GripperController | ( | ) |
Definition at line 51 of file gripper_controller.cpp.
| bool pr2_interactive_manipulation::GripperController::commandGripperValue | ( | std::string | arm_name, | |
| double | value | |||
| ) |
Sends a command to the gripper action, does not wait for result.
Definition at line 93 of file gripper_controller.cpp.
| bool pr2_interactive_manipulation::GripperController::getGripperValue | ( | std::string | arm_name, | |
| double & | value | |||
| ) |
Returns the current value of the gripper joint.
Definition at line 61 of file gripper_controller.cpp.
| std::string pr2_interactive_manipulation::GripperController::virtualJointName | ( | std::string | arm_name | ) | [private] |
Gets the virtual gripper joint name for the given arm.
Definition at line 55 of file gripper_controller.cpp.
object_manipulator::MultiArmActionWrapper<pr2_controllers_msgs::Pr2GripperCommandAction> pr2_interactive_manipulation::GripperController::gripper_action_client_ [private] |
The gripper command action.
Definition at line 52 of file gripper_controller.h.
const double pr2_interactive_manipulation::GripperController::GRIPPER_CLOSED = 0.0 [static] |
Consts for gripper fully open or fully closed for gripper controller.
Definition at line 74 of file gripper_controller.h.
const double pr2_interactive_manipulation::GripperController::GRIPPER_OPEN = 0.086 [static] |
Consts for gripper fully open or fully closed for gripper controller.
Definition at line 72 of file gripper_controller.h.
ros::NodeHandle pr2_interactive_manipulation::GripperController::priv_nh_ [private] |
The private namespace node handle.
Definition at line 49 of file gripper_controller.h.
ros::NodeHandle pr2_interactive_manipulation::GripperController::root_nh_ [private] |
The root namespace node handle.
Definition at line 46 of file gripper_controller.h.