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_can_client.h>
Public Member Functions | |
void | init (ros::NodeHandle nh) |
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... | |
Robotiq3FGripperCanClient (unsigned int can_id, boost::shared_ptr< can::DriverInterface > driver) | |
void | writeOutputs (const GripperOutput &output) |
Write the given set of control flags to the memory of the gripper. More... | |
virtual | ~Robotiq3FGripperCanClient () |
Public Member Functions inherited from robotiq_3f_gripper_control::Robotiq3FGripperClientBase | |
virtual | ~Robotiq3FGripperClientBase () |
Private Member Functions | |
void | decodeFaultStatus (const u_int8_t &f) |
void | decodeFingerACurrent (const u_int8_t &f) |
void | decodeFingerAPos (const u_int8_t &f) |
void | decodeFingerAPosCmd (const u_int8_t &f) |
void | decodeFingerBCurrent (const u_int8_t &f) |
void | decodeFingerBPos (const u_int8_t &f) |
void | decodeFingerBPosCmd (const u_int8_t &f) |
void | decodeFingerCCurrent (const u_int8_t &f) |
void | decodeFingerCPos (const u_int8_t &f) |
void | decodeFingerCPosCmd (const u_int8_t &f) |
void | decodeFingerSCurrent (const u_int8_t &f) |
void | decodeFingerSPos (const u_int8_t &f) |
void | decodeFingerSPosCmd (const u_int8_t &f) |
void | decodeGripperStatus (const u_int8_t &f) |
void | decodeObjectStatus (const u_int8_t &f) |
void | frameCallback (const can::Frame &f) |
void | requestStart () |
void | stateCallback (const can::State &s) |
Private Attributes | |
std::string | can_device_ |
unsigned int | can_id_ |
boost::shared_ptr< can::DriverInterface > | driver_ |
can::CommInterface::FrameListenerConstSharedPtr | frame_listener_ |
GripperInput | input_ |
GripperOutput | output_ |
std::map< unsigned char, unsigned char > | prevCmd_ |
boost::timed_mutex | read_mutex |
can::Frame::Header | resp_header_ |
can::StateInterface::StateListenerConstSharedPtr | state_listener_ |
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 41 of file robotiq_3f_gripper_can_client.h.
Robotiq3FGripperCanClient::Robotiq3FGripperCanClient | ( | unsigned int | can_id, |
boost::shared_ptr< can::DriverInterface > | driver | ||
) |
Definition at line 35 of file robotiq_3f_gripper_can_client.cpp.
|
virtual |
Definition at line 42 of file robotiq_3f_gripper_can_client.cpp.
|
private |
Definition at line 386 of file robotiq_3f_gripper_can_client.cpp.
|
private |
Definition at line 401 of file robotiq_3f_gripper_can_client.cpp.
|
private |
Definition at line 396 of file robotiq_3f_gripper_can_client.cpp.
|
private |
Definition at line 391 of file robotiq_3f_gripper_can_client.cpp.
|
private |
Definition at line 416 of file robotiq_3f_gripper_can_client.cpp.
|
private |
Definition at line 411 of file robotiq_3f_gripper_can_client.cpp.
|
private |
Definition at line 406 of file robotiq_3f_gripper_can_client.cpp.
|
private |
Definition at line 431 of file robotiq_3f_gripper_can_client.cpp.
|
private |
Definition at line 426 of file robotiq_3f_gripper_can_client.cpp.
|
private |
Definition at line 421 of file robotiq_3f_gripper_can_client.cpp.
|
private |
Definition at line 446 of file robotiq_3f_gripper_can_client.cpp.
|
private |
Definition at line 441 of file robotiq_3f_gripper_can_client.cpp.
|
private |
Definition at line 436 of file robotiq_3f_gripper_can_client.cpp.
|
private |
Definition at line 369 of file robotiq_3f_gripper_can_client.cpp.
|
private |
Definition at line 378 of file robotiq_3f_gripper_can_client.cpp.
|
private |
received response from write request
unknown subindex
Definition at line 274 of file robotiq_3f_gripper_can_client.cpp.
|
virtual |
Set up listeners
Reimplemented from robotiq_3f_gripper_control::Robotiq3FGripperClientBase.
Definition at line 47 of file robotiq_3f_gripper_can_client.cpp.
|
virtual |
Reads set of input-register values from the gripper.
try to lock one more time to wait for last read
Implements robotiq_3f_gripper_control::Robotiq3FGripperClientBase.
Definition at line 211 of file robotiq_3f_gripper_can_client.cpp.
|
virtual |
Reads set of output-register values from the gripper.
Implements robotiq_3f_gripper_control::Robotiq3FGripperClientBase.
Definition at line 253 of file robotiq_3f_gripper_can_client.cpp.
|
private |
initialize node
Definition at line 355 of file robotiq_3f_gripper_can_client.cpp.
|
private |
Definition at line 258 of file robotiq_3f_gripper_can_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 |
because too much writing is bad with this device, only write when something has changed. do the check here, or elsewhere? write mutex?
Implements robotiq_3f_gripper_control::Robotiq3FGripperClientBase.
Definition at line 55 of file robotiq_3f_gripper_can_client.cpp.
|
private |
Definition at line 73 of file robotiq_3f_gripper_can_client.h.
|
private |
Definition at line 71 of file robotiq_3f_gripper_can_client.h.
|
private |
Definition at line 72 of file robotiq_3f_gripper_can_client.h.
|
private |
Definition at line 79 of file robotiq_3f_gripper_can_client.h.
|
private |
Definition at line 76 of file robotiq_3f_gripper_can_client.h.
|
private |
Definition at line 77 of file robotiq_3f_gripper_can_client.h.
|
private |
Definition at line 87 of file robotiq_3f_gripper_can_client.h.
|
mutableprivate |
Definition at line 89 of file robotiq_3f_gripper_can_client.h.
|
private |
Definition at line 74 of file robotiq_3f_gripper_can_client.h.
|
private |
Definition at line 80 of file robotiq_3f_gripper_can_client.h.