Fills ROS messages with data from the sensor. More...
#include <messageMaker.h>
| Public Member Functions | |
| mtig_driver::GpsInfo | fillGpsInfoMessage () | 
| Creates a custom mtig_driver/GpsInfo ROS message from sensor data. | |
| geometry_msgs::TwistWithCovarianceStamped | fillGpsVelocityMessage () | 
| Creates a geometry_msgs/Twist ROS message from sensor data. | |
| sensor_msgs::Imu | fillImuMessage () | 
| Creates a sensor_msgs/Imu ROS message from sensor data. | |
| sensor_msgs::MagneticField | fillMagneticFieldMessage () | 
| Creates a sensor_msgs/MagneticField ROS message from sensor data. | |
| sensor_msgs::NavSatFix | fillNavSatFixMessage () | 
| Creates a sensor_msgs/NavSatFix ROS message from sensor data. | |
| sensor_msgs::FluidPressure | fillPressureMessage () | 
| Creates a sensor_msgs/FluidPressure ROS message from sensor data. | |
| geometry_msgs::Vector3Stamped | fillRPYMessage () | 
| sensor_msgs::Temperature | fillTemperatureMessage () | 
| Creates a sensor_msgs/Temperature ROS message from sensor data. | |
| geometry_msgs::TwistWithCovarianceStamped | fillVelocityMessage () | 
| Creates a geometry_msgs/Twist ROS message from sensor data. | |
| MessageMaker (SensorData &data) | |
| Initializes holder for SensorData object. | |
| Private Attributes | |
| SensorData & | data | 
Fills ROS messages with data from the sensor.
This class will be constantly used by mtiG in order to publish ROS messages containing information about the Xsens device sensors data.
Definition at line 30 of file messageMaker.h.
| MessageMaker::MessageMaker | ( | SensorData & | _data | ) | 
Initializes holder for SensorData object.
| _data | - a SensorData object | 
Definition at line 17 of file messageMaker.cpp.
| mtig_driver::GpsInfo MessageMaker::fillGpsInfoMessage | ( | ) | 
Creates a custom mtig_driver/GpsInfo ROS message from sensor data.
This message contains important information from the Xsens' GPS that no other ROS Message accounted for.
Definition at line 253 of file messageMaker.cpp.
| geometry_msgs::TwistWithCovarianceStamped MessageMaker::fillGpsVelocityMessage | ( | ) | 
Creates a geometry_msgs/Twist ROS message from sensor data.
Publishes angular and linear speed information in the ENU frame of reference. The data is collected from the device's gyroscopes and GPS
Definition at line 158 of file messageMaker.cpp.
| sensor_msgs::Imu MessageMaker::fillImuMessage | ( | ) | 
Creates a sensor_msgs/Imu ROS message from sensor data.
Uses data collected from the device's inertial measurement unit(IMU) angular velocity from gyroscope linear acceleration from accelerometer orientation fusioned from the magnetometer error is set using values from the MTi User Manual
Definition at line 28 of file messageMaker.cpp.
| sensor_msgs::MagneticField MessageMaker::fillMagneticFieldMessage | ( | ) | 
Creates a sensor_msgs/MagneticField ROS message from sensor data.
Uses data collected from the device's magnetometer
Definition at line 223 of file messageMaker.cpp.
| sensor_msgs::NavSatFix MessageMaker::fillNavSatFixMessage | ( | ) | 
Creates a sensor_msgs/NavSatFix ROS message from sensor data.
Uses data collected from the device's GPS. The covariance is given using DOP and Position Acuraccy. We assumed Position Accuracy is the std dev.
Definition at line 77 of file messageMaker.cpp.
| sensor_msgs::FluidPressure MessageMaker::fillPressureMessage | ( | ) | 
Creates a sensor_msgs/FluidPressure ROS message from sensor data.
Uses data collected from the device's barometer.
Definition at line 206 of file messageMaker.cpp.
| geometry_msgs::Vector3Stamped MessageMaker::fillRPYMessage | ( | ) | 
Definition at line 236 of file messageMaker.cpp.
| sensor_msgs::Temperature MessageMaker::fillTemperatureMessage | ( | ) | 
Creates a sensor_msgs/Temperature ROS message from sensor data.
Uses data collected from the device's thermometer.
Definition at line 190 of file messageMaker.cpp.
| geometry_msgs::TwistWithCovarianceStamped MessageMaker::fillVelocityMessage | ( | ) | 
Creates a geometry_msgs/Twist ROS message from sensor data.
Publishes angular and linear speed information in the ENU frame of reference. The data is collected from the device's gyroscopes and GPS
Definition at line 118 of file messageMaker.cpp.
| SensorData& MessageMaker::data  [private] | 
Definition at line 33 of file messageMaker.h.