5 #ifndef SICK_SCAN_SICK_GENERIC_IMU_H 6 #define SICK_SCAN_SICK_GENERIC_IMU_H 51 #include <sensor_msgs/LaserScan.h> 52 #include <sensor_msgs/PointCloud.h> 53 #include <sensor_msgs/PointCloud2.h> 54 #include <std_msgs/String.h> 59 #include <sick_scan/RadarScan.h> 63 #include <dynamic_reconfigure/server.h> 64 #include <sick_scan/SickScanConfig.h> 71 #include <sensor_msgs/Imu.h> 189 commonPtr = commonPtr_;
192 bool isImuDatagram(
char *datagram,
size_t datagram_length);
194 bool isImuBinaryDatagram(
char *datagram,
size_t datagram_length);
196 bool isImuAsciiDatagram(
char *datagram,
size_t datagram_length);
198 bool isImuAckDatagram(
char *datagram,
size_t datagram_length);
200 int parseDatagram(
ros::Time timeStamp,
unsigned char *receiveBuffer,
int actual_length,
bool useBinaryProtocol);
202 int parseAsciiDatagram(
char *datagram,
size_t datagram_length,
SickScanImuValue *imValuePtr);
204 int parseBinaryDatagram(
char *datagram,
size_t datagram_length,
SickScanImuValue *imValuePtr);
206 static void imuParserTest();
208 static void quaternion2rpyTest();
210 double simpleFmodTwoPi(
double angle);
220 #endif //SICK_SCAN_SICK_GENERIC_IMU_H float linearAccelerationX
float linearAccelerationZ
UINT16 LinearAccelerationReliability() const
float AngularVelocityZ() const
void LinearAccelerationReliability(UINT16 val)
float linearAccelerationY
float LinearAccelerationY() const
SickScanCommon * commonPtr
float AngularVelocityX() const
void LinearAccelerationX(float val)
void AngularVelocityY(float val)
void QuaternionAccuracy(float val)
void QuaternionY(float val)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
float QuaternionAccuracy() const
void QuaternionW(float val)
float QuaternionY() const
void LinearAccelerationY(float val)
float LinearAccelerationZ() const
void LinearAccelerationZ(float val)
float AngularVelocityY() const
float QuaternionZ() const
void AngularVelocityReliability(UINT16 val)
float LinearAccelerationX() const
void AngularVelocityX(float val)
void TimeStamp(UINT64 val)
float QuaternionW() const
void AngularVelocityZ(float val)
void QuaternionX(float val)
UINT16 AngularVelocityReliability() const
float QuaternionX() const
void QuaternionZ(float val)
UINT16 linearAccelerationReliability
SickScanImu(SickScanCommon *commonPtr_)
UINT16 velocityReliability