39 #include <ethercat/ethercat_xenomai_drv.h>
40 #include <dll/ethercat_dll.h>
41 #include <dll/ethercat_device_addressed_telegram.h>
46 #include <sys/ioctl.h>
47 #include <boost/bind.hpp>
48 #include <boost/foreach.hpp>
49 #include <boost/regex.hpp>
50 #include <boost/shared_ptr.hpp>
51 #include <boost/thread/thread.hpp>
58 halt_after_reset_(false),
59 reset_motors_service_count_(0),
60 halt_motors_service_count_(0),
61 halt_motors_error_count_(0),
62 motors_halted_(false),
63 motors_halted_reason_(
"")
77 hw_(0), node_(
ros::NodeHandle(name)),
78 ni_(0), this_buffer_(0), prev_buffer_(0), buffer_size_(0), halt_motors_(true), reset_state_(0),
80 diagnostics_publisher_(node_),
81 motor_publisher_(node_,
"motors_halted", 1, true),
82 device_loader_(
"ethercat_hardware",
"EthercatDevice")
90 for (uint32_t i = 0; i <
slaves_.size(); ++i)
92 EC_FixedStationAddress fsa(i + 1);
93 EtherCAT_SlaveHandler *sh =
em_->get_slave_handler(fsa);
94 if (sh) sh->to_state(EC_PREOP_STATE);
109 unsigned product_code = sh->get_product_code();
110 unsigned serial = sh->get_serial();
111 uint32_t revision = sh->get_revision();
112 unsigned slave = sh->get_station_address()-1;
114 if (!sh->to_state(new_state))
116 ROS_FATAL(
"Cannot goto state %d for slave #%d, product code: %u (0x%X), serial: %u (0x%X), revision: %d (0x%X)",
117 new_state, slave, product_code, product_code, serial, serial, revision, revision);
118 if ((product_code==0xbaddbadd) || (serial==0xbaddbadd) || (revision==0xbaddbadd))
119 ROS_FATAL(
"Note: 0xBADDBADD indicates that the value was not read correctly from device.");
127 int sock = socket(PF_INET, SOCK_DGRAM, 0);
130 ROS_FATAL(
"Couldn't open temp socket : %s", strerror(error));
136 strncpy(ifr.ifr_name, interface, IFNAMSIZ);
137 if (ioctl(sock, SIOCGIFFLAGS, &ifr) < 0) {
139 ROS_FATAL(
"Cannot get interface flags for %s: %s", interface, strerror(error));
147 if (!(ifr.ifr_flags & IFF_UP)) {
148 ROS_FATAL(
"Interface %s is not UP. Try : ifup %s", interface, interface);
152 if (!(ifr.ifr_flags & IFF_RUNNING)) {
153 ROS_FATAL(
"Interface %s is not RUNNING. Is cable plugged in and device powered?", interface);
161 if ((
ni_ = init_ec(interface)) == NULL)
163 ROS_FATAL(
"Unable to initialize interface: %s", interface);
171 EtherCAT_DataLinkLayer::instance()->attach(
ni_);
172 if ((
al_ = EtherCAT_AL::instance()) == NULL)
174 ROS_FATAL(
"Unable to initialize Application Layer (AL): %p",
al_);
182 ROS_FATAL(
"Unable to locate any slaves");
188 if ((
em_ = EtherCAT_Master::instance()) == NULL)
190 ROS_FATAL(
"Unable to initialize EtherCAT_Master: %p",
em_);
199 std::vector<EtherCAT_SlaveHandler*> slave_handles;
200 for (
unsigned int slave = 0; slave <
slaves_.size(); ++slave)
202 EC_FixedStationAddress fsa(slave + 1);
203 EtherCAT_SlaveHandler *sh =
em_->get_slave_handler(fsa);
206 ROS_FATAL(
"Unable to get slave handler #%d", slave);
210 slave_handles.push_back(sh);
214 BOOST_FOREACH(EtherCAT_SlaveHandler *sh, slave_handles)
216 unsigned slave = sh->get_station_address()-1;
219 ROS_FATAL(
"Unable to configure slave #%d", slave);
230 BOOST_FOREACH(EtherCAT_SlaveHandler *sh, slave_handles)
236 BOOST_FOREACH(EtherCAT_SlaveHandler *sh, slave_handles)
243 BOOST_FOREACH(EtherCAT_SlaveHandler *sh, slave_handles)
257 ROS_FATAL(
"No communication with devices");
272 for (
unsigned int slave = 0; slave <
slaves_.size(); ++slave)
276 EtherCAT_SlaveHandler *sh =
slaves_[slave]->sh_;
279 ROS_FATAL(
"Unable to initialize slave #%d, product code: %d, revision: %d, serial: %d",
280 slave, sh->get_product_code(), sh->get_revision(), sh->get_serial());
285 ROS_FATAL(
"Unable to initialize slave #%d", slave);
295 static const int MAX_TIMEOUT = 100000;
296 static const int DEFAULT_TIMEOUT = 20000;
300 timeout = DEFAULT_TIMEOUT;
302 if ((timeout <= 1) || (timeout > MAX_TIMEOUT))
304 int old_timeout = timeout;
305 timeout = std::max(1,
std::min(MAX_TIMEOUT, timeout));
306 ROS_WARN(
"Invalid timeout (%d) for socket, using %d", old_timeout, timeout);
308 if (set_socket_timeout(
ni_, timeout))
310 ROS_FATAL(
"Error setting socket timeout to %d", timeout);
325 int max_pd_retries = MAX_TIMEOUT / timeout;
326 static const int MAX_RETRIES=50, MIN_RETRIES=1;
329 if ((max_pd_retries * timeout) > (MAX_TIMEOUT))
331 max_pd_retries = MAX_TIMEOUT / timeout;
332 ROS_WARN(
"Max PD retries is too large for given timeout. Limiting value to %d", max_pd_retries);
334 if ((max_pd_retries < MIN_RETRIES) || (max_pd_retries > MAX_RETRIES))
336 max_pd_retries = std::max(MIN_RETRIES,
std::min(MAX_RETRIES,max_pd_retries));
337 ROS_WARN(
"Limiting max PD retries to %d", max_pd_retries);
339 max_pd_retries = std::max(MIN_RETRIES,
std::min(MAX_RETRIES,max_pd_retries));
349 diagnostics_ready_(false),
350 publisher_(node_.advertise<diagnostic_msgs::DiagnosticArray>(
"/diagnostics", 1)),
351 diagnostics_buffer_(NULL),
352 last_dropped_packet_count_(0),
353 last_dropped_packet_time_(0)
364 unsigned int num_ethercat_devices,
365 unsigned timeout,
unsigned max_pd_retries)
386 const unsigned char *buffer,
389 boost::try_to_lock_t try_lock;
391 if (lock.owns_lock())
420 }
catch (boost::thread_interrupted
const&) {
428 const accumulator_set<
double, stats<tag::max, tag::mean> > &acc,
431 status.addf(key +
" Avg (us)",
"%5.4f", extract_result<tag::mean>(acc) * 1e6);
432 status.addf(key +
" 1 Sec Max (us)",
"%5.4f", extract_result<tag::max>(acc) * 1e6);
433 status.addf(key +
" Max (us)",
"%5.4f", max * 1e6);
444 status_.name =
"EtherCAT Master";
447 std::ostringstream desc;
448 desc <<
"Motors halted";
451 desc <<
" soon after reset";
495 status_.
addf(
"Sent Packets",
"%llu", (
unsigned long long)c->sent);
496 status_.
addf(
"Received Packets",
"%llu", (
unsigned long long)c->received);
497 status_.
addf(
"Collected Packets",
"%llu", (
unsigned long long)c->collected);
498 status_.
addf(
"Dropped Packets",
"%llu", (
unsigned long long)c->dropped);
499 status_.
addf(
"TX Errors",
"%llu", (
unsigned long long)c->tx_error);
500 status_.
addf(
"TX Network Down",
"%llu", (
unsigned long long)c->tx_net_down);
501 status_.
addf(
"TX Would Block",
"%llu", (
unsigned long long)c->tx_would_block);
502 status_.
addf(
"TX No Buffers",
"%llu", (
unsigned long long)c->tx_no_bufs);
503 status_.
addf(
"TX Queue Full",
"%llu", (
unsigned long long)c->tx_full);
504 status_.
addf(
"RX Runt Packet",
"%llu", (
unsigned long long)c->rx_runt_pkt);
505 status_.
addf(
"RX Not EtherCAT",
"%llu", (
unsigned long long)c->rx_not_ecat);
506 status_.
addf(
"RX Other EML",
"%llu", (
unsigned long long)c->rx_other_eml);
507 status_.
addf(
"RX Bad Index",
"%llu", (
unsigned long long)c->rx_bad_index);
508 status_.
addf(
"RX Bad Sequence",
"%llu", (
unsigned long long)c->rx_bad_seqnum);
509 status_.
addf(
"RX Duplicate Sequence",
"%llu", (
unsigned long long)c->rx_dup_seqnum);
510 status_.
addf(
"RX Duplicate Packet",
"%llu", (
unsigned long long)c->rx_dup_pkt);
511 status_.
addf(
"RX Bad Order",
"%llu", (
unsigned long long)c->rx_bad_order);
512 status_.
addf(
"RX Late Packet",
"%llu", (
unsigned long long)c->rx_late_pkt);
513 status_.
addf(
"RX Late Packet RTT",
"%llu", (
unsigned long long)c->rx_late_pkt_rtt_us);
515 double rx_late_pkt_rtt_us_avg = 0.0;
516 if (c->rx_late_pkt > 0) {
517 rx_late_pkt_rtt_us_avg = ((double)c->rx_late_pkt_rtt_us_sum)/((double)c->rx_late_pkt);
519 status_.
addf(
"RX Late Packet Avg RTT",
"%f", rx_late_pkt_rtt_us_avg);
540 for (
unsigned int s = 0;
s <
slaves_.size(); ++
s)
556 unsigned char *this_buffer, *prev_buffer;
569 const unsigned CYCLES_PER_HALT_RELEASE = 2;
587 for (
unsigned int s = 0;
s <
slaves_.size(); ++
s)
592 slaves_[
s]->packCommand(this_buffer, halt_device, reset_devices);
619 for (
unsigned int s = 0;
s <
slaves_.size(); ++
s)
621 if (!
slaves_[
s]->unpackState(this_buffer, prev_buffer) && !reset_devices)
689 max = std::max(max, extract_result<tag::max>(acc));
710 static accumulator_set<double, stats<tag::max, tag::mean> > blank;
721 static int start_address = 0x00010000;
723 unsigned product_code = sh->get_product_code();
724 unsigned serial = sh->get_serial();
725 uint32_t revision = sh->get_revision();
726 unsigned slave = sh->get_station_address()-1;
758 stringstream class_name_regex_str;
759 class_name_regex_str <<
"(.*/)?" << product_code;
760 boost::regex class_name_regex(class_name_regex_str.str(), boost::regex::extended);
763 std::string matching_class_name;
765 BOOST_FOREACH(
const std::string &class_name, classes)
767 if (regex_match(class_name, class_name_regex))
769 if (matching_class_name.size() != 0)
771 ROS_ERROR(
"Found more than 1 EtherCAT driver for device with product code : %d", product_code);
772 ROS_ERROR(
"First class name = '%s'. Second class name = '%s'",
773 class_name.c_str(), matching_class_name.c_str());
775 matching_class_name = class_name;
779 if (matching_class_name.size() != 0)
789 ROS_FATAL(
"Unable to load plugin for slave #%d, product code: %u (0x%X), serial: %u (0x%X), revision: %d (0x%X)",
790 slave, product_code, product_code, serial, serial, revision, revision);
796 if ((product_code==0xbaddbadd) || (serial==0xbaddbadd) || (revision==0xbaddbadd))
798 ROS_FATAL(
"Note: 0xBADDBADD indicates that the value was not read correctly from device.");
799 ROS_FATAL(
"Perhaps you should power-cycle the MCBs");
803 ROS_ERROR(
"Unable to load plugin for slave #%d, product code: %u (0x%X), serial: %u (0x%X), revision: %d (0x%X)",
804 slave, product_code, product_code, serial, serial, revision, revision);
806 BOOST_FOREACH(
const std::string &class_name, classes)
818 p->construct(sh, start_address);
835 ROS_FATAL(
"Unable to load plugin for non-EtherCAT device '%s' with type: %s : %s"
836 , name.c_str(), type.c_str(), e.what());
839 ROS_INFO(
"Creating non-EtherCAT device '%s' of type '%s'", name.c_str(), type.c_str());
888 ROS_ERROR(
"Rosparam 'non_ethercat_devices' is not a struct type");
893 typedef XmlRpc::XmlRpcValue::ValueStruct::value_type map_item_t ;
894 BOOST_FOREACH(map_item_t &item, my_devices.
getMap())
896 const std::string &name(item.first);
901 ROS_ERROR(
"non_ethercat_devices/%s is not a struct type", name.c_str());
907 ROS_ERROR(
"non_ethercat_devices/%s 'type' element", name.c_str());
911 std::string type(
static_cast<std::string
>(device_info[
"type"]));
915 if (new_device != NULL)
929 EC_Logic *logic = EC_Logic::instance();
931 EC_UINT
length =
sizeof(p);
934 APRD_Telegram
status(logic->get_idx(),
942 EC_Ethernet_Frame frame(&
status);
949 for (
unsigned i = 0; i <
slaves_.size(); ++i)
960 const struct netif_counters &c(
ni_->counters);
961 os <<
"netif counters :" << endl
962 <<
" sent = " << c.sent << endl
963 <<
" received = " << c.received << endl
964 <<
" collected = " << c.collected << endl
965 <<
" dropped = " << c.dropped << endl
966 <<
" tx_error = " << c.tx_error << endl
967 <<
" tx_net_down = " << c.tx_net_down << endl
968 <<
" tx_would_block= " << c.tx_would_block << endl
969 <<
" tx_no_bufs = " << c.tx_no_bufs << endl
970 <<
" tx_full = " << c.tx_full << endl
971 <<
" rx_runt_pkt = " << c.rx_runt_pkt << endl
972 <<
" rx_not_ecat = " << c.rx_not_ecat << endl
973 <<
" rx_other_eml = " << c.rx_other_eml << endl
974 <<
" rx_bad_index = " << c.rx_bad_index << endl
975 <<
" rx_bad_seqnum = " << c.rx_bad_seqnum << endl
976 <<
" rx_dup_seqnum = " << c.rx_dup_seqnum << endl
977 <<
" rx_dup_pkt = " << c.rx_dup_pkt << endl
978 <<
" rx_bad_order = " << c.rx_bad_order << endl
979 <<
" rx_late_pkt = " << c.rx_late_pkt << endl;
986 bool success =
false;
987 for (
unsigned i=0; i<tries && !success; ++i) {
1002 if (position >= (
int)
slaves_.size())
1004 ROS_WARN(
"Invalid device position %d. Use 0-%d, or -1.", position,
int(
slaves_.size())-1);
1010 ROS_WARN(
"Invalid level : %d. Using level=2 (ERROR).", level);
1014 string new_reason(
"Manually triggered : " + reason);
1016 bool retval =
false;
1019 for (
unsigned i=0; i<
slaves_.size(); ++i)
1029 retval =
slaves_[position]->publishTrace(new_reason,level,delay);
1032 ROS_WARN(
"Device %d does not support publishing trace", position);