DMU11.h
Go to the documentation of this file.
1 //
2 // Created by leutrim on 11/04/18.
3 //
4 
5 #ifndef DMU_ROS_DMU11_H
6 #define DMU_ROS_DMU11_H
7 
8 #include <ros/ros.h>
9 #include <sensor_msgs/Imu.h>
10 #include <dmu_ros/DMURaw.h>
11 #include <tf/tf.h>
12 #include <termios.h>
13 #include <string>
14 #include <iostream>
15 #include <signal.h>
16 #include <stdio.h>
17 #include <unistd.h>
18 #include <fcntl.h>
19 
20 
21 class DMU11
22 {
25  std::string device_;
26  std::string frame_id_;
27 
28  dmu_ros::DMURaw raw_package_; //Custom message containing all DMU11 raw data.
29 
30  //Constants
31  const double g_ = 9.80665;
32  int16_t header_ = 0x55aa;
34  struct termios defaults_;
35 
36 public:
37 //IMU ROS format
38  sensor_msgs::Imu imu_raw_;
39  double rate_;
40 
41 
42  double roll_ = 0;
43  double pitch_ = 0;
44  double yaw_ = 0;
45 
51 
57  int openPort();
58 
62  void update();
63 
67  void closePort();
68 
74  int16_t big_endian_to_short(unsigned char *data);
75 
81  float short_to_float(int16_t *data);
82 
87  void doParsing(int16_t *int16buff);
88 
89 
90  virtual ~DMU11();
91 
92 };
93 
94 
95 #endif //DMU_ROS_DMU11_H
void closePort()
Close the device.
Definition: DMU11.cpp:174
ros::Publisher imu_publisher_
Definition: DMU11.h:23
int openPort()
Open device.
Definition: DMU11.cpp:30
double roll_
Definition: DMU11.h:42
void doParsing(int16_t *int16buff)
Gets the raw data and converts them to standard ROS IMU message.
Definition: DMU11.cpp:203
std::string frame_id_
Definition: DMU11.h:26
int16_t big_endian_to_short(unsigned char *data)
change big endian 2 byte into short
Definition: DMU11.cpp:191
double pitch_
Definition: DMU11.h:43
double yaw_
Definition: DMU11.h:44
float short_to_float(int16_t *data)
change big endian short into float
Definition: DMU11.cpp:197
ros::Publisher dmu_raw_publisher_
Definition: DMU11.h:24
int file_descriptor_
Definition: DMU11.h:33
const double g_
Definition: DMU11.h:31
struct termios defaults_
Definition: DMU11.h:34
double rate_
Definition: DMU11.h:39
sensor_msgs::Imu imu_raw_
Definition: DMU11.h:38
DMU11(ros::NodeHandle &nh)
Constructor.
Definition: DMU11.cpp:8
dmu_ros::DMURaw raw_package_
Definition: DMU11.h:28
std::string device_
Definition: DMU11.h:25
virtual ~DMU11()
Definition: DMU11.cpp:263
void update()
Read the data received on serial port.
Definition: DMU11.cpp:128
Definition: DMU11.h:21
int16_t header_
Definition: DMU11.h:32


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