Classes | Variables
pr2_moveit_controller_manager Namespace Reference

Classes

class  ActionBasedControllerHandle
class  Pr2FollowJointTrajectoryControllerHandle
class  Pr2GripperControllerHandle
class  Pr2MoveItControllerManager

Variables

static const double DEFAULT_MAX_GRIPPER_EFFORT = 10000.0
 Maximum effort the PR2 gripper is allowed to exert (read as 'very large value'); this is PR2 specific.
static const double GAP_CONVERSION_RATIO = 0.1714
 The conversion ratio that needs to be applied to get the gap opening of the gripper (m) based on the value of the motor joint actuating the gripper (PR2 specific)
static const double GRIPPER_CLOSED = 0.0
 The distance between the PR2 gripper fingers when fully closed (in m); this is PR2 specific.
static const double GRIPPER_OPEN = 0.086
 The distance between the PR2 gripper fingers when fully open (in m); this is PR2 specific.
static const std::string L_GRIPPER_JOINT = "l_gripper_motor_screw_joint"
 The name of the joint we expect input for to decide how to actuate the left gripper; this is PR2 specific.
static const std::string R_GRIPPER_JOINT = "r_gripper_motor_screw_joint"
 The name of the joint we expect input for to decide how to actuate the right gripper; this is PR2 specific.

Variable Documentation

Maximum effort the PR2 gripper is allowed to exert (read as 'very large value'); this is PR2 specific.

Definition at line 54 of file pr2_moveit_controller_manager.cpp.

The conversion ratio that needs to be applied to get the gap opening of the gripper (m) based on the value of the motor joint actuating the gripper (PR2 specific)

Definition at line 69 of file pr2_moveit_controller_manager.cpp.

const double pr2_moveit_controller_manager::GRIPPER_CLOSED = 0.0 [static]

The distance between the PR2 gripper fingers when fully closed (in m); this is PR2 specific.

Definition at line 60 of file pr2_moveit_controller_manager.cpp.

const double pr2_moveit_controller_manager::GRIPPER_OPEN = 0.086 [static]

The distance between the PR2 gripper fingers when fully open (in m); this is PR2 specific.

Definition at line 57 of file pr2_moveit_controller_manager.cpp.

const std::string pr2_moveit_controller_manager::L_GRIPPER_JOINT = "l_gripper_motor_screw_joint" [static]

The name of the joint we expect input for to decide how to actuate the left gripper; this is PR2 specific.

Definition at line 66 of file pr2_moveit_controller_manager.cpp.

const std::string pr2_moveit_controller_manager::R_GRIPPER_JOINT = "r_gripper_motor_screw_joint" [static]

The name of the joint we expect input for to decide how to actuate the right gripper; this is PR2 specific.

Definition at line 63 of file pr2_moveit_controller_manager.cpp.



pr2_moveit_plugins
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Jul 4 2019 19:51:07