sick_generic_imu.cpp
Go to the documentation of this file.
1 
60 #ifdef _MSC_VER
61 //#define _WIN32_WINNT 0x0501
62 #pragma warning(disable: 4996)
63 #pragma warning(disable: 4267)
64 #endif
65 
67 
72 
73 // #include <tf/tf.h>
74 //#include <geometry_msgs/Pose2D.h>
75 
76 #define _USE_MATH_DEFINES
77 
78 #include <math.h>
79 #include "string"
80 #include <stdio.h>
81 #include <stdlib.h>
82 
83 #ifdef DEBUG_DUMP_ENABLED
84 
85 #include "sick_scan/dataDumper.h"
86 
87 #endif
88 namespace sick_scan_xd
89 {
90 
91  bool SickScanImu::isImuDatagram(char *datagram, size_t datagram_length)
92  {
93  bool ret = false;
94  if (this->isImuBinaryDatagram(datagram, datagram_length))
95  {
96  ret = true;
97  }
98  else
99  {
100  if (this->isImuAsciiDatagram(datagram, datagram_length))
101  {
102  ret = true;
103  }
104  else
105  {
106  if (this->isImuAckDatagram(datagram, datagram_length))
107  {
108  ret = true;
109  }
110  }
111  }
112 
113  return (ret);
114  }
115 
116 
123  double SickScanImu::simpleFmodTwoPi(double angle)
124  {
125  while (angle < M_PI)
126  {
127  angle += 2 * M_PI;
128  }
129  while (angle > M_PI)
130  {
131  angle -= 2 * M_PI;
132  }
133  return (angle);
134  }
135 
136  bool SickScanImu::isImuAckDatagram(char *datagram, size_t datagram_length)
137  {
138  bool isImuMsg = false;
139  std::string szKeyWord = "sEA InertialMeasurementUnit";
140  std::string cmpKeyWord = "";
141  int keyWordLen = szKeyWord.length();
142  int posTrial[] = {0, 1, 8};
143  for (int iPos = 0; iPos < sizeof(posTrial) / sizeof(posTrial[0]); iPos++)
144 
145  if (datagram_length >= (keyWordLen + posTrial[iPos])) // 8 Bytes preheader
146  {
147  cmpKeyWord = "";
148  for (int i = 0; i < keyWordLen; i++)
149  {
150  cmpKeyWord += datagram[i + posTrial[iPos]];
151  }
152  }
153  if (szKeyWord.compare(cmpKeyWord) == 0)
154  {
155  isImuMsg = true;
156  }
157  return (isImuMsg);
158  }
159 
166  bool SickScanImu::isImuBinaryDatagram(char *datagram, size_t datagram_length)
167  {
168  /*
169  * sSN InertialM
170 06b0 65 61 73 75 72 65 6d 65 6e 74 55 6e 69 74 20 be easurementUnit .
171 06c0 9d 86 2d bb 9c e9 44 41 1c 33 d6 bb 0b a1 6f 00 ..-...DA.3....o.
172 06d0 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 ................
173 06e0 00 00 00 3f 7f ec 00 3a 60 00 00 3c cd 00 00 39 ...?...:`..<...9
174 06f0 a0 00 00 00 00 00 02 1c 7e 93 a8 23
175  */
176  bool isImuMsg = false;
177  std::string szKeyWord = "sSN InertialMeasurementUnit";
178  std::string cmpKeyWord = "";
179  int keyWordLen = szKeyWord.length();
180  if (datagram_length >= (keyWordLen + 8)) // 8 Bytes preheader
181  {
182  for (int i = 0; i < keyWordLen; i++)
183  {
184  cmpKeyWord += datagram[i + 8];
185  }
186  }
187  if (szKeyWord.compare(cmpKeyWord) == 0)
188  {
189  isImuMsg = true;
190  }
191  else
192  {
193  isImuMsg = false;
194  }
195  return (isImuMsg);
196  }
197 
203  int SickScanImu::parseBinaryDatagram(char *datagram, size_t datagram_length, SickScanImuValue *imuValue)
204  {
205  static int cnt = 0;
206  cnt++;
207  int iRet = 0;
208  float tmpArr[13] = {0};
209  uint64_t timeStamp;
210  unsigned char *receiveBuffer = (unsigned char *) datagram;
211  if (false == isImuBinaryDatagram(datagram, datagram_length))
212  {
213  return (-1);
214  }
215 
216  unsigned char *bufPtr = (unsigned char *) datagram;
217 #ifdef DEBUG_DUMP_TO_CONSOLE_ENABLED
218  DataDumper::instance().dumpUcharBufferToConsole((unsigned char*)datagram, datagram_length);
219 #endif
220  memcpy(&timeStamp, receiveBuffer + 36 + 13 * 4, 4);
221  swap_endian((unsigned char *) &timeStamp, 4);
222  int adrOffset = 36;
223  for (int i = 0; i < 13; i++)
224  {
225  memcpy(&(tmpArr[i]), receiveBuffer + adrOffset, 4);
226  swap_endian((unsigned char *) (&(tmpArr[i])), 4);
227  adrOffset += 4;
228 
229 // if ((cnt % 10) == 0)
230 // {
231 // if (i == 0)
232 // {
233 // printf("===================\n");
234 // }
235 // printf("%2d: %8.6f\n", i, tmpArr[i]);
236 // }
237  }
238 
239  imuValue->LinearAccelerationX(tmpArr[0]);
240  imuValue->LinearAccelerationY(tmpArr[1]);
241  imuValue->LinearAccelerationZ(tmpArr[2]);
242 
243 
244  float angleVelMultiplier = 1.0f;
245  imuValue->AngularVelocityX(angleVelMultiplier * tmpArr[3]);
246  imuValue->AngularVelocityY(angleVelMultiplier * tmpArr[4]);
247  imuValue->AngularVelocityZ(angleVelMultiplier * tmpArr[5]);
248 
249  imuValue->TimeStamp(timeStamp);
250 
251 
252  imuValue->QuaternionW(tmpArr[9]); // w is first element
253  imuValue->QuaternionX(tmpArr[10]);
254  imuValue->QuaternionY(tmpArr[11]);
255  imuValue->QuaternionZ(tmpArr[12]);
256 
257  imuValue->QuaternionAccuracy(0.0); // not used tmpArr[4]);
258 
259 
260  uint8_t val = 0x00;
261  imuValue->AngularVelocityReliability((UINT16) val);
262  imuValue->LinearAccelerationReliability((UINT16) val);
263  return (iRet);
264  }
265 
272  bool SickScanImu::isImuAsciiDatagram(char *datagram, size_t datagram_length)
273  {
274  bool isImuMsg = false;
275  std::string szKeyWord = "sSN InertialMeasurementUnit";
276  int keyWordLen = szKeyWord.length();
277  if (datagram_length >= keyWordLen)
278  {
279 
280  char *ptr = NULL;
281  ptr = strstr(datagram, szKeyWord.c_str());
282  if (ptr != NULL)
283  {
284  int offset = ptr - datagram;
285  if ((offset == 0) || (offset == 1)) // should work with 0x02 and without 0x02
286  {
287  isImuMsg = true;
288  }
289  }
290  }
291  return (isImuMsg);
292  }
293 
299  int SickScanImu::parseAsciiDatagram(char *datagram, size_t datagram_length, SickScanImuValue *imuValue)
300  {
301  int exitCode = ExitSuccess;
302  bool dumpData = false;
303 
304  int HEADER_FIELDS = 32;
305  char *cur_field;
306  size_t count;
307 
308  // Reserve sufficient space
309  std::vector<char *> fields;
310  fields.reserve(datagram_length / 2);
311 
312  // ----- only for debug output
313  std::vector<char> datagram_copy_vec;
314  datagram_copy_vec.resize(datagram_length + 1); // to avoid using malloc. destructor frees allocated mem.
315  char *datagram_copy = &(datagram_copy_vec[0]);
316 
317  strncpy(datagram_copy, datagram, datagram_length); // datagram will be changed by strtok
318  datagram_copy[datagram_length] = 0;
319 
320  // ----- tokenize
321  count = 0;
322  cur_field = strtok(datagram, " ");
323 
324  while (cur_field != NULL)
325  {
326  fields.push_back(cur_field);
327  //std::cout << cur_field << std::endl;
328  cur_field = strtok(NULL, " ");
329  }
330 
331  //std::cout << fields[27] << std::endl;
332 
333  count = fields.size();
334 
335  enum IMU_TOKEN_SEQ // see specification
336  {
337  IMU_TOKEN_SSN, // 0: sSN
338  IMU_TOKEN_IMUDATA, // 1: LMDradardata
339  IMU_TOKEN_TIMESTAMP, // unsigned long value timestamp
340  IMU_TOKEN_QUATERNION_W,
341  IMU_TOKEN_QUATERNION_X,
342  IMU_TOKEN_QUATERNION_Y,
343  IMU_TOKEN_QUATERNION_Z,
344  IMU_TOKEN_QUATERNION_ACCURACY, // float value
345  IMU_TOKEN_ANGULAR_VELOCITY_X,
346  IMU_TOKEN_ANGULAR_VELOCITY_Y,
347  IMU_TOKEN_ANGULAR_VELOCITY_Z,
348  IMU_TOKEN_ANGULAR_VELOCITY_RELIABILITY, // int value
349  IMU_TOKEN_LINEAR_ACCELERATION_X,
350  IMU_TOKEN_LINEAR_ACCELERATION_Y,
351  IMU_TOKEN_LINEAR_ACCELERATION_Z,
352  IMU_TOKEN_LINEAR_ACCELERATION_RELIABILITY, // int value
353  IMU_TOKEN_NUM
354  };
355  for (int i = 0; i < IMU_TOKEN_NUM; i++)
356  {
357  UINT16 uiValue = 0x00;
358  UINT32 udiValue = 0x00;
359  unsigned long int uliDummy;
360  uliDummy = strtoul(fields[i], NULL, 16);
361  float floatDummy;
362  switch (i)
363  {
364  case IMU_TOKEN_TIMESTAMP:
365  imuValue->TimeStamp(uliDummy);
366  break;
367  case IMU_TOKEN_QUATERNION_X:
368  memcpy(&floatDummy, &uliDummy, sizeof(float));
369  imuValue->QuaternionX(floatDummy); // following IEEE 754 float convention
370  break;
371  case IMU_TOKEN_QUATERNION_Y:
372  memcpy(&floatDummy, &uliDummy, sizeof(float));
373  imuValue->QuaternionY(floatDummy);
374  break;
375  case IMU_TOKEN_QUATERNION_Z:
376  memcpy(&floatDummy, &uliDummy, sizeof(float));
377  imuValue->QuaternionZ(floatDummy);
378  break;
379  case IMU_TOKEN_QUATERNION_W:
380  memcpy(&floatDummy, &uliDummy, sizeof(float));
381  imuValue->QuaternionW(floatDummy);
382  break;
383 
384  case IMU_TOKEN_QUATERNION_ACCURACY: // float value
385  memcpy(&floatDummy, &uliDummy, sizeof(float));
386  imuValue->QuaternionAccuracy(floatDummy);
387  break;
388  case IMU_TOKEN_ANGULAR_VELOCITY_X:
389  memcpy(&floatDummy, &uliDummy, sizeof(float));
390  imuValue->AngularVelocityX(floatDummy);
391  break;
392  case IMU_TOKEN_ANGULAR_VELOCITY_Y:
393  memcpy(&floatDummy, &uliDummy, sizeof(float));
394  imuValue->AngularVelocityY(floatDummy);
395  break;
396  case IMU_TOKEN_ANGULAR_VELOCITY_Z:
397  memcpy(&floatDummy, &uliDummy, sizeof(float));
398  imuValue->AngularVelocityZ(floatDummy);
399  break;
400  case IMU_TOKEN_ANGULAR_VELOCITY_RELIABILITY:
401  uiValue = (UINT16) (0xFFFF & uliDummy);
402  imuValue->AngularVelocityReliability(
403  uiValue); // per definition is a 8 bit value, but we use a 16 bit value
404  break;
405  case IMU_TOKEN_LINEAR_ACCELERATION_X:
406  memcpy(&floatDummy, &uliDummy, sizeof(float));
407  imuValue->LinearAccelerationX(floatDummy);
408  break;
409  case IMU_TOKEN_LINEAR_ACCELERATION_Y:
410  memcpy(&floatDummy, &uliDummy, sizeof(float));
411  imuValue->LinearAccelerationY(floatDummy);
412  break;
413  case IMU_TOKEN_LINEAR_ACCELERATION_Z:
414  memcpy(&floatDummy, &uliDummy, sizeof(float));
415  imuValue->LinearAccelerationZ(floatDummy);
416  break;
417  case IMU_TOKEN_LINEAR_ACCELERATION_RELIABILITY:
418  uiValue = (UINT16) (0xFFFF & uliDummy);
420  uiValue); // per definition is a 8 bit value, but we use a 16 bit value
421  break;
422 
423  }
424  }
425  return (0);
426  }
427 
435  {
436  // Quaterions derived from https://quaternions.online/
437  double wxyz_test_vec[] = { 0.723, 0.440, 0.022, -0.532}; // corresponds to rpy 45,30,-60 in zyx-Order
438  double rad2deg = 180.0/M_PI;
439 
440 #if 0
441  tf::Quaternion qOrientation(
442  wxyz_test_vec[1], // x
443  wxyz_test_vec[2], // y
444  wxyz_test_vec[3], // z
445  wxyz_test_vec[0]); // w
446 
447  tf::Matrix3x3 m(qOrientation);
448  double roll, pitch, yaw;
449  m.getRPY(roll, pitch, yaw); // convert to roll pitch yaw and try to derive Angular Velocity from these values
450 
451  printf("Test result\n");
452  printf("Roll 45.054 [deg]: %8.3lf [deg]\n", roll * rad2deg);
453  printf("Pitch: 30.004 [deg]: %8.3lf [deg]\n", pitch * rad2deg);
454  printf("Yaw: -60.008 [deg]: %8.3lf [deg]\n", yaw * rad2deg);
455 #endif
456 
457  struct Quaternion {
458  double w, x, y, z;
459  };
460 
461  struct EulerAngles {
462  double roll, pitch, yaw;
463  };
464 
465  Quaternion q;
466  q.x = wxyz_test_vec[1];
467  q.y = wxyz_test_vec[2];
468  q.z = wxyz_test_vec[3];
469  q.w = wxyz_test_vec[0];
470 
471  EulerAngles angles;
472 
473 
474  // roll (x-axis rotation)
475  double sinr_cosp = 2 * (q.w * q.x + q.y * q.z);
476  double cosr_cosp = 1 - 2 * (q.x * q.x + q.y * q.y);
477  angles.roll = std::atan2(sinr_cosp, cosr_cosp);
478 
479  // pitch (y-axis rotation)
480  double sinp = 2 * (q.w * q.y - q.z * q.x);
481  if (std::abs(sinp) >= 1)
482  angles.pitch = std::copysign(M_PI / 2, sinp); // use 90 degrees if out of range
483  else
484  angles.pitch = std::asin(sinp);
485 
486  // yaw (z-axis rotation)
487  double siny_cosp = 2 * (q.w * q.z + q.x * q.y);
488  double cosy_cosp = 1 - 2 * (q.y * q.y + q.z * q.z);
489  angles.yaw = std::atan2(siny_cosp, cosy_cosp);
490 
491  printf("Test result (should be similiar to the result above)\n");
492  printf("Roll 45 [deg]: %8.3lf [deg]\n", angles.roll * rad2deg);
493  printf("Pitch: 30 [deg]: %8.3lf [deg]\n", angles.pitch * rad2deg);
494  printf("Yaw: -60 [deg]: %8.3lf [deg]\n", angles.yaw * rad2deg);
495 
496  }
498  {
499  sick_scan_xd::SickScanImu scanImu(NULL, 0);
501  // checked with online converter
502  // https://www.h-schmidt.net/FloatConverter/IEEE754de.html
503  // 55570143 0.9998779 -0.0057373047 0.016174316 0.0 0.0 0.002130192 -0.31136206 -0.10777917 9.823472
504  std::string imuTestStr = "sSN IMUData 34FEEDF 3F7FF800 BBBC0000 3C848000 00000000 00000000 00000000 3B0B9AB1 00000000 3 BE9F6AD9 BDDCBB53 411D2CF1 0";
505  const char imuTestBinStr[] =
506 
507 /*
508  * 02 02 02 02 00 00 ................
509  0640 00 58
510  73 53 4e 20 49 6e 65 72 74 69 61 6c 4d 65 .XsSN InertialMe
511  0650 61 73 75 72 65 6d 65 6e 74 55 6e 69 74 20 be a4 asurementUnit ..
512  0660 e1 1c 3b 6b 5d e5 41 1c 6e ad bb 0b a1 6f bb 0b ..;k].A.n....o..
513  0670 a1 6f 00 00 00 00 00 00 00 00 00 00 00 00 00 00 .o..............
514  0680 00 00 3f 7f ec 00 3a 60 00 00 3c cd 00 00 39 a0 ..?...:`..<...9.
515  0690 00 00 00 00 00 02 1c 7e 6c 01 20
516 
517  56 Data Bytes + 2 Byte Timestamp + CRC
518  14 Float + 4 Byte CRC
519 
520  3 Acceleration = 12 Bytes
521  3 AngularVelocity = 12
522  Magnetic Field = 12 Bytes
523  Orientatoin = 16 Bytes
524  TimeStamp = 4
525  Sum: 12 + 12 + 12 + 16 + 4 = 56 Bytes
526 
527 */
528  "\x02\x02\x02\x02\x00\x00\x00\x58" // 8 Byte Header
529  "\x73\x53\x4e\x20\x49\x6e\x65\x72\x74\x69\x61\x6c\x4d\x65" // Keyword
530  "\x61\x73\x75\x72\x65\x6d\x65\x6e\x74\x55\x6e\x69\x74\x20\xbe\xa4"
531  "\xe1\x1c\x3b\x6b\x5d\xe5\x41\x1c\x6e\xad\xbb\x0b\xa1\x6f\xbb\x0b"
532  "\xa1\x6f\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"
533  "\x00\x00\x3f\x7f\xec\x00\x3a\x60\x00\x00\x3c\xcd\x00\x00\x39\xa0"
534  "\x00\x00\x00\x00\x00\x02\x1c\x7e\x6c\x01\x20";
535 
536  char *datagramPtr = (char *) imuTestStr.c_str();
537  int datagramLen = imuTestStr.size();
538 
539  if (scanImu.isImuAsciiDatagram(datagramPtr, datagramLen))
540  {
541  scanImu.parseAsciiDatagram(datagramPtr, datagramLen, &imuValue);
542  }
543 
544  datagramPtr = (char *) imuTestBinStr;
545  datagramLen = sizeof(imuTestBinStr) / sizeof(imuTestBinStr[0]);
546 
547  if (scanImu.isImuBinaryDatagram(datagramPtr, datagramLen))
548  {
549  scanImu.parseBinaryDatagram(datagramPtr, datagramLen, &imuValue);
550  }
551 
552  }
553 
554  int SickScanImu::parseDatagram(rosTime timeStamp, unsigned char *receiveBuffer, int actual_length,
555  bool useBinaryProtocol)
556  {
557  int exitCode = ExitSuccess;
558 
559  SickScanImuValue imuValue;
560  ros_sensor_msgs::Imu imuMsg_;
561  static rosTime lastTimeStamp;
562 
563  static double lastRoll = 0.0;
564  static double lastPitch = 0.0;
565  static double lastYaw = 0.0;
566 
567  static bool firstTime = true;
568  /*
569  static int cnt = 0;
570  static u_int32_t timeStampSecBuffer[1000];
571  static u_int32_t timeStampNanoSecBuffer[1000];
572  static u_int32_t timeStampSecCorBuffer[1000];
573  static u_int32_t timeStampNanoSecCorBuffer[1000];
574  static u_int32_t imuTimeStamp[1000];
575  static int timeStampValid[1000];
576 
577  int idx = cnt % 1000;
578  cnt++;
579 
580  int dumpIdx = 500;
581  if (cnt == dumpIdx)
582  {
583  printf("TICK;TS_SEC;TS_NANO;TS;TS_CORR_SEC;TS_CORR_NANO;TS_CORR;TS_DIFF;TS_VALID\n");
584 
585  for (int i = 0; i < dumpIdx; i++)
586  {
587  double tsDouble = timeStampSecBuffer[i] + 1E-9 * timeStampNanoSecBuffer[i];
588  double tsDoubleCorr = timeStampSecCorBuffer[i] + 1E-9 * timeStampNanoSecCorBuffer[i];
589  double tsDiff = tsDouble - tsDoubleCorr;
590  printf("%10u;%10u;%10u;%16.8lf;%10u;%10u;%16.8lf;%16.8lf;%d\n",
591  imuTimeStamp[i],
592  timeStampSecBuffer[i], timeStampNanoSecBuffer[i], tsDouble,
593  timeStampSecCorBuffer[i], timeStampNanoSecCorBuffer[i], tsDoubleCorr, tsDiff, timeStampValid[i]);
594  }
595  }
596  */
597  if (useBinaryProtocol)
598  {
599  this->parseBinaryDatagram((char *) receiveBuffer, actual_length, &imuValue);
600 
601  }
602  else
603  {
604  this->parseAsciiDatagram((char *) receiveBuffer, actual_length, &imuValue);
605  }
606  /*
607  timeStampSecBuffer[idx] = timeStamp.sec;
608  timeStampNanoSecBuffer[idx] = timeStamp.nsec;
609  imuTimeStamp[idx] = imuValue.TimeStamp();
610 */
611  uint32_t timeStampSec = (uint32_t)sec(timeStamp), timeStampNsec = (uint32_t)nsec(timeStamp);
612  bool bRet = SoftwarePLL::instance().getCorrectedTimeStamp(timeStampSec, timeStampNsec,
613  (uint32_t) (imuValue.TimeStamp() & 0xFFFFFFFF));
614  timeStamp = rosTime(timeStampSec, timeStampNsec);
615  /*
616  timeStampSecCorBuffer[idx] = timeStamp.sec;
617  timeStampNanoSecCorBuffer[idx] = timeStamp.nsec;
618  timeStampValid[idx] = bRet ? 1 : 0;
619  */
620  imuMsg_.header.stamp = timeStamp;
621  ROS_HEADER_SEQ(imuMsg_.header, 0);
622  imuMsg_.header.frame_id = commonPtr->config_.imu_frame_id; //
623 
624 
625 
626  imuMsg_.orientation.x = imuValue.QuaternionX();
627  imuMsg_.orientation.y = imuValue.QuaternionY();
628  imuMsg_.orientation.z = imuValue.QuaternionZ();
629  imuMsg_.orientation.w = imuValue.QuaternionW();
630  imuMsg_.orientation_covariance[0] = 1.0;
631 
632  double roll, pitch, yaw;
633 
634 #if 0
635  // due to problems compile tf.h against the bloom server we implent a bare bone conversion from
636  // quaternion to euler following https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles
637  // include tf.h for testing it.
638  tf::Quaternion qOrientation(
639  imuMsg_.orientation.x,
640  imuMsg_.orientation.y,
641  imuMsg_.orientation.z,
642  imuMsg_.orientation.w);
643  tf::Matrix3x3 m(qOrientation);
644  m.getRPY(roll, pitch, yaw); // convert to roll pitch yaw and try to derive Angular Velocity from these values
645 #else // barebone implementation without include tf.h
646  {
647  struct Quaternion {
648  double w, x, y, z;
649  };
650 
651  struct EulerAngles {
652  double roll, pitch, yaw;
653  };
654 
655  Quaternion q;
656  q.x = imuMsg_.orientation.x;
657  q.y = imuMsg_.orientation.y;
658  q.z = imuMsg_.orientation.z;
659  q.w = imuMsg_.orientation.w;
660 
661  EulerAngles angles;
662 
663 
664  // roll (x-axis rotation)
665  double sinr_cosp = 2 * (q.w * q.x + q.y * q.z);
666  double cosr_cosp = 1 - 2 * (q.x * q.x + q.y * q.y);
667  angles.roll = std::atan2(sinr_cosp, cosr_cosp);
668 
669  // pitch (y-axis rotation)
670  double sinp = 2 * (q.w * q.y - q.z * q.x);
671  if (std::abs(sinp) >= 1)
672  angles.pitch = std::copysign(M_PI / 2, sinp); // use 90 degrees if out of range
673  else
674  angles.pitch = std::asin(sinp);
675 
676  // yaw (z-axis rotation)
677  double siny_cosp = 2 * (q.w * q.z + q.x * q.y);
678  double cosy_cosp = 1 - 2 * (q.y * q.y + q.z * q.z);
679  angles.yaw = std::atan2(siny_cosp, cosy_cosp);
680 
681  roll = angles.roll;
682  pitch = angles.pitch;
683  yaw = angles.yaw;
684  }
685 #endif
686  imuMsg_.angular_velocity.x = imuValue.AngularVelocityX();
687  imuMsg_.angular_velocity.y = imuValue.AngularVelocityY();
688  imuMsg_.angular_velocity.z = imuValue.AngularVelocityZ();
689 #if 0
690  if (firstTime)
691  {
692  lastTimeStamp = timeStamp;
693  firstTime = false;
694  }
695  else
696  {
697 
698 #ifdef DEBUG_DUMP_ENABLED
699  /*
700  float LinearAccelerationX() const { return linearAccelerationX; }
701  void LinearAccelerationX(float val) { linearAccelerationX = val; }
702  float LinearAccelerationY() const { return linearAccelerationY; }
703  void LinearAccelerationY(float val) { linearAccelerationY = val; }
704  float LinearAccelerationZ() const { return linearAccelerationZ; }
705  void LinearAccelerationZ(float val) { linearAccelerationZ = val; }
706  */
707  DataDumper::instance().pushData((double)imuValue.TimeStamp(), "ACCX", imuValue.LinearAccelerationX());
708  DataDumper::instance().pushData((double)imuValue.TimeStamp(), "ACCY", imuValue.LinearAccelerationY());
709  DataDumper::instance().pushData((double)imuValue.TimeStamp(), "ACCZ", imuValue.LinearAccelerationZ());
710 #endif
711  /*
712  * The built-in IMU unit provides three parameter sets:
713  * quaternions, angular velocity and linear accelerations.
714  * The angular velocities give noisy data without offset compensation (i.e. with drift).
715  * For this reason, the angular velocities are derived from the quaternions. The quaternions are converted
716  * into Euler angles for this purpose. The angular velocity is then calculated from these
717  * sequential Euler angles.
718  */
719  rosDuration timeDiffRos = timeStamp - lastTimeStamp;
720  double timeDiff = timeDiffRos.toSec();
721  if (timeDiff > 1E-6) // Epsilon-Check
722  {
723  double angleDiffX = roll - lastRoll;
724  double angleDiffY = pitch - lastPitch;
725  double angleDiffZ = yaw - lastYaw;
726  angleDiffX = simpleFmodTwoPi(angleDiffX);
727  angleDiffY = simpleFmodTwoPi(angleDiffY);
728  angleDiffZ = simpleFmodTwoPi(angleDiffZ);
729  double angleAngleApproxX = angleDiffX / timeDiff;
730  double angleAngleApproxY = angleDiffY / timeDiff;
731  double angleAngleApproxZ = angleDiffZ / timeDiff;
732 
733  imuMsg_.angular_velocity.x = angleAngleApproxX;
734  imuMsg_.angular_velocity.y = angleAngleApproxY;
735  imuMsg_.angular_velocity.z = angleAngleApproxZ;
736 
737  }
738  }
739  lastTimeStamp = timeStamp;
740  lastRoll = roll;
741  lastPitch = pitch;
742  lastYaw = yaw;
743 #endif
744  imuMsg_.linear_acceleration.x = imuValue.LinearAccelerationX();
745  imuMsg_.linear_acceleration.y = imuValue.LinearAccelerationY();
746  imuMsg_.linear_acceleration.z = imuValue.LinearAccelerationZ();
747  // setting main diagonal elements of covariance matrix
748  // to some meaningful values.
749  // see https://github.com/ROBOTIS-GIT/OpenCR/blob/master/arduino/opencr_arduino/opencr/libraries/ROS/examples/01.%20Basics/d_IMU/d_IMU.ino
750  // as a reference.
751 
752 
753 
754  for (int i = 0; i < 9; i++)
755  {
756  imuMsg_.angular_velocity_covariance[i] = 0.00;
757  imuMsg_.linear_acceleration_covariance[i] = 0.00;
758  imuMsg_.orientation_covariance[i] = 0.00;
759 
760  }
761 
763  {
764  imuMsg_.angular_velocity_covariance[0] = 0.02;
765  imuMsg_.angular_velocity_covariance[1] = 0;
766  imuMsg_.angular_velocity_covariance[2] = 0;
767  imuMsg_.angular_velocity_covariance[3] = 0;
768  imuMsg_.angular_velocity_covariance[4] = 0.02;
769  imuMsg_.angular_velocity_covariance[5] = 0;
770  imuMsg_.angular_velocity_covariance[6] = 0;
771  imuMsg_.angular_velocity_covariance[7] = 0;
772  imuMsg_.angular_velocity_covariance[8] = 0.02;
773 
774  imuMsg_.linear_acceleration_covariance[0] = 0.04;
775  imuMsg_.linear_acceleration_covariance[1] = 0;
776  imuMsg_.linear_acceleration_covariance[2] = 0;
777  imuMsg_.linear_acceleration_covariance[3] = 0;
778  imuMsg_.linear_acceleration_covariance[4] = 0.04;
779  imuMsg_.linear_acceleration_covariance[5] = 0;
780  imuMsg_.linear_acceleration_covariance[6] = 0;
781  imuMsg_.linear_acceleration_covariance[7] = 0;
782  imuMsg_.linear_acceleration_covariance[8] = 0.04;
783 
784  imuMsg_.orientation_covariance[0] = 0.0025;
785  imuMsg_.orientation_covariance[1] = 0;
786  imuMsg_.orientation_covariance[2] = 0;
787  imuMsg_.orientation_covariance[3] = 0;
788  imuMsg_.orientation_covariance[4] = 0.0025;
789  imuMsg_.orientation_covariance[5] = 0;
790  imuMsg_.orientation_covariance[6] = 0;
791  imuMsg_.orientation_covariance[7] = 0;
792  imuMsg_.orientation_covariance[8] = 0.0025;
793  }
794  else
795  {
796  imuMsg_.angular_velocity_covariance[0] = 0;
797  imuMsg_.angular_velocity_covariance[1] = 0;
798  imuMsg_.angular_velocity_covariance[2] = 0;
799  imuMsg_.angular_velocity_covariance[3] = 0;
800  imuMsg_.angular_velocity_covariance[4] = 0;
801  imuMsg_.angular_velocity_covariance[5] = 0;
802  imuMsg_.angular_velocity_covariance[6] = 0;
803  imuMsg_.angular_velocity_covariance[7] = 0;
804  imuMsg_.angular_velocity_covariance[8] = 0;
805 
806  imuMsg_.linear_acceleration_covariance[0] = 0;
807  imuMsg_.linear_acceleration_covariance[1] = 0;
808  imuMsg_.linear_acceleration_covariance[2] = 0;
809  imuMsg_.linear_acceleration_covariance[3] = 0;
810  imuMsg_.linear_acceleration_covariance[4] = 0;
811  imuMsg_.linear_acceleration_covariance[5] = 0;
812  imuMsg_.linear_acceleration_covariance[6] = 0;
813  imuMsg_.linear_acceleration_covariance[7] = 0;
814  imuMsg_.linear_acceleration_covariance[8] = 0;
815 
816  imuMsg_.orientation_covariance[0] = 0;
817  imuMsg_.orientation_covariance[1] = 0;
818  imuMsg_.orientation_covariance[2] = 0;
819  imuMsg_.orientation_covariance[3] = 0;
820  imuMsg_.orientation_covariance[4] = 0;
821  imuMsg_.orientation_covariance[5] = 0;
822  imuMsg_.orientation_covariance[6] = 0;
823  imuMsg_.orientation_covariance[7] = 0;
824  imuMsg_.orientation_covariance[8] = 0;
825 
826  }
827  if (true == bRet)
828  {
829  notifyImuListener(nh, &imuMsg_);
830  rosPublish(this->commonPtr->imuScan_pub_, imuMsg_);
831  }
832  return (exitCode);
833 
834  }
835 }
836 
tf::Matrix3x3
UINT16
uint16_t UINT16
Definition: BasicDatatypes.hpp:73
sensor_msgs::Imu
::sensor_msgs::Imu_< std::allocator< void > > Imu
Definition: Imu.h:93
NULL
#define NULL
swap_endian
void swap_endian(unsigned char *ptr, int numBytes)
Universal swapping function.
Definition: sick_scan_common.cpp:125
angles
angle
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
sick_scan_xd::SickScanImuValue::QuaternionAccuracy
float QuaternionAccuracy() const
Definition: sick_generic_imu.h:116
tf::Matrix3x3::getRPY
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
rad2deg
#define rad2deg(x)
Definition: sick_scan_common.cpp:98
DataDumper::dumpUcharBufferToConsole
int dumpUcharBufferToConsole(unsigned char *buffer, int bufLen)
Definition: dataDumper.cpp:67
DataDumper::instance
static DataDumper & instance()
Definition: dataDumper.h:15
sick_scan_xd::SickScanCommon::config_
SickScanConfig config_
Definition: sick_scan_common.h:395
SoftwarePLL::instance
static SoftwarePLL & instance()
Definition: softwarePLL.h:24
sick_scan_xd::SickScanImu::commonPtr
SickScanCommon * commonPtr
Definition: sick_generic_imu.h:219
sick_scan_xd::SickScanImuValue::AngularVelocityY
float AngularVelocityY() const
Definition: sick_generic_imu.h:129
sick_scan_xd::notifyImuListener
void notifyImuListener(rosNodePtr handle, const ros_sensor_msgs::Imu *msg)
Definition: sick_generic_callback.cpp:114
SoftwarePLL::getCorrectedTimeStamp
bool getCorrectedTimeStamp(uint32_t &sec, uint32_t &nanoSec, uint32_t tick)
Definition: softwarePLL.cpp:226
sick_scan_xd
Definition: abstract_parser.cpp:65
sick_scan_common.h
sick_ros_wrapper.h
sick_scan_xd::SickScanImu::isImuDatagram
bool isImuDatagram(char *datagram, size_t datagram_length)
Definition: sick_generic_imu.cpp:91
sick_scan_xd::SickScanImu::isImuAsciiDatagram
bool isImuAsciiDatagram(char *datagram, size_t datagram_length)
Checking ASCII diagram for imu message type.
Definition: sick_generic_imu.cpp:272
sick_scan_xd::SickScanImuValue::LinearAccelerationY
float LinearAccelerationY() const
Definition: sick_generic_imu.h:153
sick_scan_xd::SickScanConfig::cloud_output_mode
int cloud_output_mode
Definition: sick_ros_wrapper.h:525
ROS_HEADER_SEQ
#define ROS_HEADER_SEQ(msgheader, value)
Definition: sick_ros_wrapper.h:162
sick_scan_xd::SickScanImu::simpleFmodTwoPi
double simpleFmodTwoPi(double angle)
Checking angle to be in the interval [-M_PI,M_PI] Of course you can also use fmod,...
Definition: sick_generic_imu.cpp:123
nsec
uint32_t nsec(const rosTime &time)
Definition: sick_ros_wrapper.h:175
sick_generic_parser.h
sick_scan_common_tcp.h
sick_scan_xd::SickScanImu::parseBinaryDatagram
int parseBinaryDatagram(char *datagram, size_t datagram_length, SickScanImuValue *imValuePtr)
Parsing Ascii datagram.
Definition: sick_generic_imu.cpp:203
sick_generic_imu.h
sick_scan_xd::SickScanImu::quaternion2rpyTest
static void quaternion2rpyTest()
Test barebone implemetation from quaternio to euler (Roll-Pitch-Yaw-Sequence) to avoid problems using...
Definition: sick_generic_imu.cpp:434
rosPublish
void rosPublish(rosPublisher< T > &publisher, const T &msg)
Definition: sick_ros_wrapper.h:203
sick_scan_xd::ExitSuccess
@ ExitSuccess
Definition: abstract_parser.h:46
sick_scan_xd::SickScanImuValue::QuaternionY
float QuaternionY() const
Definition: sick_generic_imu.h:98
sick_scan_xd::SickScanCommon::imuScan_pub_
rosPublisher< ros_sensor_msgs::Imu > imuScan_pub_
Definition: sick_scan_common.h:384
sec
uint32_t sec(const rosTime &time)
Definition: sick_ros_wrapper.h:174
sick_scan_xd::SickScanImuValue::AngularVelocityX
float AngularVelocityX() const
Definition: sick_generic_imu.h:123
sick_scan_xd::SickScanImuValue::AngularVelocityReliability
UINT16 AngularVelocityReliability() const
Definition: sick_generic_imu.h:141
sick_scan_xd::SickScanImu::isImuAckDatagram
bool isImuAckDatagram(char *datagram, size_t datagram_length)
Definition: sick_generic_imu.cpp:136
sick_scan_xd::SickScanImu::isImuBinaryDatagram
bool isImuBinaryDatagram(char *datagram, size_t datagram_length)
Checking ASCII diagram for imu message type.
Definition: sick_generic_imu.cpp:166
sick_scan_xd::SickScanImu
Definition: sick_generic_imu.h:189
sick_scan_xd::SickScanImuValue::LinearAccelerationZ
float LinearAccelerationZ() const
Definition: sick_generic_imu.h:159
sick_scan_xd::SickScanConfig::imu_frame_id
std::string imu_frame_id
Definition: sick_ros_wrapper.h:515
sick_scan_xd::SickScanImuValue::TimeStamp
UINT64 TimeStamp() const
Definition: sick_generic_imu.h:86
ros::Time
sick_scan_xd::SickScanImuValue::QuaternionW
float QuaternionW() const
Definition: sick_generic_imu.h:110
geometry_msgs::Quaternion
::geometry_msgs::Quaternion_< std::allocator< void > > Quaternion
Definition: kinetic/include/geometry_msgs/Quaternion.h:63
dataDumper.h
UINT32
uint32_t UINT32
Definition: BasicDatatypes.hpp:72
sick_scan_xd::SickScanImuValue::QuaternionX
float QuaternionX() const
Definition: sick_generic_imu.h:92
roswrap::message_traits::timeStamp
ros::Time * timeStamp(M &m)
returns TimeStamp<M>::pointer(m);
Definition: message_traits.h:317
DurationBase< Duration >::toSec
double toSec() const
sick_scan_xd::SickScanImuValue::LinearAccelerationX
float LinearAccelerationX() const
Definition: sick_generic_imu.h:147
sick_scan_xd::SickScanImu::imuParserTest
static void imuParserTest()
Definition: sick_generic_imu.cpp:497
sick_scan_xd::SickScanImu::nh
rosNodePtr nh
Definition: sick_generic_imu.h:220
sick_scan_xd::SickScanImuValue
Definition: sick_generic_imu.h:83
sick_scan_xd::SickScanImu::parseDatagram
int parseDatagram(rosTime timeStamp, unsigned char *receiveBuffer, int actual_length, bool useBinaryProtocol)
Definition: sick_generic_imu.cpp:554
ros::Duration
tf::Quaternion
sick_scan_xd::SickScanImu::parseAsciiDatagram
int parseAsciiDatagram(char *datagram, size_t datagram_length, SickScanImuValue *imValuePtr)
Parsing Ascii datagram.
Definition: sick_generic_imu.cpp:299
sick_scan_xd::SickScanImuValue::LinearAccelerationReliability
UINT16 LinearAccelerationReliability() const
Definition: sick_generic_imu.h:165
DataDumper::pushData
int pushData(double timeStamp, std::string info, double val)
Definition: dataDumper.cpp:13
sick_scan_xd::SickScanImuValue::AngularVelocityZ
float AngularVelocityZ() const
Definition: sick_generic_imu.h:135
rosTime
ros::Time rosTime
Definition: sick_ros_wrapper.h:172
sick_scan_xd::SickScanImuValue::QuaternionZ
float QuaternionZ() const
Definition: sick_generic_imu.h:104


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:10