#include <MTi.h>
Classes | |
struct | _outputMode |
struct | _outputSettings |
struct | _Position |
Public Types | |
typedef struct Xsens::MTi::_outputMode | outputMode |
typedef struct Xsens::MTi::_outputSettings | outputSettings |
typedef struct Xsens::MTi::_Position | Position |
Public Member Functions | |
float | accelerometer_x () const |
float | accelerometer_y () const |
float | accelerometer_z () const |
void | addMessageToQueue (MTMessageIdentifier messageID, std::vector< unsigned char > *data, MTMessageIdentifier ack) |
Add a message to the queue in order to send it after. | |
float | altitude () const |
bool | closePort () |
Close the serial port. | |
float | compass_x () const |
float | compass_y () const |
float | compass_z () const |
sensor_msgs::Imu | fillImuMessage (const ros::Time &now) |
Fill ROS IMU message with the values come from the xsens. | |
sensor_msgs::NavSatFix | fillNavFixMessage (const ros::Time &now) |
Fill ROS NavSatFix message with the values come from the xsens. | |
nav_msgs::Odometry | fillOdometryMessage (const tf::TransformListener &listener, tf::TransformBroadcaster &odom_broadcaster, const ros::Time &now) |
Fill ROS odometry message with the values come from the xsens. | |
void | getDeviceID () |
Ask to the xsens its Device ID. | |
bool | GPSFix () const |
float | gyroscope_x () const |
float | gyroscope_y () const |
float | gyroscope_z () const |
uint32_t | horizontalAccuracy () const |
float | latitude () const |
float | longitude () const |
void | makeMessage (MTMessageIdentifier mid, std::vector< unsigned char > *data, std::vector< unsigned char > *message) |
Make the message with the right ID and to match with the xsens protocol. | |
MTi () | |
Constructor. | |
bool | openPort (char *name, int baudrate) |
Open serial port to communicate with the Xsens. | |
float | pitch () |
float | quaternion_w () const |
float | quaternion_x () const |
float | quaternion_y () const |
float | quaternion_z () const |
float | roll () |
bool | setSettings (outputMode mode, outputSettings settings, Scenario scenario, const std::string &rosNamespace, const std::string &frameID, const Position &GPSLeverArm, int timeout) |
Set the configuration of the xsens:
| |
float | temperature () const |
float | velocity_x () const |
float | velocity_y () const |
float | velocity_z () const |
float | velocityDown () const |
float | velocityEast () const |
float | velocityNorth () const |
uint32_t | verticalAccuracy () const |
bool | waitForQueueToFinish (int timeout) |
Wait all the messages queued to be sent. | |
float | yaw () |
~MTi () | |
Destructor. | |
Private Member Functions | |
void | fillQuaternionWithOutputSettings (double &x, double &y, double &z, double &w) |
Fill value according to the configuration of the xsens. | |
bool | isMtiG () |
Check if the xsens model is a Mti-G. | |
bool | isSelfTestCompleted () |
Check if the power‐up self test completed successfully. | |
void | manageIncomingData (std::vector< unsigned char > *data, bool dataIsExtended) |
Manage the incoming data in order to retreive the ID and the corresponding data. | |
void | manageQueue () |
Manage the queue in order to send messages. | |
void | resetGPSValues () |
Reset GPS values as altitude, longitude ... | |
void | resetPackage () |
Reset data received. | |
void | serialPortReadData (char *data, int length) |
Read data on the serial port. | |
bool | serialPortSendData (std::vector< unsigned char > *data) |
Send data to the XSens. | |
Private Attributes | |
float | accX |
float | accY |
float | accZ |
bool | ConfigState |
float | epitch |
float | eroll |
float | eyaw |
float | gyrX |
float | gyrY |
float | gyrZ |
tf::TransformListener | listener |
float | magX |
float | magY |
float | magZ |
float | mAltitude |
uint32_t | mDeviceID |
std::string | mFrameID |
uint32_t | mHorizontalAccuracy |
Position | mInitialPosition |
float | mLatitude |
float | mLongitude |
std::string | mRosNamespace |
Scenario | mScenario |
std::vector< unsigned char > | mScenarioData |
unsigned char | mStatus |
float | mTemperature |
float | mVelocityDown |
float | mVelocityEast |
float | mVelocityNorth |
float | mVelocityX |
float | mVelocityY |
float | mVelocityZ |
uint32_t | mVerticalAccuracy |
int | numOfBytes |
outputMode | output_mode |
outputSettings | output_settings |
std::vector< unsigned char > | outputModeData |
std::vector< unsigned char > | outputSettingsData |
std::vector< unsigned char > | package |
int | packageIndex |
bool | packageInTransit |
bool | packageIsExtended |
int | packageLength |
float | q0 |
float | q1 |
float | q2 |
float | q3 |
std::vector< MTMessage > | queue |
MTMessageIdentifier | queueAck |
bool | queueIsRunning |
bool | queueIsWaiting |
cereal::CerealPort | serial_port |
geometry_msgs::PoseStamped | source_pose |
geometry_msgs::PoseStamped | target_pose |
unsigned int | ts |
float | yawCompensation |
Definition at line 86 of file MTi.h.
typedef struct Xsens::MTi::_outputMode Xsens::MTi::outputMode |
typedef struct Xsens::MTi::_outputSettings Xsens::MTi::outputSettings |
typedef struct Xsens::MTi::_Position Xsens::MTi::Position |
void Xsens::MTi::addMessageToQueue | ( | MTMessageIdentifier | messageID, | |
std::vector< unsigned char > * | data, | |||
MTMessageIdentifier | ack | |||
) |
bool Xsens::MTi::closePort | ( | ) |
sensor_msgs::Imu Xsens::MTi::fillImuMessage | ( | const ros::Time & | now | ) |
sensor_msgs::NavSatFix Xsens::MTi::fillNavFixMessage | ( | const ros::Time & | now | ) |
nav_msgs::Odometry Xsens::MTi::fillOdometryMessage | ( | const tf::TransformListener & | listener, | |
tf::TransformBroadcaster & | odom_broadcaster, | |||
const ros::Time & | now | |||
) |
void Xsens::MTi::fillQuaternionWithOutputSettings | ( | double & | x, | |
double & | y, | |||
double & | z, | |||
double & | w | |||
) | [private] |
void Xsens::MTi::getDeviceID | ( | ) |
bool Xsens::MTi::isMtiG | ( | ) | [private] |
bool Xsens::MTi::isSelfTestCompleted | ( | ) | [private] |
void Xsens::MTi::makeMessage | ( | MTMessageIdentifier | mid, | |
std::vector< unsigned char > * | data, | |||
std::vector< unsigned char > * | message | |||
) |
void Xsens::MTi::manageIncomingData | ( | std::vector< unsigned char > * | incomingData, | |
bool | dataIsExtended | |||
) | [private] |
void Xsens::MTi::manageQueue | ( | ) | [private] |
bool Xsens::MTi::openPort | ( | char * | name, | |
int | baudrate | |||
) |
void Xsens::MTi::resetGPSValues | ( | ) | [private] |
void Xsens::MTi::resetPackage | ( | ) | [private] |
void Xsens::MTi::serialPortReadData | ( | char * | data, | |
int | length | |||
) | [private] |
bool Xsens::MTi::serialPortSendData | ( | std::vector< unsigned char > * | data | ) | [private] |
bool Xsens::MTi::setSettings | ( | outputMode | mode, | |
outputSettings | settings, | |||
Scenario | scenario, | |||
const std::string & | rosNamespace, | |||
const std::string & | frameID, | |||
const Position & | GPSLeverArm, | |||
int | timeout | |||
) |
Set the configuration of the xsens:
mode | ||
settings | ||
timeout |
bool Xsens::MTi::waitForQueueToFinish | ( | int | timeout | ) |
float Xsens::MTi::accX [private] |
float Xsens::MTi::accY [private] |
float Xsens::MTi::accZ [private] |
bool Xsens::MTi::ConfigState [private] |
float Xsens::MTi::epitch [private] |
float Xsens::MTi::eroll [private] |
float Xsens::MTi::eyaw [private] |
float Xsens::MTi::gyrX [private] |
float Xsens::MTi::gyrY [private] |
float Xsens::MTi::gyrZ [private] |
tf::TransformListener Xsens::MTi::listener [private] |
float Xsens::MTi::magX [private] |
float Xsens::MTi::magY [private] |
float Xsens::MTi::magZ [private] |
float Xsens::MTi::mAltitude [private] |
uint32_t Xsens::MTi::mDeviceID [private] |
std::string Xsens::MTi::mFrameID [private] |
uint32_t Xsens::MTi::mHorizontalAccuracy [private] |
Position Xsens::MTi::mInitialPosition [private] |
float Xsens::MTi::mLatitude [private] |
float Xsens::MTi::mLongitude [private] |
std::string Xsens::MTi::mRosNamespace [private] |
Scenario Xsens::MTi::mScenario [private] |
std::vector<unsigned char> Xsens::MTi::mScenarioData [private] |
unsigned char Xsens::MTi::mStatus [private] |
float Xsens::MTi::mTemperature [private] |
float Xsens::MTi::mVelocityDown [private] |
float Xsens::MTi::mVelocityEast [private] |
float Xsens::MTi::mVelocityNorth [private] |
float Xsens::MTi::mVelocityX [private] |
float Xsens::MTi::mVelocityY [private] |
float Xsens::MTi::mVelocityZ [private] |
uint32_t Xsens::MTi::mVerticalAccuracy [private] |
int Xsens::MTi::numOfBytes [private] |
outputMode Xsens::MTi::output_mode [private] |
outputSettings Xsens::MTi::output_settings [private] |
std::vector<unsigned char> Xsens::MTi::outputModeData [private] |
std::vector<unsigned char> Xsens::MTi::outputSettingsData [private] |
std::vector<unsigned char> Xsens::MTi::package [private] |
int Xsens::MTi::packageIndex [private] |
bool Xsens::MTi::packageInTransit [private] |
bool Xsens::MTi::packageIsExtended [private] |
int Xsens::MTi::packageLength [private] |
float Xsens::MTi::q0 [private] |
float Xsens::MTi::q1 [private] |
float Xsens::MTi::q2 [private] |
float Xsens::MTi::q3 [private] |
std::vector<MTMessage> Xsens::MTi::queue [private] |
MTMessageIdentifier Xsens::MTi::queueAck [private] |
bool Xsens::MTi::queueIsRunning [private] |
bool Xsens::MTi::queueIsWaiting [private] |
cereal::CerealPort Xsens::MTi::serial_port [private] |
geometry_msgs::PoseStamped Xsens::MTi::source_pose [private] |
geometry_msgs::PoseStamped Xsens::MTi::target_pose [private] |
unsigned int Xsens::MTi::ts [private] |
float Xsens::MTi::yawCompensation [private] |