$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 #include <map> 00036 #include <stdio.h> 00037 #include <getopt.h> 00038 #include <sys/mman.h> 00039 00040 #include <tinyxml.h> 00041 00042 #include <ethercat/ethercat_xenomai_drv.h> 00043 #include <dll/ethercat_dll.h> 00044 #include <al/ethercat_AL.h> 00045 #include <al/ethercat_master.h> 00046 #include <al/ethercat_slave_handler.h> 00047 00048 #include "ethercat_hardware/motor_heating_model.h" 00049 #include <ethercat_hardware/wg0x.h> 00050 #include <ethercat_hardware/wg05.h> 00051 #include <ethercat_hardware/wg06.h> 00052 #include <ethercat_hardware/wg021.h> 00053 #include <ethercat_hardware/wg014.h> 00054 00055 #include <boost/crc.hpp> 00056 #include <boost/foreach.hpp> 00057 00058 #include <net/if.h> 00059 #include <sys/ioctl.h> 00060 #include <netinet/in.h> 00061 00062 using namespace ethercat_hardware; 00063 00064 vector<EthercatDevice *> devices; 00065 00066 struct Actuator { 00067 string motor; 00068 string board; 00069 bool enforce_heating_model; 00070 }; 00071 typedef pair<string, Actuator> ActuatorPair; 00072 map<string, Actuator> actuators; 00073 00074 struct Config 00075 { 00076 Config(const WG0XActuatorInfo &actuator_info, const MotorHeatingModelParametersEepromConfig &heating_config) : 00077 actuator_info_(actuator_info), heating_config_(heating_config) 00078 { } 00079 Config() {} 00080 WG0XActuatorInfo actuator_info_; 00081 MotorHeatingModelParametersEepromConfig heating_config_; 00082 }; 00083 typedef pair<string, Config> MotorPair; 00084 map<string, Config> motors; 00085 00086 void init(char *interface) 00087 { 00088 // open temporary socket to use with ioctl 00089 int sock = socket(PF_INET, SOCK_DGRAM, 0); 00090 if (sock < 0) { 00091 int error = errno; 00092 fprintf(stderr,"Couldn't open temp socket : %s", strerror(error)); 00093 exit(-1); 00094 } 00095 00096 struct ifreq ifr; 00097 strncpy(ifr.ifr_name, interface, IFNAMSIZ); 00098 if (ioctl(sock, SIOCGIFFLAGS, &ifr) < 0) { 00099 int error = errno; 00100 fprintf(stderr,"Cannot get interface flags for %s: %s\n", interface, strerror(error)); 00101 exit(-1); 00102 } 00103 00104 close(sock); 00105 sock = -1; 00106 00107 if (!(ifr.ifr_flags & IFF_UP)) { 00108 fprintf(stderr,"Interface %s is not UP. Try : ifup %s\n", interface, interface); 00109 exit(-1); 00110 } 00111 if (!(ifr.ifr_flags & IFF_RUNNING)) { 00112 fprintf(stderr,"Interface %s is not RUNNING. Is cable plugged in and device powered?\n", interface); 00113 exit(-1); 00114 } 00115 00116 struct netif *ni; 00117 00118 // Initialize network interface 00119 if ((ni = init_ec(interface)) == NULL) 00120 { 00121 fprintf(stderr, "Unable to initialize interface: %s\n", interface); 00122 exit(-1); 00123 } 00124 00125 // Initialize Application Layer (AL) 00126 EtherCAT_DataLinkLayer::instance()->attach(ni); 00127 EtherCAT_AL *al; 00128 if ((al = EtherCAT_AL::instance()) == NULL) 00129 { 00130 fprintf(stderr, "Unable to initialize Application Layer (AL): %p\n", al); 00131 exit(-1); 00132 } 00133 00134 uint32_t num_slaves = al->get_num_slaves(); 00135 if (num_slaves == 0) 00136 { 00137 fprintf(stderr, "Unable to locate any slaves\n"); 00138 exit(-1); 00139 } 00140 00141 // Initialize Master 00142 EtherCAT_Master *em; 00143 if ((em = EtherCAT_Master::instance()) == NULL) 00144 { 00145 fprintf(stderr, "Unable to initialize EtherCAT_Master: %p", em); 00146 exit(-1); 00147 } 00148 00149 static int start_address = 0x00010000; 00150 00151 for (unsigned int slave = 0; slave < num_slaves; ++slave) 00152 { 00153 EC_FixedStationAddress fsa(slave + 1); 00154 EtherCAT_SlaveHandler *sh = em->get_slave_handler(fsa); 00155 if (sh == NULL) 00156 { 00157 fprintf(stderr, "Unable to get slave handler #%d", slave); 00158 exit(-1); 00159 } 00160 00161 if (sh->get_product_code() == WG05::PRODUCT_CODE) 00162 { 00163 WG05 *dev = new WG05(); 00164 dev->construct(sh, start_address); 00165 devices.push_back(dev); 00166 } 00167 else if (sh->get_product_code() == WG06::PRODUCT_CODE) 00168 { 00169 WG06 *dev = new WG06(); 00170 dev->construct(sh, start_address); 00171 devices.push_back(dev); 00172 } 00173 else if (sh->get_product_code() == WG021::PRODUCT_CODE) 00174 { 00175 WG021 *dev = new WG021(); 00176 dev->construct(sh, start_address); 00177 devices.push_back(dev); 00178 } 00179 else if (sh->get_product_code() == WG014::PRODUCT_CODE) 00180 { 00181 WG014 *dev = new WG014(); 00182 dev->construct(sh, start_address); 00183 devices.push_back(dev); 00184 } 00185 else 00186 { 00187 devices.push_back(NULL); 00188 } 00189 } 00190 00191 BOOST_FOREACH(EthercatDevice *device, devices) 00192 { 00193 if (!device) continue; 00194 if (!device->sh_->to_state(EC_OP_STATE)) 00195 { 00196 fprintf(stderr, "Unable set device %d into OP_STATE", device->sh_->get_ring_position()); 00197 } 00198 } 00199 00200 BOOST_FOREACH(EthercatDevice *device, devices) 00201 { 00202 if (!device) continue; 00203 device->use_ros_ = false; 00204 device->initialize(NULL, true); 00205 } 00206 } 00207 00208 string boardName(EthercatDevice *d) 00209 { 00210 if (dynamic_cast<WG021 *>(d)) { 00211 return "wg021"; 00212 } else if (dynamic_cast<WG06 *>(d)) { 00213 return "wg006"; 00214 } else if (dynamic_cast<WG05 *>(d)) { 00215 return "wg005"; 00216 } 00217 return "unknown"; 00218 } 00219 00220 00221 WG0X* getWGDevice(int device) 00222 { 00223 uint32_t num_slaves = EtherCAT_AL::instance()->get_num_slaves(); 00224 if ((device >= (int)num_slaves) || (device < 0)) 00225 { 00226 ROS_FATAL("Invalid device number %d. Must be value between 0 and %d", device, num_slaves-1); 00227 return NULL; 00228 } 00229 00230 if (devices[device] == NULL) 00231 { 00232 ROS_FATAL("There is no device at position #%d", device); 00233 return NULL; 00234 } 00235 00236 WG0X *wg = dynamic_cast<WG0X *>(devices[device]); 00237 if (wg==NULL) 00238 { 00239 ROS_FATAL("The device a position #%d is not programmable", device); 00240 return NULL; 00241 } 00242 00243 return wg; 00244 } 00245 00246 00247 bool programDevice(int device, 00248 const Config &config, 00249 char *name, string expected_board, bool enforce_heating_model) 00250 { 00251 WG0X *wg = getWGDevice(device); 00252 if (wg == NULL) 00253 { 00254 return false; 00255 } 00256 00257 string board = boardName(devices[device]); 00258 if (expected_board != board) 00259 { 00260 ROS_FATAL("Device #%02d is a %s, but %s expects a %s\n", device, board.c_str(), name, expected_board.c_str()); 00261 return false; 00262 } 00263 ROS_INFO("Programming device %d, to be named: %s\n", device, name); 00264 00265 WG0XActuatorInfo actuator_info = config.actuator_info_; 00266 if (strlen(name) >= sizeof(actuator_info.name_)) 00267 { 00268 ROS_FATAL("Device name '%s' is too long", name); 00269 } 00270 strncpy(actuator_info.name_, name, sizeof(actuator_info.name_)); 00271 actuator_info.generateCRC(); 00272 00273 ROS_INFO("Programming actuator version %d.%d", 00274 int(actuator_info.major_), int(actuator_info.minor_)); 00275 00276 EthercatDirectCom com(EtherCAT_DataLinkLayer::instance()); 00277 if (!wg->program(&com, actuator_info)) 00278 { 00279 ROS_FATAL("Error writing actuator info to device #%d", device); 00280 return false; 00281 } 00282 00283 MotorHeatingModelParametersEepromConfig heating_config = config.heating_config_; 00284 heating_config.enforce_ = enforce_heating_model; 00285 heating_config.generateCRC(); 00286 if (!wg->program(&com, config.heating_config_)) 00287 { 00288 ROS_FATAL("Writing heating model config to device #%d", device); 00289 return false; 00290 } 00291 00292 return true; 00293 } 00294 00295 00296 // Uses ActuatorInfo name already stored in device 00297 // to find appropriate motor heating model config 00298 // Then only updates motor heating model config 00299 bool updateHeatingConfig(int device) 00300 { 00301 WG0XActuatorInfo actuator_info; 00302 EthercatDirectCom com(EtherCAT_DataLinkLayer::instance()); 00303 WG0X *wg = getWGDevice(device); 00304 if (wg == NULL) 00305 { 00306 ROS_WARN("Skipping update of device %d", device); 00307 return false; 00308 } 00309 00310 if (!wg->readActuatorInfoFromEeprom(&com, actuator_info)) 00311 { 00312 ROS_ERROR("Could not read actuator info from device %d", device); 00313 return false; 00314 } 00315 00316 if (!actuator_info.verifyCRC()) 00317 { 00318 ROS_ERROR("Device %d has not actuator configuration", device); 00319 return false; 00320 } 00321 00322 if (actuators.find(actuator_info.name_) == actuators.end()) 00323 { 00324 ROS_ERROR("Could not find actuator info for device %d with name '%s'", 00325 device, actuator_info.name_); 00326 return false; 00327 } 00328 00329 const Actuator &actuator(actuators[actuator_info.name_]); 00330 const string &motor_name(actuator.motor); 00331 bool enforce_heating_model = actuator.enforce_heating_model; 00332 00333 if (motors.find(motor_name) == motors.end()) 00334 { 00335 ROS_ERROR("Could not find motor '%s' for device %d with actuator name '%s'", 00336 motor_name.c_str(), device, actuator_info.name_); 00337 return false; 00338 } 00339 00340 const Config &config(motors[motor_name]); 00341 00342 if (strcmp(config.actuator_info_.motor_model_, actuator_info.motor_model_) != 0) 00343 { 00344 ROS_ERROR("For device %d '%s' : the motor name stored in EEPROM '%s' does not match the motor name '%s' from XML file", 00345 device, actuator_info.name_, actuator_info.motor_model_, config.actuator_info_.motor_model_); 00346 return false; 00347 } 00348 00349 MotorHeatingModelParametersEepromConfig heating_config = config.heating_config_; 00350 heating_config.enforce_ = enforce_heating_model; 00351 heating_config.generateCRC(); 00352 if (!wg->program(&com, heating_config)) 00353 { 00354 ROS_FATAL("Writing heating model config to device #%d", device); 00355 return false; 00356 } 00357 00358 ROS_INFO("Updated device %d (%s) with heating config for motor '%s'", 00359 device, actuator_info.name_, config.actuator_info_.motor_model_); 00360 00361 return true; 00362 } 00363 00364 00365 // Updates heating configuration of all devices 00366 bool updateAllHeatingConfig() 00367 { 00368 for (unsigned device=0; device<devices.size(); ++device) 00369 { 00370 updateHeatingConfig(device); 00371 } 00372 return true; 00373 } 00374 00375 00376 static struct 00377 { 00378 char *program_name_; 00379 char *interface_; 00380 char *name_; 00381 bool program_; 00382 bool help_; 00383 int device_; 00384 string motor_; 00385 string actuators_; 00386 string board_; 00387 bool update_motor_heating_config_; 00388 bool enforce_heating_model_; 00389 } g_options; 00390 00391 void Usage(string msg = "") 00392 { 00393 fprintf(stderr, "Usage: %s [options]\n", g_options.program_name_); 00394 fprintf(stderr, " -i, --interface <i> Use the network interface <i>\n"); 00395 fprintf(stderr, " -a, --actuators <file> Get the actuator definitions from file (default: actuators.conf)\n"); 00396 fprintf(stderr, " -d, --device <d> Select the device to program\n"); 00397 fprintf(stderr, " -b, --board <b> Set the expected board type (wg005, wg006, wg021)\n"); 00398 fprintf(stderr, " -p, --program Program a motor control board\n"); 00399 fprintf(stderr, " -n, --name <n> Set the name of the motor control board to <n>\n"); 00400 fprintf(stderr, " -U, --update_heating_config Update motor heating model configuration of all boards\n"); 00401 fprintf(stderr, " Known actuator names:\n"); 00402 BOOST_FOREACH(ActuatorPair p, actuators) 00403 { 00404 string name = p.first; 00405 fprintf(stderr, " %s\n", name.c_str()); 00406 } 00407 fprintf(stderr, " -m, --motor <m> Set the configuration for motor <m>\n"); 00408 fprintf(stderr, " Legal motor values are:\n"); 00409 BOOST_FOREACH(MotorPair p, motors) 00410 { 00411 const string &name(p.first); 00412 const WG0XActuatorInfo &info(p.second.actuator_info_); 00413 fprintf(stderr, " %s - %s %s\n", name.c_str(), info.motor_make_, info.motor_model_); 00414 } 00415 fprintf(stderr, " -h, --help Print this message and exit\n"); 00416 if (msg != "") 00417 { 00418 fprintf(stderr, "Error: %s\n", msg.c_str()); 00419 exit(-1); 00420 } 00421 else 00422 { 00423 exit(0); 00424 } 00425 } 00426 00427 00428 bool getDoubleAttribute(TiXmlElement *params, const char* motor_name, const char* param_name, double& value) 00429 { 00430 const char *val_str = params->Attribute(param_name); 00431 if (val_str == NULL) 00432 { 00433 ROS_ERROR("Attribute '%s' for motor '%s' is not defined", param_name, motor_name); 00434 return false; 00435 } 00436 00437 char *endptr=NULL; 00438 value = strtod(val_str, &endptr); 00439 if ((endptr == val_str) || (endptr < (val_str+strlen(val_str)))) 00440 { 00441 ROS_ERROR("Couldn't convert '%s' to double for attribute '%s' of motor '%s'", 00442 val_str, param_name, motor_name); 00443 return false; 00444 } 00445 00446 return true; 00447 } 00448 00449 bool getIntegerAttribute(TiXmlElement *params, const char* motor_name, const char* param_name, int& value) 00450 { 00451 const char *val_str = params->Attribute(param_name); 00452 if (val_str == NULL) 00453 { 00454 ROS_ERROR("Attribute '%s' for motor '%s' is not defined", param_name, motor_name); 00455 return false; 00456 } 00457 00458 char *endptr=NULL; 00459 value = strtol(val_str, &endptr, 0); 00460 if ((endptr == val_str) || (endptr < (val_str+strlen(val_str)))) 00461 { 00462 ROS_ERROR("Couldn't convert '%s' to integer for attribute '%s' of motor '%s'", 00463 val_str, param_name, motor_name); 00464 return false; 00465 } 00466 00467 return true; 00468 } 00469 00470 bool getStringAttribute(TiXmlElement *params, const char* motor_name, const char* param_name, char* strbuf, unsigned buflen) 00471 { 00472 const char *val = params->Attribute(param_name); 00473 if (val == NULL) 00474 { 00475 ROS_ERROR("No '%s' attribute for motor '%s'", param_name, motor_name); 00476 return false; 00477 } 00478 if (strlen(val) >= buflen) 00479 { 00480 ROS_ERROR("'%s' value '%s' for motor '%s' is too long. Limit value to %d characters.", 00481 param_name, val, motor_name, buflen-1); 00482 return false; 00483 } 00484 strncpy(strbuf, val, buflen); 00485 strbuf[buflen-1] = '\0'; 00486 return true; 00487 } 00488 00489 00490 bool parseConfig(TiXmlElement *config) 00491 { 00492 TiXmlElement *actuatorElt = config->FirstChildElement("actuators"); 00493 TiXmlElement *motorElt = config->FirstChildElement("motors"); 00494 00495 for (TiXmlElement *elt = actuatorElt->FirstChildElement("actuator"); 00496 elt; 00497 elt = elt->NextSiblingElement("actuator")) 00498 { 00499 const char *name = elt->Attribute("name"); 00500 if (name == NULL) 00501 { 00502 ROS_ERROR("Acutuator attribute 'name' not specified"); 00503 return false; 00504 } 00505 00506 struct Actuator a; 00507 00508 const char *motor = elt->Attribute("motor"); 00509 if (motor == NULL) 00510 { 00511 ROS_ERROR("For actuator '%s', 'motor' attribute not specified", name); 00512 return false; 00513 } 00514 a.motor = motor; 00515 00516 const char *board = elt->Attribute("board"); 00517 if (board == NULL) 00518 { 00519 ROS_ERROR("For actuator '%s', 'board' attribute not specified", name); 00520 return false; 00521 } 00522 a.board = board; 00523 00524 const char *enforce_heating_model = elt->Attribute("enforce_heating_model"); 00525 if (enforce_heating_model == NULL) 00526 { 00527 // ROS_ERROR("For actuator '%s', 'enforce_heating_model' attribute not specified", name); 00528 //return false; 00529 a.enforce_heating_model=false; 00530 } 00531 else if (strcmp(enforce_heating_model, "true") == 0) 00532 { 00533 a.enforce_heating_model=true; 00534 } 00535 else if (strcmp(enforce_heating_model, "false") == 0) 00536 { 00537 a.enforce_heating_model=false; 00538 } 00539 else 00540 { 00541 ROS_ERROR("For actuator '%s' : 'enforce_heating_model' attribute should be 'true' or 'false' not '%s'", 00542 name, enforce_heating_model); 00543 return false; 00544 } 00545 00546 actuators[name] = a; 00547 } 00548 00549 WG0XActuatorInfo info; 00550 memset(&info, 0, sizeof(info)); 00551 info.major_ = 0; 00552 info.minor_ = 2; 00553 strcpy(info.robot_name_, "PR2"); 00554 ethercat_hardware::MotorHeatingModelParametersEepromConfig heating_config; 00555 memset(&heating_config, 0, sizeof(heating_config)); 00556 heating_config.major_ = 0; 00557 heating_config.minor_ = 1; 00558 heating_config.enforce_ = 0; // default, don't enforce heating model 00559 00560 for (TiXmlElement *elt = motorElt->FirstChildElement("motor"); 00561 elt; 00562 elt = elt->NextSiblingElement("motor")) 00563 { 00564 bool success = true; 00565 const char *name = elt->Attribute("name"); 00566 if (name == NULL) 00567 { 00568 ROS_ERROR("Motor 'name' attribute is not specified"); 00569 return false; 00570 } 00571 00572 TiXmlElement *params = elt->FirstChildElement("params"); 00573 if (params == NULL) 00574 { 00575 ROS_ERROR("No 'params' tag available for motor '%s'", name); 00576 return false; 00577 } 00578 00579 TiXmlElement *encoder = elt->FirstChildElement("encoder"); 00580 if (encoder == NULL) 00581 { 00582 ROS_ERROR("No 'encoder' tag available for motor '%s'", name); 00583 return false; 00584 } 00585 00586 success &= getStringAttribute(params, name, "make", info.motor_make_, sizeof(info.motor_make_)); 00587 success &= getStringAttribute(params, name, "model", info.motor_model_, sizeof(info.motor_model_)); 00588 00589 double fvalue; 00590 00591 success &= getDoubleAttribute(params, name, "max_current", fvalue); 00592 info.max_current_ = fvalue; 00593 success &= getDoubleAttribute(params, name, "speed_constant", fvalue); 00594 info.speed_constant_ = fvalue; 00595 success &= getDoubleAttribute(params, name, "resistance", fvalue); 00596 info.resistance_ = fvalue; 00597 success &= getDoubleAttribute(params, name, "motor_torque_constant", fvalue); 00598 info.motor_torque_constant_ = fvalue; 00599 success &= getDoubleAttribute(encoder, name, "reduction", fvalue); 00600 info.encoder_reduction_ = fvalue; 00601 00602 int ivalue=-1; 00603 success &= getIntegerAttribute(encoder, name, "pulses_per_revolution", ivalue); 00604 info.pulses_per_revolution_ = ivalue; 00605 00606 ethercat_hardware::MotorHeatingModelParameters &hmp(heating_config.params_); 00607 success &= getDoubleAttribute(params, name, "housing_to_ambient_thermal_resistance", fvalue); 00608 hmp.housing_to_ambient_thermal_resistance_ = fvalue; 00609 success &= getDoubleAttribute(params, name, "winding_to_housing_thermal_resistance", fvalue); 00610 hmp.winding_to_housing_thermal_resistance_ = fvalue; 00611 success &= getDoubleAttribute(params, name, "winding_thermal_time_constant", fvalue); 00612 hmp.winding_thermal_time_constant_ = fvalue; 00613 success &= getDoubleAttribute(params, name, "housing_thermal_time_constant", fvalue); 00614 hmp.housing_thermal_time_constant_ = fvalue; 00615 success &= getDoubleAttribute(params, name, "max_winding_temperature", fvalue); 00616 hmp.max_winding_temperature_ = fvalue; 00617 00618 if (!success) 00619 { 00620 return false; 00621 } 00622 00623 if (motors.find(name) != motors.end()) 00624 { 00625 ROS_ERROR("Motor named '%s' exists motor than once",name); 00626 return false; 00627 } 00628 00629 motors[name] = Config(info, heating_config); 00630 } 00631 return true; 00632 } 00633 00634 00635 00636 00637 int main(int argc, char *argv[]) 00638 { 00639 00640 // Set log level to DEBUG to allow device information to be displayed to 00641 // output by default 00642 log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME); 00643 logger->setLevel(ros::console::g_level_lookup[ros::console::levels::Debug]); 00644 ros::console::notifyLoggerLevelsChanged(); 00645 00646 // Parse options 00647 g_options.program_name_ = argv[0]; 00648 g_options.device_ = -1; 00649 g_options.help_ = false; 00650 g_options.board_ = ""; 00651 g_options.update_motor_heating_config_ = false; 00652 g_options.enforce_heating_model_ = false; 00653 while (1) 00654 { 00655 static struct option long_options[] = { 00656 {"help", no_argument, 0, 'h'}, 00657 {"interface", required_argument, 0, 'i'}, 00658 {"name", required_argument, 0, 'n'}, 00659 {"device", required_argument, 0, 'd'}, 00660 {"board", required_argument, 0, 'b'}, 00661 {"motor", required_argument, 0, 'm'}, 00662 {"program", no_argument, 0, 'p'}, 00663 {"actuators", required_argument, 0, 'a'}, 00664 {"update_heating_config", no_argument, 0, 'U'}, 00665 {"enforce_heating_model", no_argument, 0, 'H'}, 00666 }; 00667 int option_index = 0; 00668 int c = getopt_long(argc, argv, "d:b:hi:m:n:pa:UH", long_options, &option_index); 00669 if (c == -1) break; 00670 switch (c) 00671 { 00672 case 'h': 00673 g_options.help_ = true; 00674 break; 00675 case 'd': 00676 g_options.device_ = atoi(optarg); 00677 break; 00678 case 'b': 00679 g_options.board_ = optarg; 00680 break; 00681 case 'i': 00682 g_options.interface_ = optarg; 00683 break; 00684 case 'n': 00685 g_options.name_ = optarg; 00686 break; 00687 case 'm': 00688 g_options.motor_ = optarg; 00689 break; 00690 case 'p': 00691 g_options.program_ = 1; 00692 break; 00693 case 'a': 00694 g_options.actuators_ = optarg; 00695 break; 00696 case 'U': 00697 g_options.update_motor_heating_config_ = true; 00698 break; 00699 case 'H': 00700 g_options.enforce_heating_model_ = true; 00701 break; 00702 } 00703 } 00704 00705 // Parse configuration file 00706 string filename = "actuators.conf"; 00707 if (g_options.actuators_ != "") 00708 filename = g_options.actuators_; 00709 TiXmlDocument xml(filename); 00710 00711 if (!xml.LoadFile()) 00712 { 00713 Usage("Unable to load configuration file"); 00714 } 00715 00716 00717 if (!parseConfig(xml.RootElement())) 00718 { 00719 exit(EXIT_FAILURE); 00720 } 00721 00722 if (g_options.help_) 00723 Usage(); 00724 00725 if (optind < argc) 00726 { 00727 Usage("Extra arguments"); 00728 } 00729 00730 if (!g_options.interface_) 00731 Usage("You must specify a network interface"); 00732 00733 // Try to get a raw socket. 00734 int test_sock = socket(PF_PACKET, SOCK_RAW, htons(0x88A4)); 00735 if ((test_sock < 0) && (errno == EPERM)) 00736 { 00737 ROS_FATAL("Insufficient priviledges to obtain raw socket. Try running as root."); 00738 exit(-1); 00739 } 00740 close(test_sock); 00741 00742 // Keep the kernel from swapping us out 00743 if (mlockall(MCL_CURRENT | MCL_FUTURE) != 0) 00744 { 00745 ROS_WARN("mlockall failed : %s", strerror(errno)); 00746 } 00747 00748 init(g_options.interface_); 00749 00750 if (g_options.update_motor_heating_config_) 00751 { 00752 updateAllHeatingConfig(); 00753 } 00754 00755 if (g_options.program_) 00756 { 00757 string board = "wg005"; 00758 bool enforce_heating_model = false; 00759 if (!g_options.name_) 00760 Usage("You must specify a name"); 00761 if (g_options.motor_ == "") 00762 { 00763 if (actuators.find(g_options.name_) == actuators.end()) 00764 Usage("No default motor for this name"); 00765 g_options.motor_ = actuators[g_options.name_].motor; 00766 board = actuators[g_options.name_].board; 00767 enforce_heating_model = actuators[g_options.name_].enforce_heating_model; 00768 } 00769 if (g_options.board_ != "") { 00770 board = g_options.board_; 00771 } 00772 if (g_options.device_ == -1) 00773 Usage("You must specify a device #"); 00774 if (motors.find(g_options.motor_) == motors.end()) 00775 Usage("You must specify a valid motor"); 00776 if (g_options.enforce_heating_model_) 00777 enforce_heating_model = true; 00778 00779 programDevice(g_options.device_, motors[g_options.motor_], g_options.name_, board, enforce_heating_model); 00780 } 00781 00782 return 0; 00783 } 00784 00785