Public Member Functions | |
void | callback (const robotiq_s_model_control::SModel_robot_input::ConstPtr &msg) |
Callback function for "SModelRobotInput" topic. | |
std::vector< std::string > | jointNames () |
Joint names. | |
Robotiq3 () | |
Robotiq3 (std::string gripper_prefix) | |
double | scissorJoint () const |
Joint value for so-called scissor joint. | |
Public Attributes | |
Finger | finger_left |
Robotiq FINGER A. | |
Finger | finger_middle |
Robotiq FINGER C. | |
Finger | finger_right |
Robotiq FINGER B. | |
std::vector< double > | joint_positions |
Joint values. | |
std::string | prefix |
Gripper prefix. | |
int | scissor |
Scissor position. |
Robotiq S-model with three Fingers.
Definition at line 93 of file s_model_joint_states.cpp.
Robotiq3::Robotiq3 | ( | ) | [inline] |
Default constructor for Robotiq3
Definition at line 96 of file s_model_joint_states.cpp.
Robotiq3::Robotiq3 | ( | std::string | gripper_prefix | ) | [inline] |
Constructor for Robotiq3
Definition at line 103 of file s_model_joint_states.cpp.
void Robotiq3::callback | ( | const robotiq_s_model_control::SModel_robot_input::ConstPtr & | msg | ) |
Callback function for "SModelRobotInput" topic.
Definition at line 135 of file s_model_joint_states.cpp.
std::vector< std::string > Robotiq3::jointNames | ( | ) | [inline] |
Joint names.
Assigns appropriate joint names.
Definition at line 158 of file s_model_joint_states.cpp.
double Robotiq3::scissorJoint | ( | ) | const [inline] |
Joint value for so-called scissor joint.
Calculates joint value of the scissor joint based on the scissor position.
Definition at line 123 of file s_model_joint_states.cpp.
Robotiq FINGER A.
Definition at line 111 of file s_model_joint_states.cpp.
Robotiq FINGER C.
Definition at line 113 of file s_model_joint_states.cpp.
Robotiq FINGER B.
Definition at line 112 of file s_model_joint_states.cpp.
std::vector<double> Robotiq3::joint_positions |
Joint values.
Definition at line 117 of file s_model_joint_states.cpp.
std::string Robotiq3::prefix |
Gripper prefix.
Definition at line 115 of file s_model_joint_states.cpp.
Scissor position.
Definition at line 114 of file s_model_joint_states.cpp.