This class provides a client for the EtherCAT manager object that can translate robot input/output messages and translate them to the underlying IO Map. More...
#include <robotiq_3f_gripper_ethercat_client.h>
Public Member Functions | |
GripperInput | readInputs () const |
Reads set of input-register values from the gripper. More... | |
GripperOutput | readOutputs () const |
Reads set of output-register values from the gripper. More... | |
Robotiq3FGripperEtherCatClient (robotiq_ethercat::EtherCatManager &manager, int slave_no) | |
Constructs a control interface to a 3F Robotiq gripper on the given ethercat network and the given slave_no. More... | |
void | writeOutputs (const GripperOutput &output) |
Write the given set of control flags to the memory of the gripper. More... | |
Public Member Functions inherited from robotiq_3f_gripper_control::Robotiq3FGripperClientBase | |
virtual void | init (ros::NodeHandle nh) |
virtual | ~Robotiq3FGripperClientBase () |
Private Attributes | |
robotiq_ethercat::EtherCatManager & | manager_ |
const int | slave_no_ |
Additional Inherited Members | |
Public Types inherited from robotiq_3f_gripper_control::Robotiq3FGripperClientBase | |
typedef robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotInput | GripperInput |
typedef robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput | GripperOutput |
Protected Member Functions inherited from robotiq_3f_gripper_control::Robotiq3FGripperClientBase | |
Robotiq3FGripperClientBase () | |
This class provides a client for the EtherCAT manager object that can translate robot input/output messages and translate them to the underlying IO Map.
Definition at line 45 of file robotiq_3f_gripper_ethercat_client.h.
robotiq_3f_gripper_control::Robotiq3FGripperEtherCatClient::Robotiq3FGripperEtherCatClient | ( | robotiq_ethercat::EtherCatManager & | manager, |
int | slave_no | ||
) |
Constructs a control interface to a 3F Robotiq gripper on the given ethercat network and the given slave_no.
[in] | manager | The interface to an EtherCAT network that the gripper is connected to. |
[in] | slave_no | The slave number of the gripper on the EtherCAT network (>= 1) |
Definition at line 34 of file robotiq_3f_gripper_ethercat_client.cpp.
|
virtual |
Reads set of input-register values from the gripper.
Implements robotiq_3f_gripper_control::Robotiq3FGripperClientBase.
Definition at line 81 of file robotiq_3f_gripper_ethercat_client.cpp.
|
virtual |
Reads set of output-register values from the gripper.
Implements robotiq_3f_gripper_control::Robotiq3FGripperClientBase.
Definition at line 132 of file robotiq_3f_gripper_ethercat_client.cpp.
|
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 |
Implements robotiq_3f_gripper_control::Robotiq3FGripperClientBase.
Definition at line 43 of file robotiq_3f_gripper_ethercat_client.cpp.
|
private |
Definition at line 80 of file robotiq_3f_gripper_ethercat_client.h.
|
private |
Definition at line 81 of file robotiq_3f_gripper_ethercat_client.h.