#include <robotiq_3f_gripper_client_base.h>

Public Types | |
| typedef robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotInput | GripperInput |
| typedef robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput | GripperOutput |
Public Member Functions | |
| virtual void | init (ros::NodeHandle nh) |
| virtual GripperInput | readInputs () const =0 |
| Reads set of input-register values from the gripper. More... | |
| virtual GripperOutput | readOutputs () const =0 |
| Reads set of output-register values from the gripper. More... | |
| virtual void | writeOutputs (const GripperOutput &output)=0 |
| Write the given set of control flags to the memory of the gripper. More... | |
| virtual | ~Robotiq3FGripperClientBase () |
Protected Member Functions | |
| Robotiq3FGripperClientBase () | |
Definition at line 35 of file robotiq_3f_gripper_client_base.h.
| typedef robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotInput robotiq_3f_gripper_control::Robotiq3FGripperClientBase::GripperInput |
Definition at line 39 of file robotiq_3f_gripper_client_base.h.
| typedef robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput robotiq_3f_gripper_control::Robotiq3FGripperClientBase::GripperOutput |
Definition at line 38 of file robotiq_3f_gripper_client_base.h.
|
inlinevirtual |
Definition at line 62 of file robotiq_3f_gripper_client_base.h.
|
inlineprotected |
Definition at line 65 of file robotiq_3f_gripper_client_base.h.
|
inlinevirtual |
Reimplemented in robotiq_3f_gripper_control::Robotiq3FGripperCanClient.
Definition at line 41 of file robotiq_3f_gripper_client_base.h.
|
pure virtual |
Reads set of input-register values from the gripper.
Implemented in robotiq_3f_gripper_control::Robotiq3FGripperEtherCatClient, and robotiq_3f_gripper_control::Robotiq3FGripperCanClient.
|
pure virtual |
Reads set of output-register values from the gripper.
Implemented in robotiq_3f_gripper_control::Robotiq3FGripperEtherCatClient, and robotiq_3f_gripper_control::Robotiq3FGripperCanClient.
|
pure virtual |
Write the given set of control flags to the memory of the gripper.
| [in] | output | The set of output-register values to write to the gripper |
Implemented in robotiq_3f_gripper_control::Robotiq3FGripperEtherCatClient, and robotiq_3f_gripper_control::Robotiq3FGripperCanClient.