#include <DMU11.h>
Definition at line 21 of file DMU11.h.
Constructor.
- Parameters
-
Definition at line 8 of file DMU11.cpp.
int16_t DMU11::big_endian_to_short |
( |
unsigned char * |
data | ) |
|
change big endian 2 byte into short
- Parameters
-
data | Head pointer to the data converted value |
Definition at line 191 of file DMU11.cpp.
void DMU11::closePort |
( |
| ) |
|
void DMU11::doParsing |
( |
int16_t * |
int16buff | ) |
|
Gets the raw data and converts them to standard ROS IMU message.
- Parameters
-
Definition at line 203 of file DMU11.cpp.
Open device.
- Return values
-
Definition at line 30 of file DMU11.cpp.
float DMU11::short_to_float |
( |
int16_t * |
data | ) |
|
change big endian short into float
- Parameters
-
data | Head pointer to the data converted value |
Definition at line 197 of file DMU11.cpp.
Read the data received on serial port.
Definition at line 128 of file DMU11.cpp.
struct termios DMU11::defaults_ |
|
private |
std::string DMU11::device_ |
|
private |
int DMU11::file_descriptor_ |
|
private |
std::string DMU11::frame_id_ |
|
private |
const double DMU11::g_ = 9.80665 |
|
private |
int16_t DMU11::header_ = 0x55aa |
|
private |
sensor_msgs::Imu DMU11::imu_raw_ |
dmu_ros::DMURaw DMU11::raw_package_ |
|
private |
The documentation for this class was generated from the following files: