Go to the documentation of this file.00001
00002
00003
00004
00005 #ifndef SICK_SCAN_SICK_GENERIC_IMU_H
00006 #define SICK_SCAN_SICK_GENERIC_IMU_H
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044 #include <stdio.h>
00045 #include <stdlib.h>
00046 #include <string>
00047 #include <string.h>
00048 #include <vector>
00049
00050 #include <ros/ros.h>
00051 #include <sensor_msgs/LaserScan.h>
00052 #include <sensor_msgs/PointCloud.h>
00053 #include <sensor_msgs/PointCloud2.h>
00054 #include <std_msgs/String.h>
00055
00056 #include <diagnostic_updater/diagnostic_updater.h>
00057 #include <diagnostic_updater/publisher.h>
00058 #include <sick_scan/sick_scan_common_nw.h>
00059 #include <sick_scan/RadarScan.h>
00060
00061 #ifndef _MSC_VER
00062 #include <dynamic_reconfigure/server.h>
00063 #include <sick_scan/SickScanConfig.h>
00064 #endif
00065 #include "sick_scan/sick_generic_parser.h"
00066 #include "sick_scan/sick_scan_common_nw.h"
00067 #include <ros/ros.h>
00068 #include <sensor_msgs/Imu.h>
00069 #include "softwarePLL.h"
00070 namespace sick_scan
00071 {
00072
00073
00074 class SickScanImuValue
00075 {
00076 public:
00077 UINT64 TimeStamp() const { return timeStamp; }
00078 void TimeStamp(UINT64 val) { timeStamp = val; }
00079 float QuaternionX() const { return quaternionX; }
00080 void QuaternionX(float val) { quaternionX = val; }
00081 float QuaternionY() const { return quaternionY; }
00082 void QuaternionY(float val) { quaternionY = val; }
00083 float QuaternionZ() const { return quaternionZ; }
00084 void QuaternionZ(float val) { quaternionZ = val; }
00085 float QuaternionW() const { return quaternionW; }
00086 void QuaternionW(float val) { quaternionW = val; }
00087
00088 float QuaternionAccuracy() const { return quaternionAccuracy; }
00089 void QuaternionAccuracy(float val) { quaternionAccuracy = val; }
00090
00091
00092 float AngularVelocityX() const { return velocityX; }
00093 void AngularVelocityX(float val) { velocityX = val; }
00094 float AngularVelocityY() const { return velocityY; }
00095 void AngularVelocityY(float val) { velocityY = val; }
00096 float AngularVelocityZ() const { return velocityZ; }
00097 void AngularVelocityZ(float val) { velocityZ = val; }
00098
00099 UINT16 AngularVelocityReliability() const {return velocityReliability;}
00100 void AngularVelocityReliability(UINT16 val) {velocityReliability = val;}
00101
00102 float LinearAccelerationX() const { return linearAccelerationX; }
00103 void LinearAccelerationX(float val) { linearAccelerationX = val; }
00104 float LinearAccelerationY() const { return linearAccelerationY; }
00105 void LinearAccelerationY(float val) { linearAccelerationY = val; }
00106 float LinearAccelerationZ() const { return linearAccelerationZ; }
00107 void LinearAccelerationZ(float val) { linearAccelerationZ = val; }
00108
00109 UINT16 LinearAccelerationReliability() const {return linearAccelerationReliability;}
00110 void LinearAccelerationReliability(UINT16 val) {linearAccelerationReliability = val;}
00111
00112 private:
00113 UINT32 timeStamp;
00114 float quaternionX;
00115 float quaternionY;
00116 float quaternionZ;
00117 float quaternionW;
00118 float quaternionAccuracy;
00119 float velocityX;
00120 float velocityY;
00121 float velocityZ;
00122 UINT16 velocityReliability;
00123 float linearAccelerationX;
00124 float linearAccelerationY;
00125 float linearAccelerationZ;
00126 UINT16 linearAccelerationReliability;
00127
00128 };
00129
00130 class SickScanImu
00131 {
00132 public:
00133 SickScanImu(SickScanCommon *commonPtr_)
00134 {
00135 commonPtr = commonPtr_;
00136 }
00137 bool isImuDatagram(char *datagram, size_t datagram_length);
00138 bool isImuBinaryDatagram(char *datagram, size_t datagram_length);
00139 bool isImuAsciiDatagram(char *datagram, size_t datagram_length);
00140 bool isImuAckDatagram(char *datagram, size_t datagram_length);
00141
00142 int parseDatagram(ros::Time timeStamp, unsigned char *receiveBuffer, int actual_length, bool useBinaryProtocol);
00143 int parseAsciiDatagram(char* datagram, size_t datagram_length, SickScanImuValue *imValuePtr);
00144 int parseBinaryDatagram(char* datagram, size_t datagram_length, SickScanImuValue *imValuePtr);
00145 static void imuParserTest();
00146 double simpleFmodTwoPi(double angle);
00147
00148 private:
00149 SickScanCommon *commonPtr;
00150 bool emul;
00151 };
00152
00153 }
00154
00155
00156 #endif //SICK_SCAN_SICK_GENERIC_IMU_H