motorconf.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include <map>
36 #include <stdio.h>
37 #include <getopt.h>
38 #include <sys/mman.h>
39 
40 #include <tinyxml.h>
41 
42 #include <ethercat/ethercat_xenomai_drv.h>
43 #include <dll/ethercat_dll.h>
44 #include <al/ethercat_AL.h>
45 #include <al/ethercat_master.h>
46 #include <al/ethercat_slave_handler.h>
47 
49 #include <ethercat_hardware/wg0x.h>
50 #include <ethercat_hardware/wg05.h>
51 #include <ethercat_hardware/wg06.h>
54 
55 #include <boost/crc.hpp>
56 #include <boost/foreach.hpp>
57 
58 #include <net/if.h>
59 #include <sys/ioctl.h>
60 #include <netinet/in.h>
61 
62 #include <log4cxx/logger.h>
63 
64 using namespace ethercat_hardware;
65 
66 vector<EthercatDevice *> devices;
67 
68 struct Actuator {
69  string motor;
70  string board;
72 };
73 typedef pair<string, Actuator> ActuatorPair;
74 map<string, Actuator> actuators;
75 
76 struct Config
77 {
78  Config(const WG0XActuatorInfo &actuator_info, const MotorHeatingModelParametersEepromConfig &heating_config) :
79  actuator_info_(actuator_info), heating_config_(heating_config)
80  { }
81  Config() {}
84 };
85 typedef pair<string, Config> MotorPair;
86 map<string, Config> motors;
87 
88 void init(char *interface)
89 {
90  // open temporary socket to use with ioctl
91  int sock = socket(PF_INET, SOCK_DGRAM, 0);
92  if (sock < 0) {
93  int error = errno;
94  fprintf(stderr,"Couldn't open temp socket : %s", strerror(error));
95  exit(-1);
96  }
97 
98  struct ifreq ifr;
99  strncpy(ifr.ifr_name, interface, IFNAMSIZ);
100  if (ioctl(sock, SIOCGIFFLAGS, &ifr) < 0) {
101  int error = errno;
102  fprintf(stderr,"Cannot get interface flags for %s: %s\n", interface, strerror(error));
103  exit(-1);
104  }
105 
106  close(sock);
107  sock = -1;
108 
109  if (!(ifr.ifr_flags & IFF_UP)) {
110  fprintf(stderr,"Interface %s is not UP. Try : ifup %s\n", interface, interface);
111  exit(-1);
112  }
113  if (!(ifr.ifr_flags & IFF_RUNNING)) {
114  fprintf(stderr,"Interface %s is not RUNNING. Is cable plugged in and device powered?\n", interface);
115  exit(-1);
116  }
117 
118  struct netif *ni;
119 
120  // Initialize network interface
121  if ((ni = init_ec(interface)) == NULL)
122  {
123  fprintf(stderr, "Unable to initialize interface: %s\n", interface);
124  exit(-1);
125  }
126 
127  // Initialize Application Layer (AL)
128  EtherCAT_DataLinkLayer::instance()->attach(ni);
129  EtherCAT_AL *al;
130  if ((al = EtherCAT_AL::instance()) == NULL)
131  {
132  fprintf(stderr, "Unable to initialize Application Layer (AL): %p\n", al);
133  exit(-1);
134  }
135 
136  uint32_t num_slaves = al->get_num_slaves();
137  if (num_slaves == 0)
138  {
139  fprintf(stderr, "Unable to locate any slaves\n");
140  exit(-1);
141  }
142 
143  // Initialize Master
144  EtherCAT_Master *em;
145  if ((em = EtherCAT_Master::instance()) == NULL)
146  {
147  fprintf(stderr, "Unable to initialize EtherCAT_Master: %p", em);
148  exit(-1);
149  }
150 
151  static int start_address = 0x00010000;
152 
153  for (unsigned int slave = 0; slave < num_slaves; ++slave)
154  {
155  EC_FixedStationAddress fsa(slave + 1);
156  EtherCAT_SlaveHandler *sh = em->get_slave_handler(fsa);
157  if (sh == NULL)
158  {
159  fprintf(stderr, "Unable to get slave handler #%d", slave);
160  exit(-1);
161  }
162 
163  if (sh->get_product_code() == WG05::PRODUCT_CODE)
164  {
165  WG05 *dev = new WG05();
166  dev->construct(sh, start_address);
167  devices.push_back(dev);
168  }
169  else if (sh->get_product_code() == WG06::PRODUCT_CODE)
170  {
171  WG06 *dev = new WG06();
172  dev->construct(sh, start_address);
173  devices.push_back(dev);
174  }
175  else if (sh->get_product_code() == WG021::PRODUCT_CODE)
176  {
177  WG021 *dev = new WG021();
178  dev->construct(sh, start_address);
179  devices.push_back(dev);
180  }
181  else if (sh->get_product_code() == WG014::PRODUCT_CODE)
182  {
183  WG014 *dev = new WG014();
184  dev->construct(sh, start_address);
185  devices.push_back(dev);
186  }
187  else
188  {
189  devices.push_back(NULL);
190  }
191  }
192 
193  BOOST_FOREACH(EthercatDevice *device, devices)
194  {
195  if (!device) continue;
196  if (!device->sh_->to_state(EC_OP_STATE))
197  {
198  fprintf(stderr, "Unable set device %d into OP_STATE", device->sh_->get_ring_position());
199  }
200  }
201 
202  BOOST_FOREACH(EthercatDevice *device, devices)
203  {
204  if (!device) continue;
205  device->use_ros_ = false;
206  device->initialize(NULL, true);
207  }
208 }
209 
211 {
212  if (dynamic_cast<WG021 *>(d)) {
213  return "wg021";
214  } else if (dynamic_cast<WG06 *>(d)) {
215  return "wg006";
216  } else if (dynamic_cast<WG05 *>(d)) {
217  return "wg005";
218  }
219  return "unknown";
220 }
221 
222 
223 WG0X* getWGDevice(int device)
224 {
225  uint32_t num_slaves = EtherCAT_AL::instance()->get_num_slaves();
226  if ((device >= (int)num_slaves) || (device < 0))
227  {
228  ROS_FATAL("Invalid device number %d. Must be value between 0 and %d", device, num_slaves-1);
229  return NULL;
230  }
231 
232  if (devices[device] == NULL)
233  {
234  ROS_FATAL("There is no device at position #%d", device);
235  return NULL;
236  }
237 
238  WG0X *wg = dynamic_cast<WG0X *>(devices[device]);
239  if (wg==NULL)
240  {
241  ROS_FATAL("The device a position #%d is not programmable", device);
242  return NULL;
243  }
244 
245  return wg;
246 }
247 
248 
249 bool programDevice(int device,
250  const Config &config,
251  char *name, string expected_board, bool enforce_heating_model)
252 {
253  WG0X *wg = getWGDevice(device);
254  if (wg == NULL)
255  {
256  return false;
257  }
258 
259  string board = boardName(devices[device]);
260  if (expected_board != board)
261  {
262  ROS_FATAL("Device #%02d is a %s, but %s expects a %s\n", device, board.c_str(), name, expected_board.c_str());
263  return false;
264  }
265  ROS_INFO("Programming device %d, to be named: %s\n", device, name);
266 
267  WG0XActuatorInfo actuator_info = config.actuator_info_;
268  if (strlen(name) >= sizeof(actuator_info.name_))
269  {
270  ROS_FATAL("Device name '%s' is too long", name);
271  }
272  strncpy(actuator_info.name_, name, sizeof(actuator_info.name_));
273  actuator_info.generateCRC();
274 
275  ROS_INFO("Programming actuator version %d.%d",
276  int(actuator_info.major_), int(actuator_info.minor_));
277 
278  EthercatDirectCom com(EtherCAT_DataLinkLayer::instance());
279  if (!wg->program(&com, actuator_info))
280  {
281  ROS_FATAL("Error writing actuator info to device #%d", device);
282  return false;
283  }
284 
286  heating_config.enforce_ = enforce_heating_model;
287  heating_config.generateCRC();
288  if (!wg->program(&com, config.heating_config_))
289  {
290  ROS_FATAL("Writing heating model config to device #%d", device);
291  return false;
292  }
293 
294  return true;
295 }
296 
297 
298 // Uses ActuatorInfo name already stored in device
299 // to find appropriate motor heating model config
300 // Then only updates motor heating model config
301 bool updateHeatingConfig(int device)
302 {
303  WG0XActuatorInfo actuator_info;
304  EthercatDirectCom com(EtherCAT_DataLinkLayer::instance());
305  WG0X *wg = getWGDevice(device);
306  if (wg == NULL)
307  {
308  ROS_WARN("Skipping update of device %d", device);
309  return false;
310  }
311 
312  if (!wg->readActuatorInfoFromEeprom(&com, actuator_info))
313  {
314  ROS_ERROR("Could not read actuator info from device %d", device);
315  return false;
316  }
317 
318  if (!actuator_info.verifyCRC())
319  {
320  ROS_ERROR("Device %d has not actuator configuration", device);
321  return false;
322  }
323 
324  if (actuators.find(actuator_info.name_) == actuators.end())
325  {
326  ROS_ERROR("Could not find actuator info for device %d with name '%s'",
327  device, actuator_info.name_);
328  return false;
329  }
330 
331  const Actuator &actuator(actuators[actuator_info.name_]);
332  const string &motor_name(actuator.motor);
333  bool enforce_heating_model = actuator.enforce_heating_model;
334 
335  if (motors.find(motor_name) == motors.end())
336  {
337  ROS_ERROR("Could not find motor '%s' for device %d with actuator name '%s'",
338  motor_name.c_str(), device, actuator_info.name_);
339  return false;
340  }
341 
342  const Config &config(motors[motor_name]);
343 
344  if (strcmp(config.actuator_info_.motor_model_, actuator_info.motor_model_) != 0)
345  {
346  ROS_ERROR("For device %d '%s' : the motor name stored in EEPROM '%s' does not match the motor name '%s' from XML file",
347  device, actuator_info.name_, actuator_info.motor_model_, config.actuator_info_.motor_model_);
348  return false;
349  }
350 
352  heating_config.enforce_ = enforce_heating_model;
353  heating_config.generateCRC();
354  if (!wg->program(&com, heating_config))
355  {
356  ROS_FATAL("Writing heating model config to device #%d", device);
357  return false;
358  }
359 
360  ROS_INFO("Updated device %d (%s) with heating config for motor '%s'",
361  device, actuator_info.name_, config.actuator_info_.motor_model_);
362 
363  return true;
364 }
365 
366 
367 // Updates heating configuration of all devices
369 {
370  for (unsigned device=0; device<devices.size(); ++device)
371  {
372  updateHeatingConfig(device);
373  }
374  return true;
375 }
376 
377 
378 static struct
379 {
381  char *interface_;
382  char *name_;
383  bool program_;
384  bool help_;
385  int device_;
386  string motor_;
387  string actuators_;
388  string board_;
391 } g_options;
392 
393 void Usage(string msg = "")
394 {
395  fprintf(stderr, "Usage: %s [options]\n", g_options.program_name_);
396  fprintf(stderr, " -i, --interface <i> Use the network interface <i>\n");
397  fprintf(stderr, " -a, --actuators <file> Get the actuator definitions from file (default: actuators.conf)\n");
398  fprintf(stderr, " -d, --device <d> Select the device to program\n");
399  fprintf(stderr, " -b, --board <b> Set the expected board type (wg005, wg006, wg021)\n");
400  fprintf(stderr, " -p, --program Program a motor control board\n");
401  fprintf(stderr, " -n, --name <n> Set the name of the motor control board to <n>\n");
402  fprintf(stderr, " -U, --update_heating_config Update motor heating model configuration of all boards\n");
403  fprintf(stderr, " Known actuator names:\n");
404  BOOST_FOREACH(ActuatorPair p, actuators)
405  {
406  string name = p.first;
407  fprintf(stderr, " %s\n", name.c_str());
408  }
409  fprintf(stderr, " -m, --motor <m> Set the configuration for motor <m>\n");
410  fprintf(stderr, " Legal motor values are:\n");
411  BOOST_FOREACH(MotorPair p, motors)
412  {
413  const string &name(p.first);
414  const WG0XActuatorInfo &info(p.second.actuator_info_);
415  fprintf(stderr, " %s - %s %s\n", name.c_str(), info.motor_make_, info.motor_model_);
416  }
417  fprintf(stderr, " -h, --help Print this message and exit\n");
418  if (msg != "")
419  {
420  fprintf(stderr, "Error: %s\n", msg.c_str());
421  exit(-1);
422  }
423  else
424  {
425  exit(0);
426  }
427 }
428 
429 
430 bool getDoubleAttribute(TiXmlElement *params, const char* motor_name, const char* param_name, double& value)
431 {
432  const char *val_str = params->Attribute(param_name);
433  if (val_str == NULL)
434  {
435  ROS_ERROR("Attribute '%s' for motor '%s' is not defined", param_name, motor_name);
436  return false;
437  }
438 
439  char *endptr=NULL;
440  value = strtod(val_str, &endptr);
441  if ((endptr == val_str) || (endptr < (val_str+strlen(val_str))))
442  {
443  ROS_ERROR("Couldn't convert '%s' to double for attribute '%s' of motor '%s'",
444  val_str, param_name, motor_name);
445  return false;
446  }
447 
448  return true;
449 }
450 
451 bool getIntegerAttribute(TiXmlElement *params, const char* motor_name, const char* param_name, int& value)
452 {
453  const char *val_str = params->Attribute(param_name);
454  if (val_str == NULL)
455  {
456  ROS_ERROR("Attribute '%s' for motor '%s' is not defined", param_name, motor_name);
457  return false;
458  }
459 
460  char *endptr=NULL;
461  value = strtol(val_str, &endptr, 0);
462  if ((endptr == val_str) || (endptr < (val_str+strlen(val_str))))
463  {
464  ROS_ERROR("Couldn't convert '%s' to integer for attribute '%s' of motor '%s'",
465  val_str, param_name, motor_name);
466  return false;
467  }
468 
469  return true;
470 }
471 
472 bool getStringAttribute(TiXmlElement *params, const char* motor_name, const char* param_name, char* strbuf, unsigned buflen)
473 {
474  const char *val = params->Attribute(param_name);
475  if (val == NULL)
476  {
477  ROS_ERROR("No '%s' attribute for motor '%s'", param_name, motor_name);
478  return false;
479  }
480  if (strlen(val) >= buflen)
481  {
482  ROS_ERROR("'%s' value '%s' for motor '%s' is too long. Limit value to %d characters.",
483  param_name, val, motor_name, buflen-1);
484  return false;
485  }
486  strncpy(strbuf, val, buflen);
487  strbuf[buflen-1] = '\0';
488  return true;
489 }
490 
491 
492 bool parseConfig(TiXmlElement *config)
493 {
494  TiXmlElement *actuatorElt = config->FirstChildElement("actuators");
495  TiXmlElement *motorElt = config->FirstChildElement("motors");
496 
497  for (TiXmlElement *elt = actuatorElt->FirstChildElement("actuator");
498  elt;
499  elt = elt->NextSiblingElement("actuator"))
500  {
501  const char *name = elt->Attribute("name");
502  if (name == NULL)
503  {
504  ROS_ERROR("Acutuator attribute 'name' not specified");
505  return false;
506  }
507 
508  struct Actuator a;
509 
510  const char *motor = elt->Attribute("motor");
511  if (motor == NULL)
512  {
513  ROS_ERROR("For actuator '%s', 'motor' attribute not specified", name);
514  return false;
515  }
516  a.motor = motor;
517 
518  const char *board = elt->Attribute("board");
519  if (board == NULL)
520  {
521  ROS_ERROR("For actuator '%s', 'board' attribute not specified", name);
522  return false;
523  }
524  a.board = board;
525 
526  const char *enforce_heating_model = elt->Attribute("enforce_heating_model");
527  if (enforce_heating_model == NULL)
528  {
529  // ROS_ERROR("For actuator '%s', 'enforce_heating_model' attribute not specified", name);
530  //return false;
531  a.enforce_heating_model=false;
532  }
533  else if (strcmp(enforce_heating_model, "true") == 0)
534  {
535  a.enforce_heating_model=true;
536  }
537  else if (strcmp(enforce_heating_model, "false") == 0)
538  {
539  a.enforce_heating_model=false;
540  }
541  else
542  {
543  ROS_ERROR("For actuator '%s' : 'enforce_heating_model' attribute should be 'true' or 'false' not '%s'",
544  name, enforce_heating_model);
545  return false;
546  }
547 
548  actuators[name] = a;
549  }
550 
551  WG0XActuatorInfo info;
552  memset(&info, 0, sizeof(info));
553  info.major_ = 0;
554  info.minor_ = 2;
555  strcpy(info.robot_name_, "PR2");
557  memset(&heating_config, 0, sizeof(heating_config));
558  heating_config.major_ = 0;
559  heating_config.minor_ = 1;
560  heating_config.enforce_ = 0; // default, don't enforce heating model
561 
562  for (TiXmlElement *elt = motorElt->FirstChildElement("motor");
563  elt;
564  elt = elt->NextSiblingElement("motor"))
565  {
566  bool success = true;
567  const char *name = elt->Attribute("name");
568  if (name == NULL)
569  {
570  ROS_ERROR("Motor 'name' attribute is not specified");
571  return false;
572  }
573 
574  TiXmlElement *params = elt->FirstChildElement("params");
575  if (params == NULL)
576  {
577  ROS_ERROR("No 'params' tag available for motor '%s'", name);
578  return false;
579  }
580 
581  TiXmlElement *encoder = elt->FirstChildElement("encoder");
582  if (encoder == NULL)
583  {
584  ROS_ERROR("No 'encoder' tag available for motor '%s'", name);
585  return false;
586  }
587 
588  success &= getStringAttribute(params, name, "make", info.motor_make_, sizeof(info.motor_make_));
589  success &= getStringAttribute(params, name, "model", info.motor_model_, sizeof(info.motor_model_));
590 
591  double fvalue;
592 
593  success &= getDoubleAttribute(params, name, "max_current", fvalue);
594  info.max_current_ = fvalue;
595  success &= getDoubleAttribute(params, name, "speed_constant", fvalue);
596  info.speed_constant_ = fvalue;
597  success &= getDoubleAttribute(params, name, "resistance", fvalue);
598  info.resistance_ = fvalue;
599  success &= getDoubleAttribute(params, name, "motor_torque_constant", fvalue);
600  info.motor_torque_constant_ = fvalue;
601  success &= getDoubleAttribute(encoder, name, "reduction", fvalue);
602  info.encoder_reduction_ = fvalue;
603 
604  int ivalue=-1;
605  success &= getIntegerAttribute(encoder, name, "pulses_per_revolution", ivalue);
606  info.pulses_per_revolution_ = ivalue;
607 
609  success &= getDoubleAttribute(params, name, "housing_to_ambient_thermal_resistance", fvalue);
611  success &= getDoubleAttribute(params, name, "winding_to_housing_thermal_resistance", fvalue);
613  success &= getDoubleAttribute(params, name, "winding_thermal_time_constant", fvalue);
614  hmp.winding_thermal_time_constant_ = fvalue;
615  success &= getDoubleAttribute(params, name, "housing_thermal_time_constant", fvalue);
616  hmp.housing_thermal_time_constant_ = fvalue;
617  success &= getDoubleAttribute(params, name, "max_winding_temperature", fvalue);
618  hmp.max_winding_temperature_ = fvalue;
619 
620  if (!success)
621  {
622  return false;
623  }
624 
625  if (motors.find(name) != motors.end())
626  {
627  ROS_ERROR("Motor named '%s' exists motor than once",name);
628  return false;
629  }
630 
631  motors[name] = Config(info, heating_config);
632  }
633  return true;
634 }
635 
636 
637 
638 
639 int main(int argc, char *argv[])
640 {
641 
642  // Set log level to DEBUG to allow device information to be displayed to
643  // output by default
644  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
645  logger->setLevel(ros::console::g_level_lookup[ros::console::levels::Debug]);
647 
648  // Parse options
649  g_options.program_name_ = argv[0];
650  g_options.device_ = -1;
651  g_options.help_ = false;
652  g_options.board_ = "";
653  g_options.update_motor_heating_config_ = false;
654  g_options.enforce_heating_model_ = false;
655  while (1)
656  {
657  static struct option long_options[] = {
658  {"help", no_argument, 0, 'h'},
659  {"interface", required_argument, 0, 'i'},
660  {"name", required_argument, 0, 'n'},
661  {"device", required_argument, 0, 'd'},
662  {"board", required_argument, 0, 'b'},
663  {"motor", required_argument, 0, 'm'},
664  {"program", no_argument, 0, 'p'},
665  {"actuators", required_argument, 0, 'a'},
666  {"update_heating_config", no_argument, 0, 'U'},
667  {"enforce_heating_model", no_argument, 0, 'H'},
668  };
669  int option_index = 0;
670  int c = getopt_long(argc, argv, "d:b:hi:m:n:pa:UH", long_options, &option_index);
671  if (c == -1) break;
672  switch (c)
673  {
674  case 'h':
675  g_options.help_ = true;
676  break;
677  case 'd':
678  g_options.device_ = atoi(optarg);
679  break;
680  case 'b':
681  g_options.board_ = optarg;
682  break;
683  case 'i':
684  g_options.interface_ = optarg;
685  break;
686  case 'n':
687  g_options.name_ = optarg;
688  break;
689  case 'm':
690  g_options.motor_ = optarg;
691  break;
692  case 'p':
693  g_options.program_ = 1;
694  break;
695  case 'a':
696  g_options.actuators_ = optarg;
697  break;
698  case 'U':
699  g_options.update_motor_heating_config_ = true;
700  break;
701  case 'H':
702  g_options.enforce_heating_model_ = true;
703  break;
704  }
705  }
706 
707  // Parse configuration file
708  string filename = "actuators.conf";
709  if (g_options.actuators_ != "")
710  filename = g_options.actuators_;
711  TiXmlDocument xml(filename);
712 
713  if (!xml.LoadFile())
714  {
715  Usage("Unable to load configuration file");
716  }
717 
718 
719  if (!parseConfig(xml.RootElement()))
720  {
721  exit(EXIT_FAILURE);
722  }
723 
724  if (g_options.help_)
725  Usage();
726 
727  if (optind < argc)
728  {
729  Usage("Extra arguments");
730  }
731 
732  if (!g_options.interface_)
733  Usage("You must specify a network interface");
734 
735  // Try to get a raw socket.
736  int test_sock = socket(PF_PACKET, SOCK_RAW, htons(0x88A4));
737  if ((test_sock < 0) && (errno == EPERM))
738  {
739  ROS_FATAL("Insufficient priviledges to obtain raw socket. Try running as root.");
740  exit(-1);
741  }
742  close(test_sock);
743 
744  // Keep the kernel from swapping us out
745  if (mlockall(MCL_CURRENT | MCL_FUTURE) != 0)
746  {
747  ROS_WARN("mlockall failed : %s", strerror(errno));
748  }
749 
750  init(g_options.interface_);
751 
752  if (g_options.update_motor_heating_config_)
753  {
755  }
756 
757  if (g_options.program_)
758  {
759  string board = "wg005";
760  bool enforce_heating_model = false;
761  if (!g_options.name_)
762  Usage("You must specify a name");
763  if (g_options.motor_ == "")
764  {
765  if (actuators.find(g_options.name_) == actuators.end())
766  Usage("No default motor for this name");
767  g_options.motor_ = actuators[g_options.name_].motor;
768  board = actuators[g_options.name_].board;
769  enforce_heating_model = actuators[g_options.name_].enforce_heating_model;
770  }
771  if (g_options.board_ != "") {
772  board = g_options.board_;
773  }
774  if (g_options.device_ == -1)
775  Usage("You must specify a device #");
776  if (motors.find(g_options.motor_) == motors.end())
777  Usage("You must specify a valid motor");
778  if (g_options.enforce_heating_model_)
779  enforce_heating_model = true;
780 
781  programDevice(g_options.device_, motors[g_options.motor_], g_options.name_, board, enforce_heating_model);
782  }
783 
784  return 0;
785 }
786 
787 
msg
char name_[64]
Definition: wg0x.h:141
Config()
Definition: motorconf.cpp:81
uint16_t major_
Major revision of this structure.
MotorHeatingModelParameters params_
Motor parameters.
#define ROS_FATAL(...)
double winding_thermal_time_constant_
Thermal time constant of motor winding : in seconds.
uint32_t pulses_per_revolution_
Definition: wg0x.h:150
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
Definition: wg06.cpp:90
static bool getDoubleAttribute(TiXmlElement *elt, const std::string &filename, const char *param_name, double &value)
bool enforce_heating_model
Definition: motorconf.cpp:71
string board_
Definition: motorconf.cpp:388
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
char * interface_
Definition: motorconf.cpp:381
bool readActuatorInfoFromEeprom(EthercatCom *com, WG0XActuatorInfo &actuator_info)
Reads actuator info from eeprom.
Definition: wg0x.cpp:998
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
Definition: wg021.cpp:54
string actuators_
Definition: motorconf.cpp:387
double speed_constant_
Definition: wg0x.h:146
char motor_model_[32]
Definition: wg0x.h:144
double max_current_
Definition: wg0x.h:145
bool updateAllHeatingConfig()
Definition: motorconf.cpp:368
virtual int initialize(pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=0)=0
char robot_name_[32]
Definition: wg0x.h:142
EtherCAT driver for WG005 motor controller.
Definition: wg05.h:43
static struct @52 g_options
WG0X * getWGDevice(int device)
Definition: motorconf.cpp:223
bool enforce_
0 if heating model should be not be enforced, 0 otherwise
void generateCRC(void)
Calculate CRC of structure and update crc32_256_ and crc32_264_ elements.
Definition: wg0x.cpp:145
string motor
Definition: motorconf.cpp:69
int device_
Definition: motorconf.cpp:385
static bool getStringAttribute(TiXmlElement *elt, const std::string &filename, const char *param_name, std::string &value)
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
Definition: wg014.cpp:42
bool parseConfig(TiXmlElement *config)
Definition: motorconf.cpp:492
double resistance_
Definition: wg0x.h:147
bool program(EthercatCom *com, const WG0XActuatorInfo &actutor_info)
Programs acutator and heating parameters into device EEPROM.
Definition: wg0x.cpp:1050
pair< string, Actuator > ActuatorPair
Definition: motorconf.cpp:73
pair< string, Config > MotorPair
Definition: motorconf.cpp:85
#define ROS_WARN(...)
bool verifyCRC(void) const
Verify CRC stored in actuator info structure.
Definition: wg0x.cpp:130
int main(int argc, char *argv[])
Definition: motorconf.cpp:639
uint16_t minor_
Minor revision of this structure.
double motor_torque_constant_
Definition: wg0x.h:148
double encoder_reduction_
Definition: wg0x.h:149
MotorHeatingModelParametersEepromConfig heating_config_
Definition: motorconf.cpp:83
string boardName(EthercatDevice *d)
Definition: motorconf.cpp:210
void Usage(string msg="")
Definition: motorconf.cpp:393
vector< EthercatDevice * > devices
Definition: motorconf.cpp:66
double winding_to_housing_thermal_resistance_
Thermal resistance between motor winding and motor housing : in C/Watt.
#define ROS_INFO(...)
string motor_
Definition: motorconf.cpp:386
Config(const WG0XActuatorInfo &actuator_info, const MotorHeatingModelParametersEepromConfig &heating_config)
Definition: motorconf.cpp:78
Definition: wg021.h:85
bool programDevice(int device, const Config &config, char *name, string expected_board, bool enforce_heating_model)
Definition: motorconf.cpp:249
bool program_
Definition: motorconf.cpp:383
double housing_thermal_time_constant_
Thermal time constant of motor housing : in seconds.
uint16_t major_
Definition: wg0x.h:138
uint16_t minor_
Definition: wg0x.h:139
static bool getIntegerAttribute(TiXmlElement *elt, const std::string &filename, const char *param_name, int &value)
EtherCAT_SlaveHandler * sh_
map< string, Actuator > actuators
Definition: motorconf.cpp:74
double max_winding_temperature_
temperature limit of motor windings : in Celcius
bool updateHeatingConfig(int device)
Definition: motorconf.cpp:301
char * name_
Definition: motorconf.cpp:382
bool help_
Definition: motorconf.cpp:384
string board
Definition: motorconf.cpp:70
double housing_to_ambient_thermal_resistance_
Thermal resistance between motor housing and ambient : in C/Watt.
Definition: wg0x.h:234
bool enforce_heating_model_
Definition: motorconf.cpp:390
bool update_motor_heating_config_
Definition: motorconf.cpp:389
WG0XActuatorInfo actuator_info_
Definition: motorconf.cpp:82
#define ROS_ERROR(...)
#define ROSCONSOLE_DEFAULT_NAME
char * program_name_
Definition: motorconf.cpp:380
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
Definition: wg05.cpp:53
Definition: wg014.h:40
void init(char *interface)
Definition: motorconf.cpp:88
map< string, Config > motors
Definition: motorconf.cpp:86
char motor_make_[32]
Definition: wg0x.h:143
Definition: wg06.h:163


ethercat_hardware
Author(s): Rob Wheeler , Derek King
autogenerated on Fri Mar 15 2019 02:53:29