26 #ifndef SR_EDC_ETHERCAT_DRIVERS_SR08_H 27 #define SR_EDC_ETHERCAT_DRIVERS_SR08_H 29 #include <ros_ethercat_hardware/ethercat_hardware.h> 32 #include <std_msgs/Int16.h> 33 #include <std_msgs/Float64MultiArray.h> 34 #include <sr_robot_msgs/SimpleMotorFlasher.h> 37 #include <boost/smart_ptr.hpp> 40 #include <boost/assign.hpp> 41 #include <boost/algorithm/string.hpp> 42 #include <boost/algorithm/string/find_iterator.hpp> 46 #include <sr_robot_msgs/EthercatDebug.h> 61 virtual void construct(EtherCAT_SlaveHandler *sh,
int &start_address);
63 virtual int initialize(hardware_interface::HardwareInterface *hw,
bool allow_unprogrammed =
true);
65 virtual void multiDiagnostics(vector<diagnostic_msgs::DiagnosticStatus> &vec,
unsigned char *buffer);
67 virtual void packCommand(
unsigned char *buffer,
bool halt,
bool reset);
69 virtual bool unpackState(
unsigned char *this_buffer,
unsigned char *prev_buffer);
118 #endif // SR_EDC_ETHERCAT_DRIVERS_SR08_H
virtual void get_board_id_and_can_bus(int board_id, int *can_bus, unsigned int *board_can_id)
boost::shared_ptr< realtime_tools::RealtimePublisher< std_msgs::Float64MultiArray > > extra_analog_inputs_publisher
Extra analog inputs real time publisher (+ accelerometer and gyroscope)
SR08()
Constructor of the SR08 driver.
virtual void construct(EtherCAT_SlaveHandler *sh, int &start_address)
Construct function, run at startup to set SyncManagers and FMMUs.
boost::shared_ptr< shadow_robot::SrMotorHandLib< ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_COMMAND > > sr_hand_lib
virtual void packCommand(unsigned char *buffer, bool halt, bool reset)
packs the commands before sending them to the EtherCAT bus
virtual int initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed=true)
virtual void reinitialize_boards()
This function will call the reinitialization function for the boards attached to the CAN bus...
std::vector< boost::shared_ptr< rt_pub_int16_t > > realtime_pub_
realtime_tools::RealtimePublisher< std_msgs::Int16 > rt_pub_int16_t
This is a parent class for the ROS drivers for any Shadow Robot EtherCAT Dual CAN Slave...
virtual void multiDiagnostics(vector< diagnostic_msgs::DiagnosticStatus > &vec, unsigned char *buffer)
This function gives some diagnostics data.
virtual bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
This functions receives data from the EtherCAT bus.
unsigned int zero_buffer_read
boost::shared_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::EthercatDebug > > debug_publisher
Debug real time publisher: publishes the raw ethercat data.