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/crc.hpp>    56 #include <boost/foreach.hpp>    59 #include <sys/ioctl.h>    60 #include <netinet/in.h>    62 #include <log4cxx/logger.h>    79     actuator_info_(actuator_info), heating_config_(heating_config)
    91   int sock = socket(PF_INET, SOCK_DGRAM, 0);
    94     fprintf(stderr,
"Couldn't open temp socket : %s", strerror(error));
    99   strncpy(ifr.ifr_name, interface, IFNAMSIZ);
   100   if (ioctl(sock, SIOCGIFFLAGS, &ifr) < 0) {
   102     fprintf(stderr,
"Cannot get interface flags for %s: %s\n", interface, strerror(error));
   109   if (!(ifr.ifr_flags & IFF_UP)) {
   110     fprintf(stderr,
"Interface %s is not UP. Try : ifup %s\n", interface, interface);
   113   if (!(ifr.ifr_flags & IFF_RUNNING)) {
   114     fprintf(stderr,
"Interface %s is not RUNNING. Is cable plugged in and device powered?\n", interface);
   121   if ((ni = init_ec(interface)) == NULL)
   123     fprintf(stderr, 
"Unable to initialize interface: %s\n", interface);
   128   EtherCAT_DataLinkLayer::instance()->attach(ni);
   130   if ((al = EtherCAT_AL::instance()) == NULL)
   132     fprintf(stderr, 
"Unable to initialize Application Layer (AL): %p\n", al);
   136   uint32_t num_slaves = al->get_num_slaves();
   139     fprintf(stderr, 
"Unable to locate any slaves\n");
   145   if ((em = EtherCAT_Master::instance()) == NULL)
   147     fprintf(stderr, 
"Unable to initialize EtherCAT_Master: %p", em);
   151   static int start_address = 0x00010000;
   153   for (
unsigned int slave = 0; slave < num_slaves; ++slave)
   155     EC_FixedStationAddress fsa(slave + 1);
   156     EtherCAT_SlaveHandler *sh = em->get_slave_handler(fsa);
   159       fprintf(stderr, 
"Unable to get slave handler #%d", slave);
   195     if (!device) 
continue;
   196     if (!device->
sh_->to_state(EC_OP_STATE))
   198       fprintf(stderr, 
"Unable set device %d into OP_STATE", device->
sh_->get_ring_position());
   204     if (!device) 
continue;
   212   if (dynamic_cast<WG021 *>(d)) {
   214   } 
else if (dynamic_cast<WG06 *>(d)) {
   216   } 
else if (dynamic_cast<WG05 *>(d)) {
   225   uint32_t num_slaves = EtherCAT_AL::instance()->get_num_slaves();
   226   if ((device >= (
int)num_slaves) || (device < 0)) 
   228     ROS_FATAL(
"Invalid device number %d.  Must be value between 0 and %d", device, num_slaves-1);
   234     ROS_FATAL(
"There is no device at position #%d", device);
   241     ROS_FATAL(
"The device a position #%d is not programmable", device);
   251                    char *name, 
string expected_board, 
bool enforce_heating_model)
   260   if (expected_board != board)
   262     ROS_FATAL(
"Device #%02d is a %s, but %s expects a %s\n", device, board.c_str(), name, expected_board.c_str());
   265   ROS_INFO(
"Programming device %d, to be named: %s\n", device, name);
   268   if (strlen(name) >= 
sizeof(actuator_info.
name_))
   270     ROS_FATAL(
"Device name '%s' is too long", name);
   272   strncpy(actuator_info.
name_, name, 
sizeof(actuator_info.
name_));
   275   ROS_INFO(
"Programming actuator version %d.%d", 
   279   if (!wg->
program(&com, actuator_info))
   281     ROS_FATAL(
"Error writing actuator info to device #%d", device);
   286   heating_config.
enforce_ = enforce_heating_model;
   290     ROS_FATAL(
"Writing heating model config to device #%d", device);
   308     ROS_WARN(
"Skipping update of device %d", device);      
   314     ROS_ERROR(
"Could not read actuator info from device %d", device);      
   320     ROS_ERROR(
"Device %d has not actuator configuration", device);
   326     ROS_ERROR(
"Could not find actuator info for device %d with name '%s'",
   327               device, actuator_info.
name_);
   332   const string &motor_name(actuator.
motor);
   337     ROS_ERROR(
"Could not find motor '%s' for device %d with actuator name '%s'",
   338               motor_name.c_str(), device, actuator_info.
name_);
   346     ROS_ERROR(
"For device %d '%s' : the motor name stored in EEPROM '%s' does not match the motor name '%s' from XML file", 
   352   heating_config.
enforce_ = enforce_heating_model;
   354   if (!wg->
program(&com, heating_config))
   356     ROS_FATAL(
"Writing heating model config to device #%d", device);
   360   ROS_INFO(
"Updated device %d (%s) with heating config for motor '%s'", 
   370   for (
unsigned device=0; device<
devices.size(); ++device)
   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");
   406     string name = p.first;
   407     fprintf(stderr, 
"        %s\n", name.c_str());
   409   fprintf(stderr, 
" -m, --motor <m>        Set the configuration for motor <m>\n");
   410   fprintf(stderr, 
"     Legal motor values are:\n");
   413     const string &name(p.first);
   417   fprintf(stderr, 
" -h, --help    Print this message and exit\n");
   420     fprintf(stderr, 
"Error: %s\n", 
msg.c_str());
   430 bool getDoubleAttribute(TiXmlElement *params, 
const char* motor_name, 
const char* param_name, 
double& value)
   432   const char *val_str = params->Attribute(param_name);
   435     ROS_ERROR(
"Attribute '%s' for motor '%s' is not defined", param_name, motor_name);
   440   value = strtod(val_str, &endptr);
   441   if ((endptr == val_str) || (endptr < (val_str+strlen(val_str))))
   443     ROS_ERROR(
"Couldn't convert '%s' to double for attribute '%s' of motor '%s'", 
   444               val_str, param_name, motor_name);
   451 bool getIntegerAttribute(TiXmlElement *params, 
const char* motor_name, 
const char* param_name, 
int& value)
   453   const char *val_str = params->Attribute(param_name);
   456     ROS_ERROR(
"Attribute '%s' for motor '%s' is not defined", param_name, motor_name);
   461   value = strtol(val_str, &endptr, 0);
   462   if ((endptr == val_str) || (endptr < (val_str+strlen(val_str))))
   464     ROS_ERROR(
"Couldn't convert '%s' to integer for attribute '%s' of motor '%s'", 
   465               val_str, param_name, motor_name);
   472 bool getStringAttribute(TiXmlElement *params, 
const char* motor_name, 
const char* param_name, 
char* strbuf, 
unsigned buflen)
   474   const char *val = params->Attribute(param_name);
   477     ROS_ERROR(
"No '%s' attribute for motor '%s'", param_name, motor_name);
   480   if (strlen(val) >= buflen)
   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);
   486   strncpy(strbuf, val, buflen);
   487   strbuf[buflen-1] = 
'\0';
   494   TiXmlElement *actuatorElt = config->FirstChildElement(
"actuators");
   495   TiXmlElement *motorElt = config->FirstChildElement(
"motors");
   497   for (TiXmlElement *elt = actuatorElt->FirstChildElement(
"actuator");
   499        elt = elt->NextSiblingElement(
"actuator"))
   501     const char *name = elt->Attribute(
"name");
   504       ROS_ERROR(
"Acutuator attribute 'name' not specified");
   510     const char *
motor = elt->Attribute(
"motor");
   513       ROS_ERROR(
"For actuator '%s', 'motor' attribute not specified", name);
   518     const char *
board = elt->Attribute(
"board");
   521       ROS_ERROR(
"For actuator '%s', 'board' attribute not specified", name);
   527     if (enforce_heating_model == NULL)
   533     else if (strcmp(enforce_heating_model, 
"true") == 0)
   537     else if (strcmp(enforce_heating_model, 
"false") == 0)
   543       ROS_ERROR(
"For actuator '%s' : 'enforce_heating_model' attribute should be 'true' or 'false' not '%s'",
   544                 name, enforce_heating_model);
   552   memset(&info, 0, 
sizeof(info));
   557   memset(&heating_config, 0, 
sizeof(heating_config));
   558   heating_config.
major_ = 0;
   559   heating_config.
minor_ = 1;
   562   for (TiXmlElement *elt = motorElt->FirstChildElement(
"motor");
   564        elt = elt->NextSiblingElement(
"motor"))
   567     const char *name = elt->Attribute(
"name");
   570       ROS_ERROR(
"Motor 'name' attribute is not specified");
   574     TiXmlElement *params = elt->FirstChildElement(
"params");
   577       ROS_ERROR(
"No 'params' tag available for motor '%s'", name);
   581     TiXmlElement *encoder = elt->FirstChildElement(
"encoder");
   584       ROS_ERROR(
"No 'encoder' tag available for motor '%s'", name);
   609     success &= 
getDoubleAttribute(params, name, 
"housing_to_ambient_thermal_resistance", fvalue);
   611     success &= 
getDoubleAttribute(params, name, 
"winding_to_housing_thermal_resistance", fvalue);
   627       ROS_ERROR(
"Motor named '%s' exists motor than once",name);
   639 int main(
int argc, 
char *argv[])
   653   g_options.update_motor_heating_config_ = 
false;
   654   g_options.enforce_heating_model_ = 
false;
   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'},
   669     int option_index = 0;
   670     int c = getopt_long(argc, argv, 
"d:b:hi:m:n:pa:UH", long_options, &option_index);
   699         g_options.update_motor_heating_config_ = 
true;
   708   string filename = 
"actuators.conf";
   711   TiXmlDocument xml(filename);
   715     Usage(
"Unable to load configuration file");
   729     Usage(
"Extra arguments");
   733     Usage(
"You must specify a network interface");
   736   int test_sock = socket(PF_PACKET, SOCK_RAW, htons(0x88A4));
   737   if ((test_sock < 0) && (errno == EPERM))
   739     ROS_FATAL(
"Insufficient priviledges to obtain raw socket.  Try running as root.");
   745   if (mlockall(MCL_CURRENT | MCL_FUTURE) != 0)
   747     ROS_WARN(
"mlockall failed : %s", strerror(errno));
   752   if (
g_options.update_motor_heating_config_)
   759     string board = 
"wg005";
   760     bool enforce_heating_model = 
false;
   762       Usage(
"You must specify a name");
   766         Usage(
"No default motor for this name");
   775       Usage(
"You must specify a device #");
   777       Usage(
"You must specify a valid motor");
   779       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