ROS driver for Xsens mti-G-700. More...
#include <mtiG.h>
Public Member Functions | |
void | advertise () |
Uses mSettings to advertise corresponding ROS Messages. | |
void | configure () |
Creates an XsOutputConfigurationArray and pushes it to the sensor. | |
void | fillData (XsDataPacket *) |
Initiates data extraction from packet obtained from the device. | |
mtiG (XsDevice *_device) | |
Simplified constructor. | |
mtiG (XsDevice *_device, int argc, char **argv) | |
Initializes data values and configures the sensor with desired modules. | |
void | publish () |
Uses mSettings and the MessageMaker class to publish corresponding ROS Messages. | |
void | readSettings () |
Pulls the active configuration from the device. | |
Private Member Functions | |
void | parseOptions (int argc, char **argv) |
Parses the parameters from the launchfile. | |
void | printSettings () |
Prints the active settings. | |
Private Attributes | |
XsDevice * | device |
ros::Publisher | gpsInfoPublisher |
ros::Publisher | gpsPublisher |
ros::Publisher | gpsVelPublisher |
ros::Publisher | imuPublisher |
ros::Publisher | magFieldPub |
MessageMaker * | messageMaker |
outputSettings | mSettings |
int | override_settings |
ros::Publisher | pressurePublisher |
ros::Publisher | rpyPublisher |
SensorData | sensorData |
ros::Publisher | tempPublisher |
ros::Publisher | velPublisher |
ROS driver for Xsens mti-G-700.
This class is the main part of a driver for Xsens mti-G-700. It reads packets from the device using the Xsens API - see disclosure below. It stores the data in another class, named SensorData and uses MessageMaker to publish this data in ROS topics.
mtiG::mtiG | ( | XsDevice * | _device | ) |
mtiG::mtiG | ( | XsDevice * | _device, |
int | argc, | ||
char ** | argv | ||
) |
void mtiG::advertise | ( | ) |
void mtiG::configure | ( | ) |
void mtiG::fillData | ( | XsDataPacket * | packet | ) |
void mtiG::parseOptions | ( | int | argc, |
char ** | argv | ||
) | [private] |
void mtiG::printSettings | ( | ) | [private] |
void mtiG::publish | ( | ) |
Uses mSettings and the MessageMaker class to publish corresponding ROS Messages.
packet | - XsDataPacket from the Xsens API |
void mtiG::readSettings | ( | ) |
XsDevice* mtiG::device [private] |
ros::Publisher mtiG::gpsInfoPublisher [private] |
ros::Publisher mtiG::gpsPublisher [private] |
ros::Publisher mtiG::gpsVelPublisher [private] |
ros::Publisher mtiG::imuPublisher [private] |
ros::Publisher mtiG::magFieldPub [private] |
MessageMaker* mtiG::messageMaker [private] |
outputSettings mtiG::mSettings [private] |
int mtiG::override_settings [private] |
ros::Publisher mtiG::pressurePublisher [private] |
ros::Publisher mtiG::rpyPublisher [private] |
SensorData mtiG::sensorData [private] |
ros::Publisher mtiG::tempPublisher [private] |
ros::Publisher mtiG::velPublisher [private] |