00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 #include <stdio.h>
00023 #include <string.h>
00024 #include <errno.h>
00025 #include <termios.h>
00026 #include <math.h>
00027 #include <poll.h>
00028 #include <signal.h>
00029
00030 #include "hokuyo/hokuyo.h"
00031
00032 #include <algorithm>
00033
00034 #include <time.h>
00035
00036 #include <fcntl.h>
00037
00038 #include "ros/console.h"
00039
00040 #if POSIX_TIMERS <= 0
00041 #include <sys/time.h>
00042 #endif
00043
00044
00046 #define HOKUYO_EXCEPT(except, msg, ...) \
00047 { \
00048 char buf[1000]; \
00049 snprintf(buf, 1000, msg " (in hokuyo::laser::%s) You may find further details at http://www.ros.org/wiki/hokuyo_node/Troubleshooting" , ##__VA_ARGS__, __FUNCTION__); \
00050 throw except(buf); \
00051 }
00052
00053
00055 static uint64_t timeHelper()
00056 {
00057 #if POSIX_TIMERS > 0
00058 struct timespec curtime;
00059 clock_gettime(CLOCK_REALTIME, &curtime);
00060 return (uint64_t)(curtime.tv_sec) * 1000000000 + (uint64_t)(curtime.tv_nsec);
00061 #else
00062 struct timeval timeofday;
00063 gettimeofday(&timeofday,NULL);
00064 return (uint64_t)(timeofday.tv_sec) * 1000000000 + (uint64_t)(timeofday.tv_usec) * 1000;
00065 #endif
00066 }
00067
00068
00069 #ifdef USE_LOG_FILE
00070 FILE *logfile;
00071 #endif
00072
00074 hokuyo::Laser::Laser() :
00075 dmin_(0), dmax_(0), ares_(0), amin_(0), amax_(0), afrt_(0), rate_(0),
00076 wrapped_(0), last_time_(0), time_repeat_count_(0), offset_(0),
00077 laser_fd_(-1)
00078 {
00079 #ifdef USE_LOG_FILE
00080 if (!logfile)
00081 logfile = fopen("hokuyo.log", "w");
00082 #endif
00083 }
00084
00085
00087 hokuyo::Laser::~Laser ()
00088 {
00089 if (portOpen())
00090 close();
00091 }
00092
00093
00095 void
00096 hokuyo::Laser::open(const char * port_name)
00097 {
00098 if (portOpen())
00099 close();
00100
00101
00102
00103
00104
00105 laser_fd_ = ::open(port_name, O_RDWR | O_NONBLOCK | O_NOCTTY);
00106 read_buf_start = read_buf_end = 0;
00107
00108 if (laser_fd_ == -1)
00109 {
00110 const char *extra_msg = "";
00111 switch (errno)
00112 {
00113 case EACCES:
00114 extra_msg = "You probably don't have premission to open the port for reading and writing.";
00115 break;
00116 case ENOENT:
00117 extra_msg = "The requested port does not exist. Is the hokuyo connected? Was the port name misspelled?";
00118 break;
00119 }
00120
00121 HOKUYO_EXCEPT(hokuyo::Exception, "Failed to open port: %s. %s (errno = %d). %s", port_name, strerror(errno), errno, extra_msg);
00122 }
00123 try
00124 {
00125 struct flock fl;
00126 fl.l_type = F_WRLCK;
00127 fl.l_whence = SEEK_SET;
00128 fl.l_start = 0;
00129 fl.l_len = 0;
00130 fl.l_pid = getpid();
00131
00132 if (fcntl(laser_fd_, F_SETLK, &fl) != 0)
00133 HOKUYO_EXCEPT(hokuyo::Exception, "Device %s is already locked. Try 'lsof | grep %s' to find other processes that currently have the port open.", port_name, port_name);
00134
00135
00136 struct termios newtio;
00137 tcgetattr(laser_fd_, &newtio);
00138 memset (&newtio.c_cc, 0, sizeof (newtio.c_cc));
00139 newtio.c_cflag = CS8 | CLOCAL | CREAD;
00140 newtio.c_iflag = IGNPAR;
00141 newtio.c_oflag = 0;
00142 newtio.c_lflag = 0;
00143
00144
00145 tcflush (laser_fd_, TCIFLUSH);
00146 if (tcsetattr (laser_fd_, TCSANOW, &newtio) < 0)
00147 HOKUYO_EXCEPT(hokuyo::Exception, "Unable to set serial port attributes. The port you specified (%s) may not be a serial port.", port_name);
00148 usleep (200000);
00149
00150
00151 laserFlush();
00152
00153
00154 try {
00155 reset();
00156 }
00157 catch (hokuyo::Exception &e)
00158 {
00159
00160
00161
00162
00163
00164 setToSCIP2();
00165 reset();
00166 }
00167
00168 querySensorConfig();
00169
00170 queryVersionInformation();
00171 }
00172 catch (hokuyo::Exception& e)
00173 {
00174
00175 if (laser_fd_ != -1)
00176 ::close(laser_fd_);
00177 laser_fd_ = -1;
00178 throw e;
00179 }
00180 }
00181
00182
00184 void hokuyo::Laser::reset ()
00185 {
00186 if (!portOpen())
00187 HOKUYO_EXCEPT(hokuyo::Exception, "Port not open.");
00188 laserFlush();
00189 try
00190 {
00191 sendCmd("TM2", 1000);
00192 }
00193 catch (hokuyo::Exception &e)
00194 {}
00195 try
00196 {
00197 sendCmd("RS", 1000);
00198 last_time_ = 0;
00199 wrapped_ = 0;
00200 }
00201 catch (hokuyo::Exception &e)
00202 {}
00203 laserFlush();
00204 sendCmd("RS", 1000);
00205 }
00206
00207
00209 void
00210 hokuyo::Laser::close ()
00211 {
00212 int retval = 0;
00213
00214 if (portOpen()) {
00215
00216 try
00217 {
00218 reset();
00219 }
00220 catch (hokuyo::Exception& e) {
00221
00222 }
00223
00224 retval = ::close(laser_fd_);
00225 }
00226
00227 laser_fd_ = -1;
00228
00229 if (retval != 0)
00230 HOKUYO_EXCEPT(hokuyo::Exception, "Failed to close port properly -- error = %d: %s\n", errno, strerror(errno));
00231 }
00232
00234 void
00235 hokuyo::Laser::setToSCIP2()
00236 {
00237 if (!portOpen())
00238 HOKUYO_EXCEPT(hokuyo::Exception, "Port not open.");
00239 const char * cmd = "SCIP2.0";
00240 char buf[100];
00241 laserWrite(cmd);
00242 laserWrite("\n");
00243
00244 laserReadline(buf, 100, 1000);
00245 ROS_DEBUG("Laser comm protocol changed to %s \n", buf);
00246
00247 }
00248
00249
00251 int
00252 hokuyo::Laser::sendCmd(const char* cmd, int timeout)
00253 {
00254 if (!portOpen())
00255 HOKUYO_EXCEPT(hokuyo::Exception, "Port not open.");
00256
00257 char buf[100];
00258
00259 laserWrite(cmd);
00260 laserWrite("\n");
00261
00262 laserReadlineAfter(buf, 100, cmd, timeout);
00263 laserReadline(buf,100,timeout);
00264
00265 if (!checkSum(buf,4))
00266 HOKUYO_EXCEPT(hokuyo::CorruptedDataException, "Checksum failed on status code.");
00267
00268 buf[2] = 0;
00269
00270 if (buf[0] - '0' >= 0 && buf[0] - '0' <= 9 && buf[1] - '0' >= 0 && buf[1] - '0' <= 9)
00271 return (buf[0] - '0')*10 + (buf[1] - '0');
00272 else
00273 HOKUYO_EXCEPT(hokuyo::Exception, "Hokuyo error code returned. Cmd: %s -- Error: %s", cmd, buf);
00274 }
00275
00276
00278 void
00279 hokuyo::Laser::getConfig(LaserConfig& config)
00280 {
00281 config.min_angle = (amin_ - afrt_) * (2.0*M_PI)/(ares_);
00282 config.max_angle = (amax_ - afrt_) * (2.0*M_PI)/(ares_);
00283 config.ang_increment = (2.0*M_PI)/(ares_);
00284 config.time_increment = (60.0)/(double)(rate_ * ares_);
00285 config.scan_time = 60.0/((double)(rate_));
00286 config.min_range = dmin_ / 1000.0;
00287 config.max_range = dmax_ / 1000.0;
00288 }
00289
00290
00292 int
00293 hokuyo::Laser::laserWrite(const char* msg)
00294 {
00295
00296 int origflags = fcntl(laser_fd_,F_GETFL,0);
00297 fcntl(laser_fd_, F_SETFL, origflags & ~O_NONBLOCK);
00298 ssize_t len = strlen(msg);
00299 ssize_t retval = write(laser_fd_, msg, len);
00300 int fputserrno = errno;
00301 fcntl(laser_fd_, F_SETFL, origflags | O_NONBLOCK);
00302 errno = fputserrno;
00303
00304 if (retval != -1)
00305 {
00306 #ifdef USE_LOG_FILE
00307 if (strlen(msg) > 1)
00308 {
00309 long long outtime = timeHelper();
00310 fprintf(logfile, "Out: %lli.%09lli %s\n", outtime / 1000000000L, outtime % 1000000000L, msg);
00311 }
00312 #endif
00313 return retval;
00314 }
00315 else
00316 HOKUYO_EXCEPT(hokuyo::Exception, "fputs failed -- Error = %d: %s", errno, strerror(errno));
00317 }
00318
00319
00321 int
00322 hokuyo::Laser::laserFlush()
00323 {
00324 int retval = tcflush(laser_fd_, TCIOFLUSH);
00325 if (retval != 0)
00326 HOKUYO_EXCEPT(hokuyo::Exception, "tcflush failed");
00327 read_buf_start = 0;
00328 read_buf_end = 0;
00329
00330 return retval;
00331 }
00332
00333
00335 int
00336 hokuyo::Laser::laserReadline(char *buf, int len, int timeout)
00337 {
00338 int current=0;
00339
00340 struct pollfd ufd[1];
00341 int retval;
00342 ufd[0].fd = laser_fd_;
00343 ufd[0].events = POLLIN;
00344
00345 if (timeout == 0)
00346 timeout = -1;
00347
00348 while (true)
00349 {
00350 if (read_buf_start == read_buf_end)
00351 {
00352 if ((retval = poll(ufd, 1, timeout)) < 0)
00353 HOKUYO_EXCEPT(hokuyo::Exception, "poll failed -- error = %d: %s", errno, strerror(errno));
00354
00355 if (retval == 0)
00356 HOKUYO_EXCEPT(hokuyo::TimeoutException, "timeout reached");
00357
00358 if (ufd[0].revents & POLLERR)
00359 HOKUYO_EXCEPT(hokuyo::Exception, "error on socket, possibly unplugged");
00360
00361 int bytes = read(laser_fd_, read_buf, sizeof(read_buf));
00362 if (bytes == -1 && errno != EAGAIN && errno != EWOULDBLOCK)
00363 HOKUYO_EXCEPT(hokuyo::Exception, "read failed");
00364 read_buf_start = 0;
00365 read_buf_end = bytes;
00366 }
00367
00368 while (read_buf_end != read_buf_start)
00369 {
00370 if (current == len - 1)
00371 {
00372 buf[current] = 0;
00373 HOKUYO_EXCEPT(hokuyo::Exception, "buffer filled without end of line being found");
00374 }
00375
00376 buf[current] = read_buf[read_buf_start++];
00377 if (buf[current++] == '\n')
00378 {
00379 buf[current] = 0;
00380 return current;
00381 }
00382 }
00383
00384 #ifdef USE_LOG_FILE
00385 long long outtime = timeHelper();
00386 fprintf(logfile, "In: %lli.%09lli %s", outtime / 1000000000L, outtime % 1000000000L, buf);
00387 #endif
00388 }
00389 }
00390
00391
00392 char*
00393 hokuyo::Laser::laserReadlineAfter(char* buf, int len, const char* str, int timeout)
00394 {
00395 buf[0] = 0;
00396 char* ind = &buf[0];
00397
00398 int bytes_read = 0;
00399 int skipped = 0;
00400
00401 while ((strncmp(buf, str, strlen(str))) != 0) {
00402 bytes_read = laserReadline(buf,len,timeout);
00403
00404 if ((skipped += bytes_read) > MAX_SKIPPED)
00405 HOKUYO_EXCEPT(hokuyo::Exception, "too many bytes skipped while searching for match");
00406 }
00407
00408 return ind += strlen(str);
00409 }
00410
00411
00413 void
00414 hokuyo::Laser::querySensorConfig()
00415 {
00416 if (!portOpen())
00417 HOKUYO_EXCEPT(hokuyo::Exception, "Port not open.");
00418
00419 if (sendCmd("PP",1000) != 0)
00420 HOKUYO_EXCEPT(hokuyo::Exception, "Error requesting configuration information");
00421
00422 char buf[100];
00423 char* ind;
00424
00425 ind = laserReadlineAfter(buf,100,"DMIN:",-1);
00426 sscanf(ind, "%d", &dmin_);
00427
00428 ind = laserReadlineAfter(buf,100,"DMAX:",-1);
00429 sscanf(ind, "%d", &dmax_);
00430
00431 ind = laserReadlineAfter(buf,100,"ARES:",-1);
00432 sscanf(ind, "%d", &ares_);
00433
00434 ind = laserReadlineAfter(buf,100,"AMIN:",-1);
00435 sscanf(ind, "%d", &amin_);
00436
00437 ind = laserReadlineAfter(buf,100,"AMAX:",-1);
00438 sscanf(ind, "%d", &amax_);
00439
00440 ind = laserReadlineAfter(buf,100,"AFRT:",-1);
00441 sscanf(ind, "%d", &afrt_);
00442
00443 ind = laserReadlineAfter(buf,100,"SCAN:",-1);
00444 sscanf(ind, "%d", &rate_);
00445
00446 return;
00447 }
00448
00449
00451 bool
00452 hokuyo::Laser::checkSum(const char* buf, int buf_len)
00453 {
00454 char sum = 0;
00455 for (int i = 0; i < buf_len - 2; i++)
00456 sum += (unsigned char)(buf[i]);
00457
00458 if ((sum & 63) + 0x30 == buf[buf_len - 2])
00459 return true;
00460 else
00461 return false;
00462 }
00463
00464
00466 uint64_t
00467 hokuyo::Laser::readTime(int timeout)
00468 {
00469 char buf[100];
00470
00471 laserReadline(buf, 100, timeout);
00472 if (!checkSum(buf, 6))
00473 HOKUYO_EXCEPT(hokuyo::CorruptedDataException, "Checksum failed on time stamp.");
00474
00475 unsigned int laser_time = ((buf[0]-0x30) << 18) | ((buf[1]-0x30) << 12) | ((buf[2]-0x30) << 6) | (buf[3] - 0x30);
00476
00477 if (laser_time == last_time_)
00478 {
00479 if (++time_repeat_count_ > 2)
00480 {
00481 HOKUYO_EXCEPT(hokuyo::RepeatedTimeException, "The timestamp has not changed for %d reads", time_repeat_count_);
00482 }
00483 else if (time_repeat_count_ > 0)
00484 ROS_DEBUG("The timestamp has not changed for %d reads. Ignoring for now.", time_repeat_count_);
00485 }
00486 else
00487 {
00488 time_repeat_count_ = 0;
00489 }
00490
00491 if (laser_time < last_time_)
00492 wrapped_++;
00493
00494 last_time_ = laser_time;
00495
00496 return (uint64_t)((wrapped_ << 24) | laser_time)*(uint64_t)(1000000);
00497 }
00498
00499
00501 void
00502 hokuyo::Laser::readData(hokuyo::LaserScan& scan, bool has_intensity, int timeout)
00503 {
00504 scan.ranges.clear();
00505 scan.intensities.clear();
00506
00507 int data_size = 3;
00508 if (has_intensity)
00509 data_size = 6;
00510
00511 char buf[100];
00512
00513 int ind = 0;
00514
00515 scan.self_time_stamp = readTime(timeout);
00516
00517 int bytes;
00518
00519 float range;
00520 float intensity;
00521
00522 for (;;)
00523 {
00524 bytes = laserReadline(&buf[ind], 100 - ind, timeout);
00525
00526 if (bytes == 1)
00527 return;
00528
00529 if (!checkSum(&buf[ind], bytes))
00530 HOKUYO_EXCEPT(hokuyo::CorruptedDataException, "Checksum failed on data read.");
00531
00532 bytes += ind - 2;
00533
00534
00535 for (int j = 0; j < bytes - (bytes % data_size); j+=data_size)
00536 {
00537 if (scan.ranges.size() < MAX_READINGS)
00538 {
00539 range = (((buf[j]-0x30) << 12) | ((buf[j+1]-0x30) << 6) | (buf[j+2]-0x30)) / 1000.0;
00540 scan.ranges.push_back(range);
00541
00542 if (has_intensity)
00543 {
00544 intensity = (((buf[j+3]-0x30) << 12) | ((buf[j+4]-0x30) << 6) | (buf[j+5]-0x30));
00545 scan.intensities.push_back(intensity);
00546 }
00547 }
00548 else
00549 {
00550 HOKUYO_EXCEPT(hokuyo::CorruptedDataException, "Got more readings than expected");
00551 }
00552 }
00553
00554 ind = 0;
00555 for (int j = bytes - (bytes % data_size); j < bytes ; j++)
00556 buf[ind++] = buf[j];
00557 }
00558 }
00559
00560
00562 int
00563 hokuyo::Laser::pollScan(hokuyo::LaserScan& scan, double min_ang, double max_ang, int cluster, int timeout)
00564 {
00565 if (!portOpen())
00566 HOKUYO_EXCEPT(hokuyo::Exception, "Port not open.");
00567
00568 int status;
00569
00570
00571 scan.ranges.clear();
00572 scan.intensities.clear();
00573
00574
00575 if (cluster == 0)
00576 cluster = 1;
00577
00578 int min_i = (int)(afrt_ + min_ang*ares_/(2.0*M_PI));
00579 int max_i = (int)(afrt_ + max_ang*ares_/(2.0*M_PI));
00580
00581 char cmdbuf[MAX_CMD_LEN];
00582
00583 sprintf(cmdbuf,"GD%.4d%.4d%.2d", min_i, max_i, cluster);
00584
00585 status = sendCmd(cmdbuf, timeout);
00586
00587 scan.system_time_stamp = timeHelper() + offset_;
00588
00589 if (status != 0)
00590 return status;
00591
00592
00593 scan.config.min_angle = (min_i - afrt_) * (2.0*M_PI)/(ares_);
00594 scan.config.max_angle = (max_i - afrt_) * (2.0*M_PI)/(ares_);
00595 scan.config.ang_increment = cluster*(2.0*M_PI)/(ares_);
00596 scan.config.time_increment = (60.0)/(double)(rate_ * ares_);
00597 scan.config.scan_time = 0.0;
00598 scan.config.min_range = dmin_ / 1000.0;
00599 scan.config.max_range = dmax_ / 1000.0;
00600
00601 readData(scan, false, timeout);
00602
00603 long long inc = (long long)(min_i * scan.config.time_increment * 1000000000);
00604
00605 scan.system_time_stamp += inc;
00606 scan.self_time_stamp += inc;
00607
00608 return 0;
00609 }
00610
00611 int
00612 hokuyo::Laser::laserOn() {
00613 int res = sendCmd("BM",1000);
00614 if (res == 1)
00615 HOKUYO_EXCEPT(hokuyo::Exception, "Unable to control laser due to malfunction.");
00616 return res;
00617 }
00618
00619 int
00620 hokuyo::Laser::laserOff() {
00621 return sendCmd("QT",1000);
00622 }
00623
00624 int
00625 hokuyo::Laser::stopScanning() {
00626 try {
00627 return laserOff();
00628 }
00629 catch (hokuyo::Exception &e)
00630 {
00631
00632
00633 laserFlush();
00634 }
00635 return laserOff();
00636 }
00637
00639 int
00640 hokuyo::Laser::requestScans(bool intensity, double min_ang, double max_ang, int cluster, int skip, int count, int timeout)
00641 {
00642 if (!portOpen())
00643 HOKUYO_EXCEPT(hokuyo::Exception, "Port not open.");
00644
00646
00647 int status;
00648
00649 if (cluster == 0)
00650 cluster = 1;
00651
00652 int min_i = (int)(afrt_ + min_ang*ares_/(2.0*M_PI));
00653 int max_i = (int)(afrt_ + max_ang*ares_/(2.0*M_PI));
00654
00655 char cmdbuf[MAX_CMD_LEN];
00656
00657 char intensity_char = 'D';
00658 if (intensity)
00659 intensity_char = 'E';
00660
00661 sprintf(cmdbuf,"M%c%.4d%.4d%.2d%.1d%.2d", intensity_char, min_i, max_i, cluster, skip, count);
00662
00663 status = sendCmd(cmdbuf, timeout);
00664
00665 return status;
00666 }
00667
00668 bool
00669 hokuyo::Laser::isIntensitySupported()
00670 {
00671 hokuyo::LaserScan scan;
00672
00673 if (!portOpen())
00674 HOKUYO_EXCEPT(hokuyo::Exception, "Port not open.");
00675
00676
00677 try
00678 {
00679 requestScans(1, 0, 0, 0, 0, 1);
00680 serviceScan(scan, 1000);
00681 return true;
00682 }
00683 catch (hokuyo::Exception &e)
00684 {}
00685
00686
00687 try
00688 {
00689 requestScans(0, 0, 0, 0, 0, 1);
00690 serviceScan(scan, 1000);
00691 return false;
00692 }
00693 catch (hokuyo::Exception &e)
00694 {
00695 HOKUYO_EXCEPT(hokuyo::Exception, "Exception whil trying to determine if intensity scans are supported.")
00696 }
00697 }
00698
00699 int
00700 hokuyo::Laser::serviceScan(hokuyo::LaserScan& scan, int timeout)
00701 {
00702 if (!portOpen())
00703 HOKUYO_EXCEPT(hokuyo::Exception, "Port not open.");
00704
00705
00706 scan.ranges.clear();
00707 scan.intensities.clear();
00708
00709 char buf[100];
00710
00711 bool intensity = false;
00712 int min_i;
00713 int max_i;
00714 int cluster;
00715 int skip;
00716 int left;
00717
00718 char* ind;
00719
00720 int status = -1;
00721
00722 do {
00723 ind = laserReadlineAfter(buf, 100, "M",timeout);
00724 scan.system_time_stamp = timeHelper() + offset_;
00725
00726 if (ind[0] == 'D')
00727 intensity = false;
00728 else if (ind[0] == 'E')
00729 intensity = true;
00730 else
00731 continue;
00732
00733 ind++;
00734
00735 sscanf(ind, "%4d%4d%2d%1d%2d", &min_i, &max_i, &cluster, &skip, &left);
00736 laserReadline(buf,100,timeout);
00737
00738 buf[4] = 0;
00739
00740 if (!checkSum(buf, 4))
00741 HOKUYO_EXCEPT(hokuyo::CorruptedDataException, "Checksum failed on status code: %s", buf);
00742
00743 sscanf(buf, "%2d", &status);
00744
00745 if (status != 99)
00746 return status;
00747
00748 } while(status != 99);
00749
00750 scan.config.min_angle = (min_i - afrt_) * (2.0*M_PI)/(ares_);
00751 scan.config.max_angle = (max_i - afrt_) * (2.0*M_PI)/(ares_);
00752 scan.config.ang_increment = cluster*(2.0*M_PI)/(ares_);
00753 scan.config.time_increment = (60.0)/(double)(rate_ * ares_);
00754 scan.config.scan_time = (60.0 * (skip + 1))/((double)(rate_));
00755 scan.config.min_range = dmin_ / 1000.0;
00756 scan.config.max_range = dmax_ / 1000.0;
00757
00758 readData(scan, intensity, timeout);
00759
00760 long long inc = (long long)(min_i * scan.config.time_increment * 1000000000);
00761
00762 scan.system_time_stamp += inc;
00763 scan.self_time_stamp += inc;
00764
00765
00766
00767 return 0;
00768 }
00769
00771 void
00772 hokuyo::Laser::queryVersionInformation()
00773 {
00774 if (!portOpen())
00775 HOKUYO_EXCEPT(hokuyo::Exception, "Port not open.");
00776
00777 if (sendCmd("VV",1000) != 0)
00778 HOKUYO_EXCEPT(hokuyo::Exception, "Error requesting version information");
00779
00780 char buf[100];
00781 vendor_name_ = laserReadlineAfter(buf, 100, "VEND:");
00782 vendor_name_ = vendor_name_.substr(0,vendor_name_.length() - 3);
00783
00784 product_name_ = laserReadlineAfter(buf, 100, "PROD:");
00785 product_name_ = product_name_.substr(0,product_name_.length() - 3);
00786
00787 firmware_version_ = laserReadlineAfter(buf, 100, "FIRM:");
00788 firmware_version_ = firmware_version_.substr(0,firmware_version_.length() - 3);
00789
00790 protocol_version_ = laserReadlineAfter(buf, 100, "PROT:");
00791 protocol_version_ = protocol_version_.substr(0,protocol_version_.length() - 3);
00792
00793
00794
00795
00796
00797
00798
00799 serial_number_ = laserReadlineAfter(buf, 100, "SERI:");
00800 serial_number_ = serial_number_.substr(0,serial_number_.length() - 3);
00801 if (serial_number_[0] == '0')
00802 serial_number_[0] = 'H';
00803 else if (serial_number_[0] != 'H')
00804 serial_number_ = 'H' + serial_number_;
00805 }
00806
00807
00809 std::string
00810 hokuyo::Laser::getID()
00811 {
00812 if (!portOpen())
00813 HOKUYO_EXCEPT(hokuyo::Exception, "Port not open.");
00814
00815 return serial_number_;
00816 }
00817
00818
00820 std::string
00821 hokuyo::Laser::getFirmwareVersion()
00822 {
00823 if (!portOpen())
00824 HOKUYO_EXCEPT(hokuyo::Exception, "Port not open.");
00825
00826 return firmware_version_;
00827 }
00828
00829
00831 std::string
00832 hokuyo::Laser::getProtocolVersion()
00833 {
00834 if (!portOpen())
00835 HOKUYO_EXCEPT(hokuyo::Exception, "Port not open.");
00836
00837 return protocol_version_;
00838 }
00839
00840
00842 std::string
00843 hokuyo::Laser::getVendorName()
00844 {
00845 if (!portOpen())
00846 HOKUYO_EXCEPT(hokuyo::Exception, "Port not open.");
00847
00848 return vendor_name_;
00849 }
00850
00851
00853 std::string
00854 hokuyo::Laser::getProductName()
00855 {
00856 if (!portOpen())
00857 HOKUYO_EXCEPT(hokuyo::Exception, "Port not open.");
00858
00859 return product_name_;
00860 }
00861
00862
00864 std::string
00865 hokuyo::Laser::getStatus()
00866 {
00867 if (!portOpen())
00868 HOKUYO_EXCEPT(hokuyo::Exception, "Port not open.");
00869
00870 if (sendCmd("II",1000) != 0)
00871 HOKUYO_EXCEPT(hokuyo::Exception, "Error requesting device information information");
00872
00873 char buf[100];
00874 char* stat = laserReadlineAfter(buf, 100, "STAT:");
00875
00876 std::string statstr(stat);
00877 statstr = statstr.substr(0,statstr.length() - 3);
00878
00879 return statstr;
00880 }
00881
00882 template <class C>
00883 C median(std::vector<C> &v)
00884 {
00885 std::vector<long long int>::iterator start = v.begin();
00886 std::vector<long long int>::iterator end = v.end();
00887 std::vector<long long int>::iterator median = start + (end - start) / 2;
00888
00889
00890 std::nth_element(start, median, end);
00891
00892
00893
00894
00895
00896 return *median;
00897 }
00898
00899 #if 1
00900 long long int hokuyo::Laser::getHokuyoClockOffset(int reps, int timeout)
00901 {
00902 std::vector<long long int> offset(reps);
00903
00904 sendCmd("TM0",timeout);
00905 for (int i = 0; i < reps; i++)
00906 {
00907 long long int prestamp = timeHelper();
00908 sendCmd("TM1",timeout);
00909 long long int hokuyostamp = readTime();
00910 long long int poststamp = timeHelper();
00911 offset[i] = hokuyostamp - (prestamp + poststamp) / 2;
00912
00913 }
00914 sendCmd("TM2",timeout);
00915
00916 long long out = median(offset);
00917
00918 return out;
00919 }
00920
00921 long long int hokuyo::Laser::getHokuyoScanStampToSystemStampOffset(bool intensity, double min_ang, double max_ang, int clustering, int skip, int reps, int timeout)
00922 {
00923 if (reps < 1)
00924 reps = 1;
00925 else if (reps > 99)
00926 reps = 99;
00927
00928 std::vector<long long int> offset(reps);
00929
00930 if (requestScans(intensity, min_ang, max_ang, clustering, skip, reps, timeout) != 0)
00931 {
00932 HOKUYO_EXCEPT(hokuyo::Exception, "Error requesting scan while caliblating time.");
00933 return 1;
00934 }
00935
00936 hokuyo::LaserScan scan;
00937 for (int i = 0; i < reps; i++)
00938 {
00939 serviceScan(scan, timeout);
00940
00941 offset[i] = scan.self_time_stamp - scan.system_time_stamp;
00942 }
00943
00944 return median(offset);
00945 }
00946
00948 long long
00949 hokuyo::Laser::calcLatency(bool intensity, double min_ang, double max_ang, int clustering, int skip, int num, int timeout)
00950 {
00951 offset_ = 0;
00952 if (!portOpen())
00953 HOKUYO_EXCEPT(hokuyo::Exception, "Port not open.");
00954
00955 if (num <= 0)
00956 num = 10;
00957
00958 int ckreps = 1;
00959 int scanreps = 1;
00960 long long int start = getHokuyoClockOffset(ckreps, timeout);
00961 long long int pre = 0;
00962 std::vector<long long int> samples(num);
00963 for (int i = 0; i < num; i++)
00964 {
00965 long long int scan = getHokuyoScanStampToSystemStampOffset(intensity, min_ang, max_ang, clustering, skip, scanreps, timeout) - start;
00966 long long int post = getHokuyoClockOffset(ckreps, timeout) - start;
00967 samples[i] = scan - (post+pre)/2;
00968
00969
00970 pre = post;
00971 }
00972
00973 offset_ = median(samples);
00974
00975 return offset_;
00976 }
00977
00978 #else
00979
00980 long long
00981 hokuyo::Laser::calcLatency(bool intensity, double min_ang, double max_ang, int clustering, int skip, int num, int timeout)
00982 {
00983 ROS_DEBUG("Entering calcLatency.");
00984
00985 if (!portOpen())
00986 HOKUYO_EXCEPT(hokuyo::Exception, "Port not open.");
00987
00988 static const std::string buggy_version = "1.16.02(19/Jan./2010)";
00989 if (firmware_version_ == buggy_version)
00990 {
00991 ROS_INFO("Hokuyo firmware version %s detected. Using hard-coded time offset of -23 ms.",
00992 buggy_version.c_str());
00993 offset_ = -23000000;
00994 }
00995 else
00996 {
00997 offset_ = 0;
00998
00999 uint64_t comp_time = 0;
01000 uint64_t laser_time = 0;
01001 long long diff_time = 0;
01002 long long drift_time = 0;
01003 long long tmp_offset1 = 0;
01004 long long tmp_offset2 = 0;
01005
01006 int count = 0;
01007
01008 sendCmd("TM0",timeout);
01009 count = 100;
01010
01011 for (int i = 0; i < count;i++)
01012 {
01013 usleep(1000);
01014 sendCmd("TM1",timeout);
01015 comp_time = timeHelper();
01016 try
01017 {
01018 laser_time = readTime();
01019
01020 diff_time = comp_time - laser_time;
01021
01022 tmp_offset1 += diff_time / count;
01023 } catch (hokuyo::RepeatedTimeException &e)
01024 {
01025
01026 continue;
01027 }
01028 }
01029
01030 uint64_t start_time = timeHelper();
01031 usleep(5000000);
01032 sendCmd("TM1;a",timeout);
01033 sendCmd("TM1;b",timeout);
01034 comp_time = timeHelper();
01035 drift_time = comp_time - start_time;
01036 laser_time = readTime() + tmp_offset1;
01037 diff_time = comp_time - laser_time;
01038 double drift_rate = double(diff_time) / double(drift_time);
01039
01040 sendCmd("TM2",timeout);
01041
01042 if (requestScans(intensity, min_ang, max_ang, clustering, skip, num, timeout) != 0)
01043 HOKUYO_EXCEPT(hokuyo::Exception, "Error requesting scans during latency calculation");
01044
01045 hokuyo::LaserScan scan;
01046
01047 count = 200;
01048 for (int i = 0; i < count;i++)
01049 {
01050 try
01051 {
01052 serviceScan(scan, 1000);
01053 } catch (hokuyo::CorruptedDataException &e) {
01054 continue;
01055 }
01056
01057 comp_time = scan.system_time_stamp;
01058 drift_time = comp_time - start_time;
01059 laser_time = scan.self_time_stamp + tmp_offset1 + (long long)(drift_time*drift_rate);
01060 diff_time = laser_time - comp_time;
01061
01062 tmp_offset2 += diff_time / count;
01063 }
01064
01065 offset_ = tmp_offset2;
01066
01067 stopScanning();
01068 }
01069
01070 ROS_DEBUG("Leaving calcLatency.");
01071
01072 return offset_;
01073 }
01074 #endif