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> 55 #include <boost/foreach.hpp> 58 #include <sys/ioctl.h> 59 #include <netinet/in.h> 61 #include <log4cxx/logger.h> 78 actuator_info_(actuator_info), heating_config_(heating_config)
90 int sock = socket(PF_INET, SOCK_DGRAM, 0);
93 fprintf(stderr,
"Couldn't open temp socket : %s", strerror(error));
98 strncpy(ifr.ifr_name, interface, IFNAMSIZ);
99 if (ioctl(sock, SIOCGIFFLAGS, &ifr) < 0) {
101 fprintf(stderr,
"Cannot get interface flags for %s: %s\n", interface, strerror(error));
108 if (!(ifr.ifr_flags & IFF_UP)) {
109 fprintf(stderr,
"Interface %s is not UP. Try : ifup %s\n", interface, interface);
112 if (!(ifr.ifr_flags & IFF_RUNNING)) {
113 fprintf(stderr,
"Interface %s is not RUNNING. Is cable plugged in and device powered?\n", interface);
120 if ((ni = init_ec(interface)) == NULL)
122 fprintf(stderr,
"Unable to initialize interface: %s\n", interface);
127 EtherCAT_DataLinkLayer::instance()->attach(ni);
129 if ((al = EtherCAT_AL::instance()) == NULL)
131 fprintf(stderr,
"Unable to initialize Application Layer (AL): %p\n", al);
135 uint32_t num_slaves = al->get_num_slaves();
138 fprintf(stderr,
"Unable to locate any slaves\n");
144 if ((em = EtherCAT_Master::instance()) == NULL)
146 fprintf(stderr,
"Unable to initialize EtherCAT_Master: %p", em);
150 static int start_address = 0x00010000;
152 for (
unsigned int slave = 0; slave < num_slaves; ++slave)
154 EC_FixedStationAddress fsa(slave + 1);
155 EtherCAT_SlaveHandler *sh = em->get_slave_handler(fsa);
158 fprintf(stderr,
"Unable to get slave handler #%d", slave);
194 if (!device)
continue;
195 if (!device->
sh_->to_state(EC_OP_STATE))
197 fprintf(stderr,
"Unable set device %d into OP_STATE", device->
sh_->get_ring_position());
203 if (!device)
continue;
211 if (dynamic_cast<WG021 *>(d)) {
213 }
else if (dynamic_cast<WG06 *>(d)) {
215 }
else if (dynamic_cast<WG05 *>(d)) {
224 uint32_t num_slaves = EtherCAT_AL::instance()->get_num_slaves();
225 if ((device >= (
int)num_slaves) || (device < 0))
227 ROS_FATAL(
"Invalid device number %d. Must be value between 0 and %d", device, num_slaves-1);
233 ROS_FATAL(
"There is no device at position #%d", device);
240 ROS_FATAL(
"The device a position #%d is not programmable", device);
250 char *name,
string expected_board,
bool enforce_heating_model)
259 if (expected_board != board)
261 ROS_FATAL(
"Device #%02d is a %s, but %s expects a %s\n", device, board.c_str(), name, expected_board.c_str());
264 ROS_INFO(
"Programming device %d, to be named: %s\n", device, name);
267 if (strlen(name) >=
sizeof(actuator_info.
name_))
269 ROS_FATAL(
"Device name '%s' is too long", name);
271 strncpy(actuator_info.
name_, name,
sizeof(actuator_info.
name_));
274 ROS_INFO(
"Programming actuator version %d.%d",
278 if (!wg->
program(&com, actuator_info))
280 ROS_FATAL(
"Error writing actuator info to device #%d", device);
285 heating_config.
enforce_ = enforce_heating_model;
289 ROS_FATAL(
"Writing heating model config to device #%d", device);
307 ROS_WARN(
"Skipping update of device %d", device);
313 ROS_ERROR(
"Could not read actuator info from device %d", device);
319 ROS_ERROR(
"Device %d has not actuator configuration", device);
325 ROS_ERROR(
"Could not find actuator info for device %d with name '%s'",
326 device, actuator_info.
name_);
331 const string &motor_name(actuator.
motor);
336 ROS_ERROR(
"Could not find motor '%s' for device %d with actuator name '%s'",
337 motor_name.c_str(), device, actuator_info.
name_);
345 ROS_ERROR(
"For device %d '%s' : the motor name stored in EEPROM '%s' does not match the motor name '%s' from XML file",
351 heating_config.
enforce_ = enforce_heating_model;
353 if (!wg->
program(&com, heating_config))
355 ROS_FATAL(
"Writing heating model config to device #%d", device);
359 ROS_INFO(
"Updated device %d (%s) with heating config for motor '%s'",
369 for (
unsigned device=0; device<
devices.size(); ++device)
394 fprintf(stderr,
"Usage: %s [options]\n",
g_options.program_name_);
395 fprintf(stderr,
" -i, --interface <i> Use the network interface <i>\n");
396 fprintf(stderr,
" -a, --actuators <file> Get the actuator definitions from file (default: actuators.conf)\n");
397 fprintf(stderr,
" -d, --device <d> Select the device to program\n");
398 fprintf(stderr,
" -b, --board <b> Set the expected board type (wg005, wg006, wg021)\n");
399 fprintf(stderr,
" -p, --program Program a motor control board\n");
400 fprintf(stderr,
" -n, --name <n> Set the name of the motor control board to <n>\n");
401 fprintf(stderr,
" -U, --update_heating_config Update motor heating model configuration of all boards\n");
402 fprintf(stderr,
" Known actuator names:\n");
405 string name = p.first;
406 fprintf(stderr,
" %s\n", name.c_str());
408 fprintf(stderr,
" -m, --motor <m> Set the configuration for motor <m>\n");
409 fprintf(stderr,
" Legal motor values are:\n");
412 const string &name(p.first);
416 fprintf(stderr,
" -h, --help Print this message and exit\n");
419 fprintf(stderr,
"Error: %s\n",
msg.c_str());
429 bool getDoubleAttribute(TiXmlElement *params,
const char* motor_name,
const char* param_name,
double& value)
431 const char *val_str = params->Attribute(param_name);
434 ROS_ERROR(
"Attribute '%s' for motor '%s' is not defined", param_name, motor_name);
439 value = strtod(val_str, &endptr);
440 if ((endptr == val_str) || (endptr < (val_str+strlen(val_str))))
442 ROS_ERROR(
"Couldn't convert '%s' to double for attribute '%s' of motor '%s'",
443 val_str, param_name, motor_name);
450 bool getIntegerAttribute(TiXmlElement *params,
const char* motor_name,
const char* param_name,
int& value)
452 const char *val_str = params->Attribute(param_name);
455 ROS_ERROR(
"Attribute '%s' for motor '%s' is not defined", param_name, motor_name);
460 value = strtol(val_str, &endptr, 0);
461 if ((endptr == val_str) || (endptr < (val_str+strlen(val_str))))
463 ROS_ERROR(
"Couldn't convert '%s' to integer for attribute '%s' of motor '%s'",
464 val_str, param_name, motor_name);
471 bool getStringAttribute(TiXmlElement *params,
const char* motor_name,
const char* param_name,
char* strbuf,
unsigned buflen)
473 const char *val = params->Attribute(param_name);
476 ROS_ERROR(
"No '%s' attribute for motor '%s'", param_name, motor_name);
479 if (strlen(val) >= buflen)
481 ROS_ERROR(
"'%s' value '%s' for motor '%s' is too long. Limit value to %d characters.",
482 param_name, val, motor_name, buflen-1);
485 strncpy(strbuf, val, buflen);
486 strbuf[buflen-1] =
'\0';
493 TiXmlElement *actuatorElt = config->FirstChildElement(
"actuators");
494 TiXmlElement *motorElt = config->FirstChildElement(
"motors");
496 for (TiXmlElement *elt = actuatorElt->FirstChildElement(
"actuator");
498 elt = elt->NextSiblingElement(
"actuator"))
500 const char *name = elt->Attribute(
"name");
503 ROS_ERROR(
"Acutuator attribute 'name' not specified");
509 const char *
motor = elt->Attribute(
"motor");
512 ROS_ERROR(
"For actuator '%s', 'motor' attribute not specified", name);
517 const char *
board = elt->Attribute(
"board");
520 ROS_ERROR(
"For actuator '%s', 'board' attribute not specified", name);
526 if (enforce_heating_model == NULL)
532 else if (strcmp(enforce_heating_model,
"true") == 0)
536 else if (strcmp(enforce_heating_model,
"false") == 0)
542 ROS_ERROR(
"For actuator '%s' : 'enforce_heating_model' attribute should be 'true' or 'false' not '%s'",
543 name, enforce_heating_model);
551 memset(&info, 0,
sizeof(info));
556 memset(&heating_config, 0,
sizeof(heating_config));
557 heating_config.
major_ = 0;
558 heating_config.
minor_ = 1;
561 for (TiXmlElement *elt = motorElt->FirstChildElement(
"motor");
563 elt = elt->NextSiblingElement(
"motor"))
566 const char *name = elt->Attribute(
"name");
569 ROS_ERROR(
"Motor 'name' attribute is not specified");
573 TiXmlElement *params = elt->FirstChildElement(
"params");
576 ROS_ERROR(
"No 'params' tag available for motor '%s'", name);
580 TiXmlElement *encoder = elt->FirstChildElement(
"encoder");
583 ROS_ERROR(
"No 'encoder' tag available for motor '%s'", name);
608 success &=
getDoubleAttribute(params, name,
"housing_to_ambient_thermal_resistance", fvalue);
610 success &=
getDoubleAttribute(params, name,
"winding_to_housing_thermal_resistance", fvalue);
626 ROS_ERROR(
"Motor named '%s' exists motor than once",name);
638 int main(
int argc,
char *argv[])
652 g_options.update_motor_heating_config_ =
false;
653 g_options.enforce_heating_model_ =
false;
656 static struct option long_options[] = {
657 {
"help", no_argument, 0,
'h'},
658 {
"interface", required_argument, 0,
'i'},
659 {
"name", required_argument, 0,
'n'},
660 {
"device", required_argument, 0,
'd'},
661 {
"board", required_argument, 0,
'b'},
662 {
"motor", required_argument, 0,
'm'},
663 {
"program", no_argument, 0,
'p'},
664 {
"actuators", required_argument, 0,
'a'},
665 {
"update_heating_config", no_argument, 0,
'U'},
666 {
"enforce_heating_model", no_argument, 0,
'H'},
668 int option_index = 0;
669 int c = getopt_long(argc, argv,
"d:b:hi:m:n:pa:UH", long_options, &option_index);
698 g_options.update_motor_heating_config_ =
true;
707 string filename =
"actuators.conf";
710 TiXmlDocument xml(filename);
714 Usage(
"Unable to load configuration file");
728 Usage(
"Extra arguments");
732 Usage(
"You must specify a network interface");
735 int test_sock = socket(PF_PACKET, SOCK_RAW, htons(0x88A4));
736 if ((test_sock < 0) && (errno == EPERM))
738 ROS_FATAL(
"Insufficient priviledges to obtain raw socket. Try running as root.");
744 if (mlockall(MCL_CURRENT | MCL_FUTURE) != 0)
746 ROS_WARN(
"mlockall failed : %s", strerror(errno));
751 if (
g_options.update_motor_heating_config_)
758 string board =
"wg005";
759 bool enforce_heating_model =
false;
761 Usage(
"You must specify a name");
765 Usage(
"No default motor for this name");
774 Usage(
"You must specify a device #");
776 Usage(
"You must specify a valid motor");
778 enforce_heating_model =
true;
uint16_t major_
Major revision of this structure.
MotorHeatingModelParameters params_
Motor parameters.
double winding_thermal_time_constant_
Thermal time constant of motor winding : in seconds.
uint32_t pulses_per_revolution_
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
static bool getDoubleAttribute(TiXmlElement *elt, const std::string &filename, const char *param_name, double &value)
bool enforce_heating_model
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
bool readActuatorInfoFromEeprom(EthercatCom *com, WG0XActuatorInfo &actuator_info)
Reads actuator info from eeprom.
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
bool updateAllHeatingConfig()
virtual int initialize(pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=0)=0
EtherCAT driver for WG005 motor controller.
static struct @52 g_options
WG0X * getWGDevice(int device)
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.
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
bool parseConfig(TiXmlElement *config)
bool program(EthercatCom *com, const WG0XActuatorInfo &actutor_info)
Programs acutator and heating parameters into device EEPROM.
pair< string, Actuator > ActuatorPair
pair< string, Config > MotorPair
bool verifyCRC(void) const
Verify CRC stored in actuator info structure.
int main(int argc, char *argv[])
uint16_t minor_
Minor revision of this structure.
double motor_torque_constant_
double encoder_reduction_
MotorHeatingModelParametersEepromConfig heating_config_
string boardName(EthercatDevice *d)
void Usage(string msg="")
vector< EthercatDevice * > devices
double winding_to_housing_thermal_resistance_
Thermal resistance between motor winding and motor housing : in C/Watt.
Config(const WG0XActuatorInfo &actuator_info, const MotorHeatingModelParametersEepromConfig &heating_config)
bool programDevice(int device, const Config &config, char *name, string expected_board, bool enforce_heating_model)
double housing_thermal_time_constant_
Thermal time constant of motor housing : in seconds.
static bool getIntegerAttribute(TiXmlElement *elt, const std::string &filename, const char *param_name, int &value)
EtherCAT_SlaveHandler * sh_
map< string, Actuator > actuators
double max_winding_temperature_
temperature limit of motor windings : in Celcius
bool updateHeatingConfig(int device)
double housing_to_ambient_thermal_resistance_
Thermal resistance between motor housing and ambient : in C/Watt.
bool enforce_heating_model_
bool update_motor_heating_config_
WG0XActuatorInfo actuator_info_
#define ROSCONSOLE_DEFAULT_NAME
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
void init(char *interface)
map< string, Config > motors