Go to the documentation of this file.
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>
200 int parseDatagram(
ros::Time timeStamp,
unsigned char *receiveBuffer,
int actual_length,
bool useBinaryProtocol);
220 #endif //SICK_SCAN_SICK_GENERIC_IMU_H
void LinearAccelerationReliability(UINT16 val)
static void imuParserTest()
float QuaternionAccuracy() const
float linearAccelerationY
bool isImuDatagram(char *datagram, size_t datagram_length)
UINT16 linearAccelerationReliability
void QuaternionY(float val)
UINT16 velocityReliability
float linearAccelerationX
void QuaternionW(float val)
float LinearAccelerationY() const
float QuaternionZ() const
float QuaternionW() const
float LinearAccelerationX() const
void LinearAccelerationY(float val)
void LinearAccelerationX(float val)
static void quaternion2rpyTest()
Test barebone implemetation from quaternio to euler (Roll-Pitch-Yaw-Sequence) to avoid problems using...
void AngularVelocityY(float val)
int parseAsciiDatagram(char *datagram, size_t datagram_length, SickScanImuValue *imValuePtr)
Parsing Ascii datagram.
void QuaternionAccuracy(float val)
void AngularVelocityReliability(UINT16 val)
void AngularVelocityX(float val)
float AngularVelocityX() const
bool isImuBinaryDatagram(char *datagram, size_t datagram_length)
Checking ASCII diagram for imu message type.
SickScanImu(SickScanCommon *commonPtr_)
int parseDatagram(ros::Time timeStamp, unsigned char *receiveBuffer, int actual_length, bool useBinaryProtocol)
double simpleFmodTwoPi(double angle)
Checking angle to be in the interval [-M_PI,M_PI] Of course you can also use fmod,...
void TimeStamp(UINT64 val)
int parseBinaryDatagram(char *datagram, size_t datagram_length, SickScanImuValue *imValuePtr)
Parsing Ascii datagram.
bool isImuAckDatagram(char *datagram, size_t datagram_length)
float LinearAccelerationZ() const
float QuaternionY() const
float AngularVelocityZ() const
void QuaternionX(float val)
UINT16 AngularVelocityReliability() const
SickScanCommon * commonPtr
void LinearAccelerationZ(float val)
float AngularVelocityY() const
void QuaternionZ(float val)
UINT16 LinearAccelerationReliability() const
float QuaternionX() const
bool isImuAsciiDatagram(char *datagram, size_t datagram_length)
Checking ASCII diagram for imu message type.
float linearAccelerationZ
void AngularVelocityZ(float val)
sick_scan
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Thu Sep 8 2022 02:30:19