#include <sick_generic_imu.h>
|
bool | isImuAckDatagram (char *datagram, size_t datagram_length) |
|
bool | isImuAsciiDatagram (char *datagram, size_t datagram_length) |
| Checking ASCII diagram for imu message type. More...
|
|
bool | isImuBinaryDatagram (char *datagram, size_t datagram_length) |
| Checking ASCII diagram for imu message type. More...
|
|
bool | isImuDatagram (char *datagram, size_t datagram_length) |
|
int | parseAsciiDatagram (char *datagram, size_t datagram_length, SickScanImuValue *imValuePtr) |
| Parsing Ascii datagram. More...
|
|
int | parseBinaryDatagram (char *datagram, size_t datagram_length, SickScanImuValue *imValuePtr) |
| Parsing Ascii datagram. More...
|
|
int | parseDatagram (ros::Time timeStamp, unsigned char *receiveBuffer, int actual_length, bool useBinaryProtocol) |
|
| SickScanImu (SickScanCommon *commonPtr_) |
|
double | simpleFmodTwoPi (double angle) |
| Checking angle to be in the interval [-M_PI,M_PI] Of course you can also use fmod, e.g. fmod(angle + M_PI,2*M_PI) - M_PI. More...
|
|
|
static void | imuParserTest () |
|
static void | quaternion2rpyTest () |
| Test barebone implemetation from quaternio to euler (Roll-Pitch-Yaw-Sequence) to avoid problems using tf.h against bloom. Include tf.h for a full test and uncomment #0 for this case. More...
|
|
Definition at line 184 of file sick_generic_imu.h.
◆ SickScanImu()
◆ imuParserTest()
void sick_scan::SickScanImu::imuParserTest |
( |
| ) |
|
|
static |
◆ isImuAckDatagram()
bool sick_scan::SickScanImu::isImuAckDatagram |
( |
char * |
datagram, |
|
|
size_t |
datagram_length |
|
) |
| |
◆ isImuAsciiDatagram()
bool sick_scan::SickScanImu::isImuAsciiDatagram |
( |
char * |
datagram, |
|
|
size_t |
datagram_length |
|
) |
| |
Checking ASCII diagram for imu message type.
- Parameters
-
datagram | Pointer to datagram data |
datagram_length | Number of bytes in datagram |
- Returns
- bool flag holding prof result (false -> no ascii imu datagram, true -> ascii imu datagram)
Definition at line 266 of file sick_generic_imu.cpp.
◆ isImuBinaryDatagram()
bool sick_scan::SickScanImu::isImuBinaryDatagram |
( |
char * |
datagram, |
|
|
size_t |
datagram_length |
|
) |
| |
Checking ASCII diagram for imu message type.
- Parameters
-
datagram | Pointer to datagram data |
datagram_length | Number of bytes in datagram |
- Returns
- bool flag holding prof result (false -> no ascii imu datagram, true -> ascii imu datagram)
Definition at line 160 of file sick_generic_imu.cpp.
◆ isImuDatagram()
bool sick_scan::SickScanImu::isImuDatagram |
( |
char * |
datagram, |
|
|
size_t |
datagram_length |
|
) |
| |
◆ parseAsciiDatagram()
int sick_scan::SickScanImu::parseAsciiDatagram |
( |
char * |
datagram, |
|
|
size_t |
datagram_length, |
|
|
SickScanImuValue * |
imuValue |
|
) |
| |
Parsing Ascii datagram.
- Parameters
-
datagram | Pointer to datagram data |
datagram_length | Number of bytes in datagram |
Definition at line 293 of file sick_generic_imu.cpp.
◆ parseBinaryDatagram()
int sick_scan::SickScanImu::parseBinaryDatagram |
( |
char * |
datagram, |
|
|
size_t |
datagram_length, |
|
|
SickScanImuValue * |
imuValue |
|
) |
| |
Parsing Ascii datagram.
- Parameters
-
datagram | Pointer to datagram data |
datagram_length | Number of bytes in datagram |
Definition at line 197 of file sick_generic_imu.cpp.
◆ parseDatagram()
int sick_scan::SickScanImu::parseDatagram |
( |
ros::Time |
timeStamp, |
|
|
unsigned char * |
receiveBuffer, |
|
|
int |
actual_length, |
|
|
bool |
useBinaryProtocol |
|
) |
| |
◆ quaternion2rpyTest()
void sick_scan::SickScanImu::quaternion2rpyTest |
( |
| ) |
|
|
static |
Test barebone implemetation from quaternio to euler (Roll-Pitch-Yaw-Sequence) to avoid problems using tf.h against bloom. Include tf.h for a full test and uncomment #0 for this case.
Definition at line 437 of file sick_generic_imu.cpp.
◆ simpleFmodTwoPi()
double sick_scan::SickScanImu::simpleFmodTwoPi |
( |
double |
angle | ) |
|
Checking angle to be in the interval [-M_PI,M_PI] Of course you can also use fmod, e.g. fmod(angle + M_PI,2*M_PI) - M_PI.
- Parameters
-
angle | Input angle to be checked |
- Returns
- normalized angle value (normalized means here the interval -M_PI,M_PI)
Definition at line 117 of file sick_generic_imu.cpp.
◆ commonPtr
◆ emul
bool sick_scan::SickScanImu::emul |
|
private |
The documentation for this class was generated from the following files: