62 #pragma warning(disable: 4996)
63 #pragma warning(disable: 4267)
76 #define _USE_MATH_DEFINES
83 #ifdef DEBUG_DUMP_ENABLED
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++)
145 if (datagram_length >= (keyWordLen + posTrial[iPos]))
148 for (
int i = 0; i < keyWordLen; i++)
150 cmpKeyWord += datagram[i + posTrial[iPos]];
153 if (szKeyWord.compare(cmpKeyWord) == 0)
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))
182 for (
int i = 0; i < keyWordLen; i++)
184 cmpKeyWord += datagram[i + 8];
187 if (szKeyWord.compare(cmpKeyWord) == 0)
208 float tmpArr[13] = {0};
210 unsigned char *receiveBuffer = (
unsigned char *) datagram;
216 unsigned char *bufPtr = (
unsigned char *) datagram;
217 #ifdef DEBUG_DUMP_TO_CONSOLE_ENABLED
220 memcpy(&
timeStamp, receiveBuffer + 36 + 13 * 4, 4);
223 for (
int i = 0; i < 13; i++)
225 memcpy(&(tmpArr[i]), receiveBuffer + adrOffset, 4);
244 float angleVelMultiplier = 1.0f;
274 bool isImuMsg =
false;
275 std::string szKeyWord =
"sSN InertialMeasurementUnit";
276 int keyWordLen = szKeyWord.length();
277 if (datagram_length >= keyWordLen)
281 ptr = strstr(datagram, szKeyWord.c_str());
284 int offset = ptr - datagram;
285 if ((offset == 0) || (offset == 1))
302 bool dumpData =
false;
304 int HEADER_FIELDS = 32;
309 std::vector<char *> fields;
310 fields.reserve(datagram_length / 2);
313 std::vector<char> datagram_copy_vec;
314 datagram_copy_vec.resize(datagram_length + 1);
315 char *datagram_copy = &(datagram_copy_vec[0]);
317 strncpy(datagram_copy, datagram, datagram_length);
318 datagram_copy[datagram_length] = 0;
322 cur_field = strtok(datagram,
" ");
324 while (cur_field !=
NULL)
326 fields.push_back(cur_field);
328 cur_field = strtok(
NULL,
" ");
333 count = fields.size();
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,
345 IMU_TOKEN_ANGULAR_VELOCITY_X,
346 IMU_TOKEN_ANGULAR_VELOCITY_Y,
347 IMU_TOKEN_ANGULAR_VELOCITY_Z,
348 IMU_TOKEN_ANGULAR_VELOCITY_RELIABILITY,
349 IMU_TOKEN_LINEAR_ACCELERATION_X,
350 IMU_TOKEN_LINEAR_ACCELERATION_Y,
351 IMU_TOKEN_LINEAR_ACCELERATION_Z,
352 IMU_TOKEN_LINEAR_ACCELERATION_RELIABILITY,
355 for (
int i = 0; i < IMU_TOKEN_NUM; i++)
359 unsigned long int uliDummy;
360 uliDummy = strtoul(fields[i],
NULL, 16);
364 case IMU_TOKEN_TIMESTAMP:
367 case IMU_TOKEN_QUATERNION_X:
368 memcpy(&floatDummy, &uliDummy,
sizeof(
float));
371 case IMU_TOKEN_QUATERNION_Y:
372 memcpy(&floatDummy, &uliDummy,
sizeof(
float));
375 case IMU_TOKEN_QUATERNION_Z:
376 memcpy(&floatDummy, &uliDummy,
sizeof(
float));
379 case IMU_TOKEN_QUATERNION_W:
380 memcpy(&floatDummy, &uliDummy,
sizeof(
float));
384 case IMU_TOKEN_QUATERNION_ACCURACY:
385 memcpy(&floatDummy, &uliDummy,
sizeof(
float));
388 case IMU_TOKEN_ANGULAR_VELOCITY_X:
389 memcpy(&floatDummy, &uliDummy,
sizeof(
float));
392 case IMU_TOKEN_ANGULAR_VELOCITY_Y:
393 memcpy(&floatDummy, &uliDummy,
sizeof(
float));
396 case IMU_TOKEN_ANGULAR_VELOCITY_Z:
397 memcpy(&floatDummy, &uliDummy,
sizeof(
float));
400 case IMU_TOKEN_ANGULAR_VELOCITY_RELIABILITY:
401 uiValue = (
UINT16) (0xFFFF & uliDummy);
405 case IMU_TOKEN_LINEAR_ACCELERATION_X:
406 memcpy(&floatDummy, &uliDummy,
sizeof(
float));
409 case IMU_TOKEN_LINEAR_ACCELERATION_Y:
410 memcpy(&floatDummy, &uliDummy,
sizeof(
float));
413 case IMU_TOKEN_LINEAR_ACCELERATION_Z:
414 memcpy(&floatDummy, &uliDummy,
sizeof(
float));
417 case IMU_TOKEN_LINEAR_ACCELERATION_RELIABILITY:
418 uiValue = (
UINT16) (0xFFFF & uliDummy);
437 double wxyz_test_vec[] = { 0.723, 0.440, 0.022, -0.532};
448 double roll, pitch, yaw;
449 m.
getRPY(roll, pitch, yaw);
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);
462 double roll, pitch, yaw;
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];
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);
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);
484 angles.pitch = std::asin(sinp);
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);
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);
504 std::string imuTestStr =
"sSN IMUData 34FEEDF 3F7FF800 BBBC0000 3C848000 00000000 00000000 00000000 3B0B9AB1 00000000 3 BE9F6AD9 BDDCBB53 411D2CF1 0";
505 const char imuTestBinStr[] =
528 "\x02\x02\x02\x02\x00\x00\x00\x58"
529 "\x73\x53\x4e\x20\x49\x6e\x65\x72\x74\x69\x61\x6c\x4d\x65"
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";
536 char *datagramPtr = (
char *) imuTestStr.c_str();
537 int datagramLen = imuTestStr.size();
544 datagramPtr = (
char *) imuTestBinStr;
545 datagramLen =
sizeof(imuTestBinStr) /
sizeof(imuTestBinStr[0]);
555 bool useBinaryProtocol)
563 static double lastRoll = 0.0;
564 static double lastPitch = 0.0;
565 static double lastYaw = 0.0;
567 static bool firstTime =
true;
597 if (useBinaryProtocol)
613 (uint32_t) (imuValue.
TimeStamp() & 0xFFFFFFFF));
630 imuMsg_.orientation_covariance[0] = 1.0;
632 double roll, pitch, yaw;
639 imuMsg_.orientation.x,
640 imuMsg_.orientation.y,
641 imuMsg_.orientation.z,
642 imuMsg_.orientation.w);
644 m.
getRPY(roll, pitch, yaw);
645 #else // barebone implementation without include tf.h
652 double roll, pitch, yaw;
656 q.x = imuMsg_.orientation.x;
657 q.y = imuMsg_.orientation.y;
658 q.z = imuMsg_.orientation.z;
659 q.w = imuMsg_.orientation.w;
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);
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);
674 angles.pitch = std::asin(sinp);
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);
698 #ifdef DEBUG_DUMP_ENABLED
720 double timeDiff = timeDiffRos.
toSec();
723 double angleDiffX = roll - lastRoll;
724 double angleDiffY = pitch - lastPitch;
725 double angleDiffZ = yaw - lastYaw;
729 double angleAngleApproxX = angleDiffX / timeDiff;
730 double angleAngleApproxY = angleDiffY / timeDiff;
731 double angleAngleApproxZ = angleDiffZ / timeDiff;
733 imuMsg_.angular_velocity.x = angleAngleApproxX;
734 imuMsg_.angular_velocity.y = angleAngleApproxY;
735 imuMsg_.angular_velocity.z = angleAngleApproxZ;
754 for (
int i = 0; i < 9; i++)
756 imuMsg_.angular_velocity_covariance[i] = 0.00;
757 imuMsg_.linear_acceleration_covariance[i] = 0.00;
758 imuMsg_.orientation_covariance[i] = 0.00;
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;
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;
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;
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;
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;
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;