36 #include <boost/foreach.hpp> 37 #include <std_msgs/Int16.h> 42 #include <sr_utilities/sr_math_utils.hpp> 45 using std::stringstream;
50 #include <boost/static_assert.hpp> 59 #define ETHERCAT_STATUS_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS) 60 #define ETHERCAT_COMMAND_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND) 62 #define ETHERCAT_CAN_BRIDGE_DATA_SIZE sizeof(ETHERCAT_CAN_BRIDGE_DATA) 64 #define ETHERCAT_COMMAND_DATA_ADDRESS PALM_0200_ETHERCAT_COMMAND_DATA_ADDRESS 65 #define ETHERCAT_STATUS_DATA_ADDRESS PALM_0200_ETHERCAT_STATUS_DATA_ADDRESS 66 #define ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS PALM_0200_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS 67 #define ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS PALM_0200_ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS 79 : zero_buffer_read(0),
132 ROS_INFO(
"Finished constructing the SR06 driver");
148 ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND> >(
180 d.name = prefix +
"EtherCAT Dual CAN Palm";
183 hwid << sh_->get_product_code() <<
"-" << sh_->get_serial();
184 d.hardware_id = hwid.str();
187 d.
addf(
"Position",
"%02d", sh_->get_ring_position());
188 d.
addf(
"Product Code",
"%d", sh_->get_product_code());
189 d.
addf(
"Serial Number",
"%d", sh_->get_serial());
190 d.
addf(
"Revision",
"%d", sh_->get_revision());
193 d.
addf(
"PIC idle time (in microsecs)",
"%d",
sr_hand_lib->main_pic_idle_time);
194 d.
addf(
"Min PIC idle time (since last diagnostics)",
"%d",
sr_hand_lib->main_pic_idle_time_min);
198 this->ethercatDiagnostics(d, 2);
228 SrEdc::packCommand(buffer, halt, reset);
230 ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND *
command =
231 reinterpret_cast<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND *
>(buffer);
247 ROS_DEBUG(
"Sending command : Type : 0x%02X ; data : 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X " 248 "0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X 0x%04X",
249 command->to_motor_data_type,
250 command->motor_data[0],
251 command->motor_data[1],
252 command->motor_data[2],
253 command->motor_data[3],
254 command->motor_data[4],
255 command->motor_data[5],
256 command->motor_data[6],
257 command->motor_data[7],
258 command->motor_data[8],
259 command->motor_data[9],
260 command->motor_data[10],
261 command->motor_data[11],
262 command->motor_data[12],
263 command->motor_data[13],
264 command->motor_data[14],
265 command->motor_data[15],
266 command->motor_data[16],
267 command->motor_data[17],
268 command->motor_data[18],
269 command->motor_data[19]);
294 ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS *status_data =
295 reinterpret_cast<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS *
>(this_buffer + command_size_);
296 ETHERCAT_CAN_BRIDGE_DATA *can_data =
reinterpret_cast<ETHERCAT_CAN_BRIDGE_DATA *
>(this_buffer + command_size_ +
299 static unsigned int num_rxed_packets = 0;
315 debug_publisher->msg_.motor_data_type.data =
static_cast<int> (status_data->motor_data_type);
317 debug_publisher->msg_.which_motor_data_arrived = status_data->which_motor_data_arrived;
318 debug_publisher->msg_.which_motor_data_had_errors = status_data->which_motor_data_had_errors;
322 for (
unsigned int i = 0; i < 10; ++i)
324 debug_publisher->msg_.motor_data_packet_torque.push_back(status_data->motor_data_packet[i].torque);
325 debug_publisher->msg_.motor_data_packet_misc.push_back(status_data->motor_data_packet[i].misc);
329 static_cast<int32u>(status_data->tactile_data_type));
331 static_cast<int16u> (status_data->tactile_data_valid));
333 for (
unsigned int i = 0; i < 5; ++i)
336 static_cast<unsigned int> (static_cast<int16u> (status_data->tactile[i].word[0])));
348 float percentage_packet_loss = 100.f * (
static_cast<float>(
zero_buffer_read) /
349 static_cast<float>(num_rxed_packets));
351 ROS_DEBUG(
"Reception error detected : %d errors out of %d rxed packets (%2.3f%%) ; idle time %dus",
352 zero_buffer_read, num_rxed_packets, percentage_packet_loss, status_data->idle_time_us);
371 std_msgs::Float64MultiArray extra_analog_msg;
372 extra_analog_msg.layout.dim.resize(3);
373 extra_analog_msg.data.resize(3 + 3 + 4);
374 std::vector<double>
data;
376 extra_analog_msg.layout.dim[0].label =
"accelerometer";
377 extra_analog_msg.layout.dim[0].size = 3;
378 extra_analog_msg.data[0] = status_data->sensors[
ACCX];
379 extra_analog_msg.data[1] = status_data->sensors[
ACCY];
380 extra_analog_msg.data[2] = status_data->sensors[
ACCZ];
382 extra_analog_msg.layout.dim[1].label =
"gyrometer";
383 extra_analog_msg.layout.dim[1].size = 3;
384 extra_analog_msg.data[3] = status_data->sensors[
GYRX];
385 extra_analog_msg.data[4] = status_data->sensors[
GYRY];
386 extra_analog_msg.data[5] = status_data->sensors[
GYRZ];
388 extra_analog_msg.layout.dim[2].label =
"analog_inputs";
389 extra_analog_msg.layout.dim[2].size = 4;
390 extra_analog_msg.data[6] = status_data->sensors[
ANA0];
391 extra_analog_msg.data[7] = status_data->sensors[
ANA1];
392 extra_analog_msg.data[8] = status_data->sensors[
ANA2];
393 extra_analog_msg.data[9] = status_data->sensors[
ANA3];
429 int motor_id_tmp = board_id;
430 if (motor_id_tmp > 9)
440 *board_can_id = motor_id_tmp;
#define ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS
virtual bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
This functions receives data from the EtherCAT bus.
ros::NodeHandle nh_tilde_
virtual int initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed=true)
void summary(unsigned char lvl, const std::string s)
virtual int initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed=true)
#define ETHERCAT_STATUS_DATA_SIZE
This is a ROS driver for Shadow Robot #6 EtherCAT product ID.
unsigned int zero_buffer_read
void addf(const std::string &key, const char *format,...)
#define ETHERCAT_COMMAND_DATA_ADDRESS
BOOST_STATIC_ASSERT(sizeof(EDC_COMMAND)==4)
EDC_COMMAND_CAN_DIRECT_MODE
virtual void multiDiagnostics(vector< diagnostic_msgs::DiagnosticStatus > &vec, unsigned char *buffer)
This function gives some diagnostics data.
virtual void construct(EtherCAT_SlaveHandler *sh, int &start_address, unsigned int ethercat_command_data_size, unsigned int ethercat_status_data_size, unsigned int ethercat_can_bridge_data_size, unsigned int ethercat_command_data_address, unsigned int ethercat_status_data_address, unsigned int ethercat_can_bridge_data_command_address, unsigned int ethercat_can_bridge_data_status_address)
Construct function, run at startup to set SyncManagers and FMMUs.
ROSLIB_DECL std::string command(const std::string &cmd)
ros::NodeHandle nodehandle_
void build_CAN_message(ETHERCAT_CAN_BRIDGE_DATA *message)
PLUGINLIB_EXPORT_CLASS(SR06, EthercatDevice)
#define ETHERCAT_COMMAND_DATA_SIZE
bool can_data_is_ack(ETHERCAT_CAN_BRIDGE_DATA *packet)
This function checks if the can packet in the unpackState() this_buffer is an ACK.
#define ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS
boost::shared_ptr< realtime_tools::RealtimePublisher< std_msgs::Float64MultiArray > > extra_analog_inputs_publisher
Extra analog inputs real time publisher (+ accelerometer and gyroscope)
#define ETHERCAT_CAN_BRIDGE_DATA_SIZE
std::string device_joint_prefix_
virtual void reinitialize_boards()
This function will call the reinitialization function for the boards attached to the CAN bus...
#define ETHERCAT_STATUS_DATA_ADDRESS
boost::shared_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::EthercatDebug > > debug_publisher
Debug real time publisher: publishes the raw ethercat data.
boost::shared_ptr< shadow_robot::SrMotorHandLib< ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND > > sr_hand_lib
virtual void get_board_id_and_can_bus(int board_id, int *can_bus, unsigned int *board_can_id)
virtual void packCommand(unsigned char *buffer, bool halt, bool reset)
packs the commands before sending them to the EtherCAT bus
virtual void construct(EtherCAT_SlaveHandler *sh, int &start_address)
Construct function, run at startup to set SyncManagers and FMMUs.
SR06()
Constructor of the SR06 driver.