Public Member Functions | Public Attributes | Private Attributes | List of all members
DMU11 Class Reference

#include <DMU11.h>

Public Member Functions

int16_t big_endian_to_short (unsigned char *data)
 change big endian 2 byte into short More...
 
void closePort ()
 Close the device. More...
 
 DMU11 (ros::NodeHandle &nh)
 Constructor. More...
 
void doParsing (int16_t *int16buff)
 Gets the raw data and converts them to standard ROS IMU message. More...
 
int openPort ()
 Open device. More...
 
float short_to_float (int16_t *data)
 change big endian short into float More...
 
void update ()
 Read the data received on serial port. More...
 
virtual ~DMU11 ()
 

Public Attributes

sensor_msgs::Imu imu_raw_
 
double pitch_ = 0
 
double rate_
 
double roll_ = 0
 
double yaw_ = 0
 

Private Attributes

struct termios defaults_
 
std::string device_
 
ros::Publisher dmu_raw_publisher_
 
int file_descriptor_
 
std::string frame_id_
 
const double g_ = 9.80665
 
int16_t header_ = 0x55aa
 
ros::Publisher imu_publisher_
 
dmu_ros::DMURaw raw_package_
 

Detailed Description

Definition at line 21 of file DMU11.h.

Constructor & Destructor Documentation

DMU11::DMU11 ( ros::NodeHandle nh)

Constructor.

Parameters
nh

Definition at line 8 of file DMU11.cpp.

DMU11::~DMU11 ( )
virtual

Definition at line 263 of file DMU11.cpp.

Member Function Documentation

int16_t DMU11::big_endian_to_short ( unsigned char *  data)

change big endian 2 byte into short

Parameters
dataHead pointer to the data converted value

Definition at line 191 of file DMU11.cpp.

void DMU11::closePort ( )

Close the device.

Definition at line 174 of file DMU11.cpp.

void DMU11::doParsing ( int16_t *  int16buff)

Gets the raw data and converts them to standard ROS IMU message.

Parameters
int16buff

Definition at line 203 of file DMU11.cpp.

int DMU11::openPort ( )

Open device.

Return values
0Success
-1Failure

Definition at line 30 of file DMU11.cpp.

float DMU11::short_to_float ( int16_t *  data)

change big endian short into float

Parameters
dataHead pointer to the data converted value

Definition at line 197 of file DMU11.cpp.

void DMU11::update ( )

Read the data received on serial port.

Definition at line 128 of file DMU11.cpp.

Member Data Documentation

struct termios DMU11::defaults_
private

Definition at line 34 of file DMU11.h.

std::string DMU11::device_
private

Definition at line 25 of file DMU11.h.

ros::Publisher DMU11::dmu_raw_publisher_
private

Definition at line 24 of file DMU11.h.

int DMU11::file_descriptor_
private

Definition at line 33 of file DMU11.h.

std::string DMU11::frame_id_
private

Definition at line 26 of file DMU11.h.

const double DMU11::g_ = 9.80665
private

Definition at line 31 of file DMU11.h.

int16_t DMU11::header_ = 0x55aa
private

Definition at line 32 of file DMU11.h.

ros::Publisher DMU11::imu_publisher_
private

Definition at line 23 of file DMU11.h.

sensor_msgs::Imu DMU11::imu_raw_

Definition at line 38 of file DMU11.h.

double DMU11::pitch_ = 0

Definition at line 43 of file DMU11.h.

double DMU11::rate_

Definition at line 39 of file DMU11.h.

dmu_ros::DMURaw DMU11::raw_package_
private

Definition at line 28 of file DMU11.h.

double DMU11::roll_ = 0

Definition at line 42 of file DMU11.h.

double DMU11::yaw_ = 0

Definition at line 44 of file DMU11.h.


The documentation for this class was generated from the following files:


dmu_ros
Author(s): Leutrim Gruda
autogenerated on Mon Jun 10 2019 13:05:49