$search
00001 /* 00002 * Description: Throttle servo controller. 00003 * 00004 * Copyright (C) 2007, 2009 Austin Robot Technology 00005 * 00006 * License: Modified BSD Software License Agreement 00007 * 00008 * $Id: devthrottle.cc 1877 2011-11-27 00:07:20Z jack.oquin $ 00009 */ 00010 00011 extern "C" { 00012 #include <string.h> 00013 #include <errno.h> 00014 #include <ctype.h> 00015 } 00016 00017 #include <poll.h> 00018 #include "devthrottle.h" 00019 00027 #define CLASS "devthrottle" 00028 #define DEVICE "Throttle" 00029 00031 // public methods 00033 00035 // Get the time (in ms) 00036 // 00037 int64_t devthrottle::GetTime() 00038 { 00039 ros::Time t = ros::Time::now(); 00040 return (int64_t) t.sec * 1000 + (int64_t) t.nsec / 1000000; 00041 } 00042 00043 devthrottle::devthrottle(bool train) 00044 { 00045 training = train; 00046 already_configured = false; 00047 last_req = cur_position = 0.0; 00048 cmd_p = (uint8_t *) &cmd; 00049 resp_p = (uint8_t *) &resp; 00050 memset(&stat, 0, sizeof(stat)); 00051 00052 // Set throttle parameters -- make sure the defaults won't overrev 00053 // the engine. These values will be used for /dev/null, in training 00054 // mode, or in case of failure. They may be updated later if 00055 // calibration changes are detected. 00056 00057 // use private node handle to get parameters 00058 ros::NodeHandle mynh("~"); 00059 00060 throttle_limit = 0.40; 00061 mynh.getParam("throttle_limit", throttle_limit); 00062 rpm_redline = 2750.0; 00063 mynh.getParam("rpm_redline", rpm_redline); 00064 ROS_INFO("throttle_limit %.f %%, rpm_redline %.f", 00065 throttle_limit*100.0, rpm_redline); 00066 00067 // AVR controller parameters 00068 avr_pos_max = 204.0; 00069 mynh.getParam("avr_pos_max", avr_pos_max); 00070 avr_pos_min = 31; 00071 mynh.getParam("avr_pos_min_est", avr_pos_min); 00072 avr_pos_range = avr_pos_max - avr_pos_min; 00073 avr_pos_epsilon = 1; 00074 mynh.getParam("avr_pos_epsilon", avr_pos_epsilon); 00075 avr_out_max = 1023; 00076 mynh.getParam("avr_out_max", avr_out_max); 00077 ROS_INFO("AVR max, estimated min, max output, epsilon: %.1f, %d, %d, %d", 00078 avr_pos_max, avr_pos_min, avr_out_max, avr_pos_epsilon); 00079 00080 // get PID parameters for controller 00081 double throttle_kp = 512.0; 00082 mynh.getParam("pid/p", throttle_kp); 00083 double throttle_ki = 0.04; 00084 mynh.getParam("pid/i", throttle_ki); 00085 double throttle_kd = 64.0; 00086 mynh.getParam("pid/d", throttle_kd); 00087 ROS_INFO("throttle ctlr PID gains (%.3f, %.3f, %.3f)", 00088 throttle_kp, throttle_ki, throttle_kd); 00089 00090 // translate PID values into AVR controller encodings 00091 avr_kp = (int) (throttle_kp * 256.0); 00092 avr_ki = (int) (throttle_ki * 256.0); 00093 avr_kd = (int) (throttle_kd * 256.0); 00094 } 00095 00096 00097 int devthrottle::Open(const char *device) 00098 { 00099 int rc; 00100 memset(&stat, 0, sizeof(stat)); // clear status response 00101 00102 rc = this->Servo::Open(device, (O_RDWR|O_NOCTTY|O_NDELAY|O_NONBLOCK)); 00103 if (rc != 0) return rc; // Open() failed 00104 00105 rc = this->configure_raw_port(B115200 | CS8, 0); 00106 if (rc != 0) goto fail; 00107 00108 // no need to configure or calibrate throttle if already done or 00109 // when in training mode 00110 if (already_configured || training) return 0; 00111 00112 rc = configure_controller(); 00113 if (rc != 0) goto fail; 00114 00115 if (have_tty) 00116 { 00117 rc = calibrate_idle(); 00118 if (rc != 0) goto fail; 00119 } 00120 00121 rc = throttle_absolute(0.0); // go to idle position 00122 if (rc != 0) goto fail; 00123 00124 already_configured = true; 00125 00126 return 0; // successful Open() 00127 00128 fail: 00129 this->Servo::Close(); 00130 return rc; // Open() failed 00131 } 00132 00133 int devthrottle::Close(void) 00134 { 00135 throttle_absolute(0.0); // go to idle position 00136 return this->Servo::Close(); 00137 } 00138 00139 bool devthrottle::query_estop(void) 00140 { 00141 return (avr_get_estop(&stat) != 0); 00142 } 00143 00144 int devthrottle::query_pid(float *pwm, float *dstate, float *istate) 00145 { 00146 if (avr_get_len(&stat) < avr_offset(data.status.pwm_count)) 00147 return EAGAIN; // no PID data available 00148 00149 // packet has PID data, unpack it 00150 uint8_t direction = avr_get_direction(&stat); 00151 *dstate = avr_get_dstate(&stat); 00152 *istate = avr_get_istate(&stat); 00153 *pwm = avr_get_pwm(&stat); 00154 00155 ROS_DEBUG(CLASS ": throttle PID status: dir=%u ds=%.f, is=%.f pwm=%.f", 00156 direction, *dstate, *istate, *pwm); 00157 00158 if (direction == 0) // motor reversing? 00159 *pwm = - *pwm; 00160 00161 return 0; 00162 } 00163 00164 int devthrottle::query_rpms(float *data) 00165 { 00166 if (avr_get_rvld(&stat) != 0) // no RPM data? 00167 return EAGAIN; 00168 00169 *data = avr_get_rpms(&stat); 00170 ROS_DEBUG(DEVICE " engine speed = %.f RPM", *data); 00171 return 0; 00172 } 00173 00174 // query throttle controller status 00175 // 00176 // updates cur_position to best available estimate 00177 // 00178 // returns: 0 if successful, updating stat 00179 // nonzero otherwise, stat unchanged 00180 int devthrottle::query_status() 00181 { 00182 int rc = send_cmd(STATUS_CMD); 00183 if (have_tty && rc == 0) 00184 { 00185 ROS_DEBUG(DEVICE " status: [G%d P%d R%d E%d]", 00186 avr_get_gen(&resp), avr_get_pvld(&resp), 00187 avr_get_rvld(&resp), avr_get_estop(&resp)); 00188 if (avr_get_gen(&resp) == 0) // general status error? 00189 { 00190 ROS_WARN(DEVICE " reports general error status 0x%x", 00191 avr_get_diag(&resp)); 00192 } 00193 stat = resp; // save STATUS response 00194 } 00195 00196 cur_position = last_req; // good approximation 00197 00198 // Use actual throttle position, if valid 00199 if (have_tty && avr_get_pvld(&stat)) 00200 { 00201 int avr_pos = avr_get_pos(&stat); 00202 00203 ROS_DEBUG(CLASS ": AVR throttle position = %d", avr_pos); 00204 00205 // check that throttle position sensor is really working 00206 if (avr_pos > AVR_POS_ABSURD) // throttle sensor working? 00207 cur_position = avr2pos(avr_pos); 00208 else 00209 { 00210 ROS_ERROR(CLASS ": AVR throttle sensor failure!"); 00211 rc = EBUSY; // device not responding 00212 } 00213 } 00214 00215 return rc; 00216 } 00217 00218 int devthrottle::throttle_absolute(float position) 00219 { 00220 DBG("throttle_absolute(%.3f)", position); 00221 last_req = limit_travel(position); 00223 ROS_DEBUG("requesting throttle position %.3f", last_req); 00224 return send_goto(pos2avr(last_req)); 00225 } 00226 00227 int devthrottle::throttle_relative(float delta) 00228 { 00229 DBG("throttle_relative(%.3f)", delta); 00230 return throttle_absolute(cur_position + delta); 00231 } 00232 00233 00235 // private methods 00237 00238 // determine current actual idle throttle position (SLOWLY) 00239 // 00240 // - for use only during Open(). 00241 // 00242 // returns: 0 if successful, updating avr_pos_min and avr_pos_range 00243 // nonzero if failure, causing the Open() to fail 00244 int devthrottle::calibrate_idle(void) 00245 { 00246 int actual_pos_min = (int) rintf(avr_pos_max); // start with a high value 00247 00248 int rc = send_goto(0); // set idle throttle 00249 if (rc != 0) return rc; 00250 cur_position = last_req = 0.0; 00251 00252 int prev_pos = -(avr_pos_epsilon*2); // significantly below zero 00253 for (;;) // loop until position settles 00254 { 00255 rc = send_cmd(STATUS_CMD); 00256 if ((rc != 0) || !avr_get_pvld(&resp)) 00257 { 00258 if (rc == 0) rc = ENODEV; 00259 ROS_ERROR(DEVICE " calibration failed! (%s)", 00260 strerror(rc)); 00261 return rc; 00262 } 00263 00264 int cur_pos = resp.data.status.pos; // current sensor reading 00265 00266 // Once in a while, the sensor returns a bogus value. Only 00267 // consider cur_pos to be valid when it is within epsilon of the 00268 // previous reading. This indicates the throttle has settled to 00269 // a stable, achievable value. 00270 if (abs(cur_pos - prev_pos) <= avr_pos_epsilon) 00271 { 00272 if (cur_pos <= AVR_POS_ABSURD) 00273 { 00274 ROS_ERROR(DEVICE " position sensor failure: %d", 00275 cur_pos); 00276 return ENODEV; 00277 } 00278 00279 if (cur_pos < actual_pos_min) 00280 { 00281 actual_pos_min = cur_pos; 00282 ROS_DEBUG(DEVICE " intermediate avr_pos_min value: %d\n", cur_pos); 00283 } 00284 else if (cur_pos < actual_pos_min + avr_pos_epsilon) 00285 { 00286 // This is close enough to the achievable min. While 00287 // updating the class variables, add epsilon to the 00288 // computed pos min so the motor need not work to 00289 // maintain an idle setting. Tell the controller what 00290 // we discovered. 00291 // (EXPERIMENTAL: try not adding epsilon to idle speed) 00292 //avr_pos_min = actual_pos_min + avr_pos_epsilon; 00293 avr_pos_min = actual_pos_min; 00294 avr_pos_range = avr_pos_max - avr_pos_min; 00295 ROS_DEBUG(DEVICE " actual avr_pos_min = %d\n", avr_pos_min); 00296 send_cmd08(SET_IDLE_CMD, avr_pos_min); 00297 return 0; 00298 } 00299 } 00300 00301 usleep(50000); // wait 50 milliseconds 00302 prev_pos = cur_pos; 00303 } 00304 } 00305 00306 // utility adapted from art_command_protocol.c (in firmware) 00307 // (len parm should not include the final csum byte) 00308 uint8_t devthrottle::cmd_compute_csum(uint8_t *buffer, int len) 00309 { 00310 int raw_sum = 0; 00311 int index; 00312 uint8_t csum; 00313 00314 for (index=0; index < len; index++) { 00315 raw_sum += buffer[index]; 00316 } 00317 00318 csum = (uint8_t) (raw_sum & 0xff); 00319 return -csum; 00320 } 00321 00322 // configure the throttle controller 00323 int devthrottle::configure_controller() 00324 { 00325 // make sure controller is not in CLI mode 00326 int rc = send_cmd08(CLI_SET_CMD, 0); 00327 if (rc != 0) return rc; 00328 00329 // send PID parameters to controller 00330 rc = send_cmd32(PID_KP_CMD, avr_kp); 00331 if (rc != 0) return rc; 00332 rc = send_cmd32(PID_KI_CMD, avr_ki); 00333 if (rc != 0) return rc; 00334 rc = send_cmd32(PID_KD_CMD, avr_kd); 00335 if (rc != 0) return rc; 00336 rc = send_cmd16(PID_LIMITS_CMD, avr_out_max); 00337 00338 return rc; 00339 } 00340 00341 // hex conversion utilities 00342 static char int2hex[] = "0123456789abcdef"; 00343 00344 static inline uint8_t hex2int(char c) 00345 { 00346 uint8_t val; 00347 00348 if ((c >= 'a') && (c <= 'f')) { 00349 val = 10 + c - 'a'; 00350 } else if ((c >= 'A') && (c <= 'F')) { 00351 val = 10 + c - 'A'; 00352 } else { 00353 val = c - '0'; 00354 } 00355 return val; 00356 } 00357 00358 // decode response character 00359 // 00360 // unpacks hex char into resp struct 00361 // updates resp_bytes and resp_digits as needed 00362 // 00363 inline void devthrottle::decode_char(char c, 00364 int *resp_bytes, 00365 int *resp_digits) 00366 { 00367 if (isxdigit(c)) 00368 { 00369 // store hex nibble in resp struct 00370 uint8_t val = hex2int(c); 00371 if (++*resp_digits & 0x01) { // odd-numbered digit? 00372 resp_p[*resp_bytes] = (val << 4); 00373 } else { 00374 resp_p[(*resp_bytes)++] |= val; 00375 } 00376 } 00377 else if (!isspace(c)) // invalid hex digit? 00378 { 00379 // The controller may return a '\n' after the '\r'. If this or 00380 // any other whitespace is received just ignore it, but complain 00381 // about anything else. 00382 ROS_WARN(DEVICE " non-hex char code (0x%02x) received", c); 00383 } 00384 } 00385 00386 // format the cmd string 00387 inline int devthrottle::format_cmd(char *cmdstr) 00388 { 00389 static int next_seq = 0; 00390 00391 // Compute sequence number and checksum. Any retries should use the 00392 // same sequence number. We avoid using 0xFF so the controller can 00393 // use that as an "unknown" sequence number. 00394 if (++next_seq >= 0xFF) 00395 { 00396 next_seq = 0; 00397 } 00398 cmd.seq = next_seq; 00399 int len = avr_get_len(&cmd); 00400 cmd_p[len-1] = cmd_compute_csum(cmd_p, len-1); 00401 00402 // convert command string to hex characters (and log) 00403 int cmdlen = 0; 00404 for (int i = 0; i < len; ++i) 00405 { 00406 cmdstr[cmdlen++] = int2hex[(cmd_p[i]>>4) & 0xF]; 00407 cmdstr[cmdlen++] = int2hex[cmd_p[i] & 0xF]; 00408 } 00409 00410 cmdstr[cmdlen] = '\0'; // add null for log message 00411 ROS_DEBUG(DEVICE " command: `%s\\r\\n'", cmdstr); 00412 cmdstr[cmdlen++] = '\r'; // replace with CR for device 00413 cmdstr[cmdlen++] = '\n'; // add a newline, too 00414 00415 // buffer overflow should not ever happen 00416 ROS_ASSERT(cmdlen <= MAX_SERVO_CMD_BUFFER); 00417 00418 return cmdlen; 00419 } 00420 00421 // read one response byte from the controller 00422 // 00423 // linelen: number of bytes already received for this packet 00424 // returns: 0 if successful; errno value otherwise. 00425 // 00426 inline int devthrottle::read_byte(int linelen) 00427 { 00428 int timeout = 15; // timeout in msecs 00429 00430 int64_t start_time = GetTime(); 00431 int64_t stop_time = start_time + timeout; 00432 00433 while (true) 00434 { 00435 if (timeout >= 0) { 00436 struct pollfd fds[1]; 00437 fds[0].fd=fd; 00438 fds[0].events = POLLIN; 00439 int64_t delay = stop_time - GetTime(); 00440 if (delay < 0) delay = 0; 00441 int retval = ::poll(fds, 1, delay); 00442 if (retval < 0) 00443 { 00444 if (errno == EINTR) 00445 continue; 00446 ROS_ERROR("error returned on poll"); 00447 return errno; 00448 } 00449 else if (!retval) 00450 { 00451 ROS_WARN("timeout on poll"); 00452 return EBUSY; 00453 } 00454 else { 00455 if ((fds[0].revents & POLLERR) || 00456 (fds[0].revents & POLLHUP) || 00457 (fds[0].revents & POLLNVAL)) 00458 { 00459 ROS_ERROR("Device error on poll"); 00460 return EIO; 00461 } 00462 } 00463 } 00464 00465 int bytes = read(fd, &buffer[linelen], 1); 00466 if (bytes < 0) 00467 { 00468 if (errno == EINTR) 00469 continue; 00470 ROS_WARN(DEVICE " error: \"%s\" after %d bytes received", 00471 strerror(errno), linelen); 00472 return errno; // read failed 00473 } 00474 00475 if (bytes > 0) // got something? 00476 { 00477 ROS_DEBUG(DEVICE " read() returns 0x%02x", buffer[linelen]); 00478 return 0; 00479 } 00480 00481 ROS_DEBUG(DEVICE " read() returns no data"); 00482 } 00483 } 00484 00485 // Send various-length commands to the throttle controller. 00486 // 00487 // returns: 0 if successful, errno value otherwise. 00488 // 00489 int devthrottle::send_cmd(int ccode) 00490 { 00491 avr_set_com_len(&cmd, ccode, 3); 00492 return servo_cmd(); 00493 } 00494 00495 int devthrottle::send_cmd08(int ccode, uint8_t data) 00496 { 00497 avr_set_com_len(&cmd, ccode, 4); 00498 cmd.data.data08 = data; 00499 return servo_cmd(); 00500 } 00501 00502 int devthrottle::send_cmd16(int ccode, uint16_t data) 00503 { 00504 avr_set_com_len(&cmd, ccode, 5); 00505 cmd.data.data16 = htons(data); 00506 return servo_cmd(); 00507 } 00508 00509 int devthrottle::send_cmd32(int ccode, uint32_t data) 00510 { 00511 avr_set_com_len(&cmd, ccode, 7); 00512 cmd.data.data32 = htonl(data); 00513 return servo_cmd(); 00514 } 00515 00516 // Send goto command to the controller. 00517 inline int devthrottle::send_goto(uint8_t pos) 00518 { 00519 ROS_DEBUG("setting AVR throttle position to %d", pos); 00520 return send_cmd08(GOTO_CMD, pos); 00521 } 00522 00523 /* Write formatted command to the throttle controller. 00524 * 00525 * input: cmd struct to be sent 00526 * returns: 0 if successful, errno value otherwise. 00527 * resp struct returned from controller 00528 */ 00529 int devthrottle::servo_cmd(void) 00530 { 00531 char cmdstr[MAX_SERVO_CMD_BUFFER]; 00532 int cmdlen = format_cmd(cmdstr); // format the cmd string 00533 00534 if (!have_tty) return 0; // /dev/null always succeeds 00535 00536 memset(&resp, 0xFF, sizeof(resp)); // for debug purposes 00537 int rc; 00538 int attempts = 3; // number of times to try command 00539 do 00540 { 00541 // Flush the I/O buffers to ensure nothing is left over from any 00542 // previous command. 00543 tcflush(fd, TCIOFLUSH); 00544 00545 // There is not much point in checking for errors on the 00546 // write(). If something went wrong, we'll find out while 00547 // reading the response. 00548 int res = write(fd, cmdstr, cmdlen); // send the command 00549 if (res < 0) 00550 ROS_ERROR_THROTTLE(100, "write() error: %d", errno); 00551 00552 ROS_DEBUG(DEVICE " write() %s\n",cmdstr); 00553 00554 int resp_bytes = 0; 00555 int resp_digits = 0; 00556 int linelen = 0; 00557 00558 for (;;) // read the response packet 00559 { 00560 rc = read_byte(linelen); 00561 if (rc != 0) break; // retry command 00562 00563 // ignore any leading newline left from a previous packet 00564 if (buffer[linelen] == '\n' && linelen == 0) 00565 continue; 00566 00567 // If we have a complete packet, validate it and return. 00568 // Normally, we only see the carriage return, but will honor 00569 // a newline, if the '\r' got lost in transmission. 00570 if (buffer[linelen] == '\r' || buffer[linelen] == '\n') 00571 { 00572 rc = validate_response(resp_bytes, linelen); 00573 if (rc != 0) break; // retry command 00574 return 0; // success 00575 } 00576 00577 // Unpack the data from each packet char as it arrives. 00578 decode_char(buffer[linelen], &resp_bytes, &resp_digits); 00579 00580 if (++linelen >= MAX_SERVO_CMD_BUFFER) 00581 { 00582 char c = buffer[MAX_SERVO_CMD_BUFFER-1]; 00583 buffer[MAX_SERVO_CMD_BUFFER-1] = '\0'; 00584 ROS_WARN(DEVICE " buffer overflow: %s%c", buffer, c); 00585 rc = ENOSPC; 00586 break; // retry command 00587 } 00588 } 00589 } 00590 while (--attempts > 0); // retry after error 00591 00592 ROS_WARN(DEVICE " command failed (%s)", strerror(rc)); 00593 return rc; 00594 } 00595 00596 // validate response packet 00597 inline int devthrottle::validate_response(int resp_bytes, int linelen) 00598 { 00599 buffer[linelen] = '\0'; // EOL is end of string 00600 ROS_DEBUG(DEVICE " \"%s\" response received", buffer); 00601 00602 // check for errors 00603 if (resp_bytes != avr_get_len(&resp)) // packet length mismatch 00604 { 00605 ROS_WARN(DEVICE " packet length error: %s", buffer); 00606 return EIO; 00607 } 00608 00609 uint8_t resp_csum = resp_p[resp_bytes-1]; 00610 uint8_t csum = cmd_compute_csum(resp_p, resp_bytes-1); 00611 if (csum != resp_csum) 00612 { 00613 ROS_WARN(DEVICE " checksum 0x%02x should be 0x%02x", csum, resp_csum); 00614 return EIO; 00615 } 00616 00617 if (resp.seq != cmd.seq) 00618 { 00619 ROS_WARN(DEVICE " sequence number 0x%02x should be 0x%02x", 00620 resp.seq, cmd.seq); 00621 return EIO; 00622 } 00623 00624 if (avr_get_com(&resp) == NAK_CMD) 00625 { 00626 ROS_WARN(DEVICE " responded with NAK error %d", resp.data.data08); 00627 return EIO; 00628 } 00629 00630 return 0; 00631 }