sick_generic_imu.cpp
Go to the documentation of this file.
00001 
00045 #ifdef _MSC_VER
00046 #define _WIN32_WINNT 0x0501
00047 #pragma warning(disable: 4996)
00048 #pragma warning(disable: 4267)
00049 #endif
00050 
00051 #ifndef _MSC_VER
00052 
00053 
00054 #endif
00055 
00056 #include <sick_scan/sick_scan_common_tcp.h>
00057 #include <sick_scan/sick_scan_common.h>
00058 #include <sick_scan/sick_generic_parser.h>
00059 #include <sick_scan/sick_generic_imu.h>
00060 
00061 #ifdef _MSC_VER
00062 #include "sick_scan/rosconsole_simu.hpp"
00063 #endif
00064 
00065 #include <tf/tf.h>
00066 #include <geometry_msgs/Pose2D.h>
00067 
00068 #include "sensor_msgs/Imu.h"
00069 
00070 #define _USE_MATH_DEFINES
00071 
00072 #include <math.h>
00073 #include "string"
00074 #include <stdio.h>
00075 #include <stdlib.h>
00076 
00077 #ifdef DEBUG_DUMP_ENABLED
00078 #include "sick_scan/dataDumper.h"
00079 #endif
00080 namespace sick_scan
00081 {
00082 
00083     bool SickScanImu::isImuDatagram(char *datagram, size_t datagram_length)
00084     {
00085         bool ret = false;
00086         if (this->isImuBinaryDatagram(datagram, datagram_length))
00087         {
00088             ret = true;
00089         } else
00090         {
00091             if (this->isImuAsciiDatagram(datagram, datagram_length))
00092             {
00093                 ret = true;
00094             } else
00095             {
00096                 if (this->isImuAckDatagram(datagram, datagram_length))
00097                 {
00098                     ret = true;
00099                 }
00100             }
00101         }
00102 
00103         return (ret);
00104     }
00105 
00106 
00113     double SickScanImu::simpleFmodTwoPi(double angle)
00114     {
00115         while (angle < M_PI)
00116         {
00117             angle += 2 * M_PI;
00118         }
00119         while (angle > M_PI)
00120         {
00121             angle -= 2 * M_PI;
00122         }
00123         return (angle);
00124     }
00125 
00126     bool SickScanImu::isImuAckDatagram(char *datagram, size_t datagram_length)
00127     {
00128         bool isImuMsg = false;
00129         std::string szKeyWord = "sEA InertialMeasurementUnit";
00130         std::string cmpKeyWord = "";
00131         int keyWordLen = szKeyWord.length();
00132         int posTrial[] = {0, 1, 8};
00133         for (int iPos = 0; iPos < sizeof(posTrial) / sizeof(posTrial[0]); iPos++)
00134 
00135             if (datagram_length >= (keyWordLen + posTrial[iPos])) // 8 Bytes preheader
00136             {
00137                 cmpKeyWord = "";
00138                 for (int i = 0; i < keyWordLen; i++)
00139                 {
00140                     cmpKeyWord += datagram[i + posTrial[iPos]];
00141                 }
00142             }
00143         if (szKeyWord.compare(cmpKeyWord) == 0)
00144         {
00145             isImuMsg = true;
00146         }
00147         return (isImuMsg);
00148     }
00149 
00156     bool SickScanImu::isImuBinaryDatagram(char *datagram, size_t datagram_length)
00157     {
00158         /*
00159          * sSN InertialM
00160 06b0  65 61 73 75 72 65 6d 65 6e 74 55 6e 69 74 20 be   easurementUnit .
00161 06c0  9d 86 2d bb 9c e9 44 41 1c 33 d6 bb 0b a1 6f 00   ..-...DA.3....o.
00162 06d0  00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00   ................
00163 06e0  00 00 00 3f 7f ec 00 3a 60 00 00 3c cd 00 00 39   ...?...:`..<...9
00164 06f0  a0 00 00 00 00 00 02 1c 7e 93 a8 23
00165          */
00166         bool isImuMsg = false;
00167         std::string szKeyWord = "sSN InertialMeasurementUnit";
00168         std::string cmpKeyWord = "";
00169         int keyWordLen = szKeyWord.length();
00170         if (datagram_length >= (keyWordLen + 8)) // 8 Bytes preheader
00171         {
00172             for (int i = 0; i < keyWordLen; i++)
00173             {
00174                 cmpKeyWord += datagram[i + 8];
00175             }
00176         }
00177         if (szKeyWord.compare(cmpKeyWord) == 0)
00178         {
00179             isImuMsg = true;
00180         } else
00181         {
00182             isImuMsg = false;
00183         }
00184         return (isImuMsg);
00185     }
00186 
00192     int SickScanImu::parseBinaryDatagram(char *datagram, size_t datagram_length, SickScanImuValue *imuValue)
00193     {
00194         static int cnt = 0;
00195         cnt++;
00196         int iRet = 0;
00197         float tmpArr[13] = {0};
00198         uint64_t timeStamp;
00199         unsigned char *receiveBuffer = (unsigned char *) datagram;
00200         if (false == isImuBinaryDatagram(datagram, datagram_length))
00201         {
00202             return (-1);
00203         }
00204 
00205         unsigned char *bufPtr = (unsigned char *) datagram;
00206 #ifdef DEBUG_DUMP_TO_CONSOLE_ENABLED
00207         DataDumper::instance().dumpUcharBufferToConsole((unsigned char*)datagram, datagram_length);
00208 #endif
00209         memcpy(&timeStamp, receiveBuffer + 36 + 13 * 4, 8);
00210         swap_endian((unsigned char *) &timeStamp, 8);
00211         int adrOffset = 36;
00212         for (int i = 0; i < 13; i++)
00213         {
00214             memcpy(&(tmpArr[i]), receiveBuffer + adrOffset, 4);
00215             swap_endian((unsigned char *) (&(tmpArr[i])), 4);
00216             adrOffset += 4;
00217 
00218 //            if ((cnt % 10) == 0)
00219 //           {
00220 //                if (i == 0)
00221 //                {
00222 //                    printf("===================\n");
00223 //                }
00224 //                printf("%2d: %8.6f\n", i, tmpArr[i]);
00225 //            }
00226         }
00227 
00228         imuValue->LinearAccelerationX(tmpArr[0]);
00229         imuValue->LinearAccelerationY(tmpArr[1]);
00230         imuValue->LinearAccelerationZ(tmpArr[2]);
00231 
00232 
00233         double angleVelMultiplier = 1.0;
00234         imuValue->AngularVelocityX(angleVelMultiplier * tmpArr[3]);
00235         imuValue->AngularVelocityY(angleVelMultiplier * tmpArr[4]);
00236         imuValue->AngularVelocityZ(angleVelMultiplier * tmpArr[5]);
00237 
00238         imuValue->TimeStamp(timeStamp);
00239 
00240 
00241         imuValue->QuaternionW(tmpArr[9]);  // w is first element
00242         imuValue->QuaternionX(tmpArr[10]);
00243         imuValue->QuaternionY(tmpArr[11]);
00244         imuValue->QuaternionZ(tmpArr[12]);
00245 
00246         imuValue->QuaternionAccuracy(0.0); // not used tmpArr[4]);
00247 
00248 
00249         uint8_t val = 0x00;
00250         imuValue->AngularVelocityReliability((UINT16) val);
00251         imuValue->LinearAccelerationReliability((UINT16) val);
00252         return (iRet);
00253     }
00254 
00261     bool SickScanImu::isImuAsciiDatagram(char *datagram, size_t datagram_length)
00262     {
00263         bool isImuMsg = false;
00264         std::string szKeyWord = "sSN InertialMeasurementUnit";
00265         int keyWordLen = szKeyWord.length();
00266         if (datagram_length >= keyWordLen)
00267         {
00268 
00269             char *ptr = NULL;
00270             ptr = strstr(datagram, szKeyWord.c_str());
00271             if (ptr != NULL)
00272             {
00273                 int offset = ptr - datagram;
00274                 if ((offset == 0) || (offset == 1)) // should work with 0x02 and without 0x02
00275                 {
00276                     isImuMsg = true;
00277                 }
00278             }
00279         }
00280         return (isImuMsg);
00281     }
00282 
00288     int SickScanImu::parseAsciiDatagram(char *datagram, size_t datagram_length, SickScanImuValue *imuValue)
00289     {
00290         int exitCode = ExitSuccess;
00291         bool dumpData = false;
00292         int verboseLevel = 0;
00293 
00294         // !!!!!
00295         // verboseLevel = 1;
00296         int HEADER_FIELDS = 32;
00297         char *cur_field;
00298         size_t count;
00299 
00300         // Reserve sufficient space
00301         std::vector<char *> fields;
00302         fields.reserve(datagram_length / 2);
00303 
00304         // ----- only for debug output
00305         std::vector<char> datagram_copy_vec;
00306         datagram_copy_vec.resize(datagram_length + 1); // to avoid using malloc. destructor frees allocated mem.
00307         char *datagram_copy = &(datagram_copy_vec[0]);
00308 
00309         if (verboseLevel > 0)
00310         {
00311             ROS_WARN("Verbose LEVEL activated. Only for DEBUG.");
00312         }
00313 
00314 
00315         strncpy(datagram_copy, datagram, datagram_length); // datagram will be changed by strtok
00316         datagram_copy[datagram_length] = 0;
00317 
00318         // ----- tokenize
00319         count = 0;
00320         cur_field = strtok(datagram, " ");
00321 
00322         while (cur_field != NULL)
00323         {
00324             fields.push_back(cur_field);
00325             //std::cout << cur_field << std::endl;
00326             cur_field = strtok(NULL, " ");
00327         }
00328 
00329         //std::cout << fields[27] << std::endl;
00330 
00331         count = fields.size();
00332 
00333         enum IMU_TOKEN_SEQ // see specification
00334         {
00335             IMU_TOKEN_SSN,          // 0: sSN
00336             IMU_TOKEN_IMUDATA, // 1: LMDradardata
00337             IMU_TOKEN_TIMESTAMP,  // unsigned long value timestamp
00338             IMU_TOKEN_QUATERNION_W,
00339             IMU_TOKEN_QUATERNION_X,
00340             IMU_TOKEN_QUATERNION_Y,
00341             IMU_TOKEN_QUATERNION_Z,
00342             IMU_TOKEN_QUATERNION_ACCURACY, // float value
00343             IMU_TOKEN_ANGULAR_VELOCITY_X,
00344             IMU_TOKEN_ANGULAR_VELOCITY_Y,
00345             IMU_TOKEN_ANGULAR_VELOCITY_Z,
00346             IMU_TOKEN_ANGULAR_VELOCITY_RELIABILITY, // int value
00347             IMU_TOKEN_LINEAR_ACCELERATION_X,
00348             IMU_TOKEN_LINEAR_ACCELERATION_Y,
00349             IMU_TOKEN_LINEAR_ACCELERATION_Z,
00350             IMU_TOKEN_LINEAR_ACCELERATION_RELIABILITY, // int value
00351             IMU_TOKEN_NUM
00352         };
00353         for (int i = 0; i < IMU_TOKEN_NUM; i++)
00354         {
00355             UINT16 uiValue = 0x00;
00356             UINT32 udiValue = 0x00;
00357             unsigned long int uliDummy;
00358             uliDummy = strtoul(fields[i], NULL, 16);
00359             float floatDummy;
00360             switch (i)
00361             {
00362                 case IMU_TOKEN_TIMESTAMP:
00363                     imuValue->TimeStamp(uliDummy);
00364                     break;
00365                 case IMU_TOKEN_QUATERNION_X:
00366                     memcpy(&floatDummy, &uliDummy, sizeof(float));
00367                     imuValue->QuaternionX(floatDummy);  // following IEEE 754 float convention
00368                     break;
00369                 case IMU_TOKEN_QUATERNION_Y:
00370                     memcpy(&floatDummy, &uliDummy, sizeof(float));
00371                     imuValue->QuaternionY(floatDummy);
00372                     break;
00373                 case IMU_TOKEN_QUATERNION_Z:
00374                     memcpy(&floatDummy, &uliDummy, sizeof(float));
00375                     imuValue->QuaternionZ(floatDummy);
00376                     break;
00377                 case IMU_TOKEN_QUATERNION_W:
00378                     memcpy(&floatDummy, &uliDummy, sizeof(float));
00379                     imuValue->QuaternionW(floatDummy);
00380                     break;
00381 
00382                 case IMU_TOKEN_QUATERNION_ACCURACY: // float value
00383                     memcpy(&floatDummy, &uliDummy, sizeof(float));
00384                     imuValue->QuaternionAccuracy(floatDummy);
00385                     break;
00386                 case IMU_TOKEN_ANGULAR_VELOCITY_X:
00387                     memcpy(&floatDummy, &uliDummy, sizeof(float));
00388                     imuValue->AngularVelocityX(floatDummy);
00389                     break;
00390                 case IMU_TOKEN_ANGULAR_VELOCITY_Y:
00391                     memcpy(&floatDummy, &uliDummy, sizeof(float));
00392                     imuValue->AngularVelocityY(floatDummy);
00393                     break;
00394                 case IMU_TOKEN_ANGULAR_VELOCITY_Z:
00395                     memcpy(&floatDummy, &uliDummy, sizeof(float));
00396                     imuValue->AngularVelocityZ(floatDummy);
00397                     break;
00398                 case IMU_TOKEN_ANGULAR_VELOCITY_RELIABILITY:
00399                     uiValue = (UINT16) (0xFFFF & uliDummy);
00400                     imuValue->AngularVelocityReliability(
00401                             uiValue);  // per definition is a 8 bit value, but we use a 16 bit value
00402                     break;
00403                 case IMU_TOKEN_LINEAR_ACCELERATION_X:
00404                     memcpy(&floatDummy, &uliDummy, sizeof(float));
00405                     imuValue->LinearAccelerationX(floatDummy);
00406                     break;
00407                 case IMU_TOKEN_LINEAR_ACCELERATION_Y:
00408                     memcpy(&floatDummy, &uliDummy, sizeof(float));
00409                     imuValue->LinearAccelerationY(floatDummy);
00410                     break;
00411                 case IMU_TOKEN_LINEAR_ACCELERATION_Z:
00412                     memcpy(&floatDummy, &uliDummy, sizeof(float));
00413                     imuValue->LinearAccelerationZ(floatDummy);
00414                     break;
00415                 case IMU_TOKEN_LINEAR_ACCELERATION_RELIABILITY:
00416                     uiValue = (UINT16) (0xFFFF & uliDummy);
00417                     imuValue->LinearAccelerationReliability(
00418                             uiValue);  // per definition is a 8 bit value, but we use a 16 bit value
00419                     break;
00420 
00421             }
00422         }
00423         return (0);
00424     }
00425 
00426     void SickScanImu::imuParserTest()
00427     {
00428         sick_scan::SickScanImu scanImu(NULL);
00429         sick_scan::SickScanImuValue imuValue;
00430         //                                             checked with online converter
00431         //                                             https://www.h-schmidt.net/FloatConverter/IEEE754de.html
00432         //                                    55570143 0.9998779 -0.0057373047 0.016174316  0.0 0.0 0.002130192             -0.31136206 -0.10777917 9.823472
00433         std::string imuTestStr = "sSN IMUData 34FEEDF 3F7FF800 BBBC0000 3C848000 00000000 00000000 00000000 3B0B9AB1 00000000 3 BE9F6AD9 BDDCBB53 411D2CF1 0";
00434         const char imuTestBinStr[] =
00435 
00436 /*
00437  *      02 02 02 02 00 00   ................
00438         0640  00 58
00439         73 53 4e 20 49 6e 65 72 74 69 61 6c 4d 65   .XsSN InertialMe
00440         0650  61 73 75 72 65 6d 65 6e 74 55 6e 69 74 20 be a4   asurementUnit ..
00441         0660  e1 1c 3b 6b 5d e5 41 1c 6e ad bb 0b a1 6f bb 0b   ..;k].A.n....o..
00442         0670  a1 6f 00 00 00 00 00 00 00 00 00 00 00 00 00 00   .o..............
00443         0680  00 00 3f 7f ec 00 3a 60 00 00 3c cd 00 00 39 a0   ..?...:`..<...9.
00444         0690  00 00 00 00 00 02 1c 7e 6c 01 20
00445 
00446         56 Data Bytes + 2 Byte Timestamp + CRC
00447         14 Float + 4 Byte CRC
00448 
00449         3 Acceleratoin = 12 Bytes
00450         3 AngularVelocity = 12
00451         Magnetic Field = 12 Bytes
00452         Orientatoin = 16 Bytes
00453         TimeStamp = 4
00454         Sum: 12 + 12 + 12 + 16 + 4 = 56 Bytes
00455 
00456 */
00457         "\x02\x02\x02\x02\x00\x00\x00\x58"  // 8 Byte Header
00458         "\x73\x53\x4e\x20\x49\x6e\x65\x72\x74\x69\x61\x6c\x4d\x65"  //  Keyword
00459         "\x61\x73\x75\x72\x65\x6d\x65\x6e\x74\x55\x6e\x69\x74\x20\xbe\xa4"
00460         "\xe1\x1c\x3b\x6b\x5d\xe5\x41\x1c\x6e\xad\xbb\x0b\xa1\x6f\xbb\x0b"
00461         "\xa1\x6f\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"
00462         "\x00\x00\x3f\x7f\xec\x00\x3a\x60\x00\x00\x3c\xcd\x00\x00\x39\xa0"
00463         "\x00\x00\x00\x00\x00\x02\x1c\x7e\x6c\x01\x20";
00464 
00465         char *datagramPtr = (char *) imuTestStr.c_str();
00466         int datagramLen = imuTestStr.size();
00467 
00468         if (scanImu.isImuAsciiDatagram(datagramPtr, datagramLen))
00469         {
00470             scanImu.parseAsciiDatagram(datagramPtr, datagramLen, &imuValue);
00471         }
00472 
00473         datagramPtr = (char *) imuTestBinStr;
00474         datagramLen = sizeof(imuTestBinStr) / sizeof(imuTestBinStr[0]);
00475 
00476         if (scanImu.isImuBinaryDatagram(datagramPtr, datagramLen))
00477         {
00478             scanImu.parseBinaryDatagram(datagramPtr, datagramLen, &imuValue);
00479         }
00480 
00481     }
00482 
00483     int SickScanImu::parseDatagram(ros::Time timeStamp, unsigned char *receiveBuffer, int actual_length,
00484                                    bool useBinaryProtocol)
00485     {
00486         int exitCode = ExitSuccess;
00487 
00488         SickScanImuValue imuValue;
00489         sensor_msgs::Imu imuMsg_;
00490       static ros::Time lastTimeStamp;
00491 
00492       static double lastRoll = 0.0;
00493       static double lastPitch = 0.0;
00494       static double lastYaw = 0.0;
00495 
00496       static bool firstTime = true;
00497         /*
00498         static int cnt = 0;
00499         static u_int32_t timeStampSecBuffer[1000];
00500         static u_int32_t timeStampNanoSecBuffer[1000];
00501         static u_int32_t timeStampSecCorBuffer[1000];
00502         static u_int32_t timeStampNanoSecCorBuffer[1000];
00503         static u_int32_t imuTimeStamp[1000];
00504         static int timeStampValid[1000];
00505 
00506         int idx = cnt % 1000;
00507         cnt++;
00508 
00509         int dumpIdx = 500;
00510         if (cnt == dumpIdx)
00511         {
00512             printf("TICK;TS_SEC;TS_NANO;TS;TS_CORR_SEC;TS_CORR_NANO;TS_CORR;TS_DIFF;TS_VALID\n");
00513 
00514             for (int i = 0; i < dumpIdx; i++)
00515             {
00516                 double tsDouble = timeStampSecBuffer[i] + 1E-9 * timeStampNanoSecBuffer[i];
00517                 double tsDoubleCorr = timeStampSecCorBuffer[i] + 1E-9 * timeStampNanoSecCorBuffer[i];
00518                 double tsDiff = tsDouble - tsDoubleCorr;
00519                 printf("%10u;%10u;%10u;%16.8lf;%10u;%10u;%16.8lf;%16.8lf;%d\n",
00520                        imuTimeStamp[i],
00521                        timeStampSecBuffer[i], timeStampNanoSecBuffer[i], tsDouble,
00522                        timeStampSecCorBuffer[i], timeStampNanoSecCorBuffer[i], tsDoubleCorr, tsDiff, timeStampValid[i]);
00523             }
00524         }
00525          */
00526         if (useBinaryProtocol)
00527         {
00528             this->parseBinaryDatagram((char *) receiveBuffer, actual_length, &imuValue);
00529 
00530         } else
00531         {
00532             this->parseAsciiDatagram((char *) receiveBuffer, actual_length, &imuValue);
00533         }
00534         /*
00535         timeStampSecBuffer[idx] = timeStamp.sec;
00536         timeStampNanoSecBuffer[idx] = timeStamp.nsec;
00537         imuTimeStamp[idx] = imuValue.TimeStamp();
00538 */
00539           bool bRet = SoftwarePLL::instance().getCorrectedTimeStamp(timeStamp.sec, timeStamp.nsec,(uint32_t)(imuValue.TimeStamp()&0xFFFFFFFF));
00540         /*
00541         timeStampSecCorBuffer[idx] = timeStamp.sec;
00542         timeStampNanoSecCorBuffer[idx] = timeStamp.nsec;
00543         timeStampValid[idx] = bRet ? 1 : 0;
00544         */
00545         imuMsg_.header.stamp = timeStamp;
00546         imuMsg_.header.seq = 0;
00547         imuMsg_.header.frame_id = commonPtr->config_.imu_frame_id; //
00548 
00549 
00550 
00551         imuMsg_.orientation.x = imuValue.QuaternionX();
00552         imuMsg_.orientation.y = imuValue.QuaternionY();
00553         imuMsg_.orientation.z = imuValue.QuaternionZ();
00554         imuMsg_.orientation.w = imuValue.QuaternionW();
00555         imuMsg_.orientation_covariance[0] = 1.0;
00556 
00557         tf::Quaternion qOrientation(
00558                 imuMsg_.orientation.x,
00559                 imuMsg_.orientation.y,
00560                 imuMsg_.orientation.z,
00561                 imuMsg_.orientation.w);
00562         tf::Matrix3x3 m(qOrientation);
00563         double roll, pitch, yaw;
00564         m.getRPY(roll, pitch, yaw); // convert to roll pitch yaw and try to derive Angular Velocity from these values
00565 
00566         imuMsg_.angular_velocity.x = imuValue.AngularVelocityX();
00567         imuMsg_.angular_velocity.y = imuValue.AngularVelocityY();
00568         imuMsg_.angular_velocity.z = imuValue.AngularVelocityZ();
00569 #if 0
00570         if (firstTime)
00571         {
00572             lastTimeStamp = timeStamp;
00573             firstTime = false;
00574         }
00575         else
00576         {
00577 
00578           #ifdef DEBUG_DUMP_ENABLED
00579           /*
00580           float LinearAccelerationX() const { return linearAccelerationX; }
00581           void LinearAccelerationX(float val) { linearAccelerationX = val; }
00582           float LinearAccelerationY() const { return linearAccelerationY; }
00583           void LinearAccelerationY(float val) { linearAccelerationY = val; }
00584           float LinearAccelerationZ() const { return linearAccelerationZ; }
00585           void LinearAccelerationZ(float val) { linearAccelerationZ = val; }
00586            */
00587           DataDumper::instance().pushData((double)imuValue.TimeStamp(), "ACCX", imuValue.LinearAccelerationX());
00588           DataDumper::instance().pushData((double)imuValue.TimeStamp(), "ACCY", imuValue.LinearAccelerationY());
00589           DataDumper::instance().pushData((double)imuValue.TimeStamp(), "ACCZ", imuValue.LinearAccelerationZ());
00590           #endif
00591             /*
00592              * The built-in IMU unit provides three parameter sets:
00593              * quaternions, angular velocity and linear accelerations.
00594              * The angular velocities give noisy data without offset compensation (i.e. with drift).
00595              * For this reason, the angular velocities are derived from the quaternions. The quaternions are converted
00596              * into Euler angles for this purpose. The angular velocity is then calculated from these
00597              * sequential Euler angles.
00598              */
00599             ros::Duration timeDiffRos = timeStamp - lastTimeStamp;
00600             double timeDiff = timeDiffRos.toSec();
00601             if (timeDiff > 1E-6) // Epsilon-Check
00602             {
00603                 double angleDiffX = roll - lastRoll;
00604                 double angleDiffY = pitch - lastPitch;
00605                 double angleDiffZ = yaw - lastYaw;
00606                 angleDiffX = simpleFmodTwoPi(angleDiffX);
00607                 angleDiffY = simpleFmodTwoPi(angleDiffY);
00608                 angleDiffZ = simpleFmodTwoPi(angleDiffZ);
00609                 double angleAngleApproxX = angleDiffX / timeDiff;
00610                 double angleAngleApproxY = angleDiffY / timeDiff;
00611                 double angleAngleApproxZ = angleDiffZ / timeDiff;
00612 
00613                 imuMsg_.angular_velocity.x = angleAngleApproxX;
00614                 imuMsg_.angular_velocity.y = angleAngleApproxY;
00615                 imuMsg_.angular_velocity.z = angleAngleApproxZ;
00616 
00617             }
00618         }
00619         lastTimeStamp = timeStamp;
00620         lastRoll = roll;
00621         lastPitch = pitch;
00622         lastYaw = yaw;
00623 #endif
00624         imuMsg_.linear_acceleration.x = imuValue.LinearAccelerationX();
00625         imuMsg_.linear_acceleration.y = imuValue.LinearAccelerationY();
00626         imuMsg_.linear_acceleration.z = imuValue.LinearAccelerationZ();
00627         // setting main diagonal elements of covariance matrix
00628         // to some meaningful values.
00629         // see https://github.com/ROBOTIS-GIT/OpenCR/blob/master/arduino/opencr_arduino/opencr/libraries/ROS/examples/01.%20Basics/d_IMU/d_IMU.ino
00630         // as a reference.
00631 
00632 
00633 
00634         for (int i = 0; i < 9; i++)
00635         {
00636             imuMsg_.angular_velocity_covariance[i] = 0.00;
00637             imuMsg_.linear_acceleration_covariance[i] = 0.00;
00638             imuMsg_.orientation_covariance[i] = 0.00;
00639 
00640         }
00641 
00642         if(commonPtr->config_.cloud_output_mode==2)
00643         {
00644           imuMsg_.angular_velocity_covariance[0] = 0.02;
00645           imuMsg_.angular_velocity_covariance[1] = 0;
00646           imuMsg_.angular_velocity_covariance[2] = 0;
00647           imuMsg_.angular_velocity_covariance[3] = 0;
00648           imuMsg_.angular_velocity_covariance[4] = 0.02;
00649           imuMsg_.angular_velocity_covariance[5] = 0;
00650           imuMsg_.angular_velocity_covariance[6] = 0;
00651           imuMsg_.angular_velocity_covariance[7] = 0;
00652           imuMsg_.angular_velocity_covariance[8] = 0.02;
00653 
00654           imuMsg_.linear_acceleration_covariance[0] = 0.04;
00655           imuMsg_.linear_acceleration_covariance[1] = 0;
00656           imuMsg_.linear_acceleration_covariance[2] = 0;
00657           imuMsg_.linear_acceleration_covariance[3] = 0;
00658           imuMsg_.linear_acceleration_covariance[4] = 0.04;
00659           imuMsg_.linear_acceleration_covariance[5] = 0;
00660           imuMsg_.linear_acceleration_covariance[6] = 0;
00661           imuMsg_.linear_acceleration_covariance[7] = 0;
00662           imuMsg_.linear_acceleration_covariance[8] = 0.04;
00663 
00664           imuMsg_.orientation_covariance[0] = 0.0025;
00665           imuMsg_.orientation_covariance[1] = 0;
00666           imuMsg_.orientation_covariance[2] = 0;
00667           imuMsg_.orientation_covariance[3] = 0;
00668           imuMsg_.orientation_covariance[4] = 0.0025;
00669           imuMsg_.orientation_covariance[5] = 0;
00670           imuMsg_.orientation_covariance[6] = 0;
00671           imuMsg_.orientation_covariance[7] = 0;
00672           imuMsg_.orientation_covariance[8] = 0.0025;
00673         }
00674         else
00675         {
00676           imuMsg_.angular_velocity_covariance[0] = 0;
00677           imuMsg_.angular_velocity_covariance[1] = 0;
00678           imuMsg_.angular_velocity_covariance[2] = 0;
00679           imuMsg_.angular_velocity_covariance[3] = 0;
00680           imuMsg_.angular_velocity_covariance[4] = 0;
00681           imuMsg_.angular_velocity_covariance[5] = 0;
00682           imuMsg_.angular_velocity_covariance[6] = 0;
00683           imuMsg_.angular_velocity_covariance[7] = 0;
00684           imuMsg_.angular_velocity_covariance[8] = 0;
00685 
00686           imuMsg_.linear_acceleration_covariance[0] = 0;
00687           imuMsg_.linear_acceleration_covariance[1] = 0;
00688           imuMsg_.linear_acceleration_covariance[2] = 0;
00689           imuMsg_.linear_acceleration_covariance[3] = 0;
00690           imuMsg_.linear_acceleration_covariance[4] = 0;
00691           imuMsg_.linear_acceleration_covariance[5] = 0;
00692           imuMsg_.linear_acceleration_covariance[6] = 0;
00693           imuMsg_.linear_acceleration_covariance[7] = 0;
00694           imuMsg_.linear_acceleration_covariance[8] = 0;
00695 
00696           imuMsg_.orientation_covariance[0] = -1;
00697           imuMsg_.orientation_covariance[1] = 0;
00698           imuMsg_.orientation_covariance[2] = 0;
00699           imuMsg_.orientation_covariance[3] = 0;
00700           imuMsg_.orientation_covariance[4] = 0;
00701           imuMsg_.orientation_covariance[5] = 0;
00702           imuMsg_.orientation_covariance[6] = 0;
00703           imuMsg_.orientation_covariance[7] = 0;
00704           imuMsg_.orientation_covariance[8] = 0;
00705 
00706           imuMsg_.orientation.x = 0;
00707           imuMsg_.orientation.y = 0;
00708           imuMsg_.orientation.z = 0;
00709           imuMsg_.orientation.w = 0;
00710         }
00711         if (true == bRet)
00712             this->commonPtr->imuScan_pub_.publish(imuMsg_);
00713         return (exitCode);
00714 
00715     }
00716 }
00717 


sick_scan
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Tue Jul 9 2019 05:05:34