25 #ifndef ROBOTIQ_3F_GRIPPER_CAN_CLIENT_H 26 #define ROBOTIQ_3F_GRIPPER_CAN_CLIENT_H 87 std::map<unsigned char, unsigned char>
prevCmd_;
110 #endif // ROBOTIQ_3F_GRIPPER_CAN_CLIENT_H void decodeFingerBCurrent(const u_int8_t &f)
void decodeFingerCPosCmd(const u_int8_t &f)
void decodeObjectStatus(const u_int8_t &f)
virtual ~Robotiq3FGripperCanClient()
robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput GripperOutput
can::Frame::Header resp_header_
void decodeFingerSCurrent(const u_int8_t &f)
void decodeFingerACurrent(const u_int8_t &f)
void decodeFingerBPos(const u_int8_t &f)
void decodeFingerAPosCmd(const u_int8_t &f)
std::map< unsigned char, unsigned char > prevCmd_
void decodeFingerAPos(const u_int8_t &f)
void decodeFaultStatus(const u_int8_t &f)
void decodeFingerBPosCmd(const u_int8_t &f)
GripperOutput readOutputs() const
Reads set of output-register values from the gripper.
void stateCallback(const can::State &s)
void init(ros::NodeHandle nh)
can::StateInterface::StateListenerConstSharedPtr state_listener_
can::CommInterface::FrameListenerConstSharedPtr frame_listener_
void decodeFingerCCurrent(const u_int8_t &f)
void decodeGripperStatus(const u_int8_t &f)
Robotiq3FGripperCanClient(unsigned int can_id, boost::shared_ptr< can::DriverInterface > driver)
void decodeFingerSPosCmd(const u_int8_t &f)
This class provides a client for the EtherCAT manager object that can translate robot input/output me...
boost::timed_mutex read_mutex
void decodeFingerSPos(const u_int8_t &f)
robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotInput GripperInput
void decodeFingerCPos(const u_int8_t &f)
void writeOutputs(const GripperOutput &output)
Write the given set of control flags to the memory of the gripper.
GripperInput readInputs() const
Reads set of input-register values from the gripper.
boost::shared_ptr< can::DriverInterface > driver_
void frameCallback(const can::Frame &f)