Classes | Public Types | Public Member Functions | Private Member Functions | Private Attributes
Xsens::MTi Class Reference

#include <MTi.h>

List of all members.

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< MTMessagequeue
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

Detailed Description

Definition at line 86 of file MTi.h.


Member Typedef Documentation


Constructor & Destructor Documentation

Constructor.

Definition at line 105 of file MTi.cpp.

Destructor.

Definition at line 140 of file MTi.cpp.


Member Function Documentation

float Xsens::MTi::accelerometer_x ( ) const [inline]

Definition at line 141 of file MTi.h.

float Xsens::MTi::accelerometer_y ( ) const [inline]

Definition at line 142 of file MTi.h.

float Xsens::MTi::accelerometer_z ( ) const [inline]

Definition at line 143 of file MTi.h.

void Xsens::MTi::addMessageToQueue ( MTMessageIdentifier  messageID,
std::vector< unsigned char > *  data,
MTMessageIdentifier  ack 
)

Add a message to the queue in order to send it after.

Parameters:
messageIDXSens ID of the message
dataData corresponding to the Xsens ID
ackXsens ID received when the message is sent (See Xsens Manual)

Definition at line 314 of file MTi.cpp.

float Xsens::MTi::altitude ( ) const [inline]

Definition at line 159 of file MTi.h.

Close the serial port.

Returns:
bool

Definition at line 390 of file MTi.cpp.

float Xsens::MTi::compass_x ( ) const [inline]

Definition at line 147 of file MTi.h.

float Xsens::MTi::compass_y ( ) const [inline]

Definition at line 148 of file MTi.h.

float Xsens::MTi::compass_z ( ) const [inline]

Definition at line 149 of file MTi.h.

sensor_msgs::Imu Xsens::MTi::fillImuMessage ( const ros::Time now)

Fill ROS IMU message with the values come from the xsens.

Parameters:
now
Returns:
sensor_msgs::Imu

Definition at line 1059 of file MTi.cpp.

sensor_msgs::NavSatFix Xsens::MTi::fillNavFixMessage ( const ros::Time now)

Fill ROS NavSatFix message with the values come from the xsens.

Parameters:
now
Returns:
sensor_msgs::NavSatFix

Definition at line 1114 of file MTi.cpp.

nav_msgs::Odometry Xsens::MTi::fillOdometryMessage ( const tf::TransformListener listener,
tf::TransformBroadcaster odom_broadcaster,
const ros::Time now 
)

Fill ROS odometry message with the values come from the xsens.

Parameters:
listener
odom_broadcaster
now
Returns:
nav_msgs::Odometry

Definition at line 948 of file MTi.cpp.

void Xsens::MTi::fillQuaternionWithOutputSettings ( double &  x,
double &  y,
double &  z,
double &  w 
) [private]

Fill value according to the configuration of the xsens.

Parameters:
x
y
z
w

Definition at line 1087 of file MTi.cpp.

Ask to the xsens its Device ID.

Definition at line 404 of file MTi.cpp.

bool Xsens::MTi::GPSFix ( ) const [inline]

Definition at line 169 of file MTi.h.

float Xsens::MTi::gyroscope_x ( ) const [inline]

Definition at line 144 of file MTi.h.

float Xsens::MTi::gyroscope_y ( ) const [inline]

Definition at line 145 of file MTi.h.

float Xsens::MTi::gyroscope_z ( ) const [inline]

Definition at line 146 of file MTi.h.

uint32_t Xsens::MTi::horizontalAccuracy ( ) const [inline]

Definition at line 170 of file MTi.h.

bool Xsens::MTi::isMtiG ( ) [private]

Check if the xsens model is a Mti-G.

Returns:
bool

Definition at line 151 of file MTi.cpp.

bool Xsens::MTi::isSelfTestCompleted ( ) [private]

Check if the power‐up self test completed successfully.

Returns:
bool

Definition at line 161 of file MTi.cpp.

float Xsens::MTi::latitude ( ) const [inline]

Definition at line 161 of file MTi.h.

float Xsens::MTi::longitude ( ) const [inline]

Definition at line 160 of file MTi.h.

void Xsens::MTi::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.

Parameters:
mid
data
message

Definition at line 867 of file MTi.cpp.

void Xsens::MTi::manageIncomingData ( std::vector< unsigned char > *  incomingData,
bool  dataIsExtended 
) [private]

Manage the incoming data in order to retreive the ID and the corresponding data.

Parameters:
incomingDataRaw data
dataIsExtendedRaw data can be larger as expected (Xsens protocol)

pow(2,20);

pow(2,20);

Definition at line 549 of file MTi.cpp.

void Xsens::MTi::manageQueue ( ) [private]

Manage the queue in order to send messages.

Definition at line 324 of file MTi.cpp.

bool Xsens::MTi::openPort ( char *  name,
int  baudrate 
)

Open serial port to communicate with the Xsens.

Parameters:
nameserial port name
baudrate
Returns:
bool

Definition at line 375 of file MTi.cpp.

float Xsens::MTi::pitch ( ) [inline]

Definition at line 156 of file MTi.h.

float Xsens::MTi::quaternion_w ( ) const [inline]

Definition at line 154 of file MTi.h.

float Xsens::MTi::quaternion_x ( ) const [inline]

Definition at line 151 of file MTi.h.

float Xsens::MTi::quaternion_y ( ) const [inline]

Definition at line 152 of file MTi.h.

float Xsens::MTi::quaternion_z ( ) const [inline]

Definition at line 153 of file MTi.h.

void Xsens::MTi::resetGPSValues ( ) [private]

Reset GPS values as altitude, longitude ...

Definition at line 854 of file MTi.cpp.

void Xsens::MTi::resetPackage ( ) [private]

Reset data received.

Definition at line 299 of file MTi.cpp.

float Xsens::MTi::roll ( ) [inline]

Definition at line 155 of file MTi.h.

void Xsens::MTi::serialPortReadData ( char *  data,
int  length 
) [private]

Read data on the serial port.

Parameters:
data
length

Definition at line 444 of file MTi.cpp.

bool Xsens::MTi::serialPortSendData ( std::vector< unsigned char > *  data) [private]

Send data to the XSens.

Parameters:
data
Returns:
bool

Definition at line 418 of file MTi.cpp.

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:

  • outputMode
  • outputSettings
  • frameID of the IMU
  • gps_arm (double, double, double) (MTI-G ONLY)
    • Default (0,0,0)
    • Specifies the x, y and z offsets of the gps antenna with respect to the imu
      Parameters:
      mode
      settings
      timeout
      Returns:
      bool

Definition at line 186 of file MTi.cpp.

float Xsens::MTi::temperature ( ) const [inline]

Definition at line 150 of file MTi.h.

float Xsens::MTi::velocity_x ( ) const [inline]

Definition at line 163 of file MTi.h.

float Xsens::MTi::velocity_y ( ) const [inline]

Definition at line 164 of file MTi.h.

float Xsens::MTi::velocity_z ( ) const [inline]

Definition at line 165 of file MTi.h.

float Xsens::MTi::velocityDown ( ) const [inline]

Definition at line 168 of file MTi.h.

float Xsens::MTi::velocityEast ( ) const [inline]

Definition at line 167 of file MTi.h.

float Xsens::MTi::velocityNorth ( ) const [inline]

Definition at line 166 of file MTi.h.

uint32_t Xsens::MTi::verticalAccuracy ( ) const [inline]

Definition at line 171 of file MTi.h.

bool Xsens::MTi::waitForQueueToFinish ( int  timeout)

Wait all the messages queued to be sent.

Parameters:
timeout
Returns:
bool

Definition at line 351 of file MTi.cpp.

float Xsens::MTi::yaw ( ) [inline]

Definition at line 157 of file MTi.h.


Member Data Documentation

float Xsens::MTi::accX [private]

Definition at line 215 of file MTi.h.

float Xsens::MTi::accY [private]

Definition at line 215 of file MTi.h.

float Xsens::MTi::accZ [private]

Definition at line 215 of file MTi.h.

bool Xsens::MTi::ConfigState [private]

Definition at line 200 of file MTi.h.

float Xsens::MTi::epitch [private]

Definition at line 220 of file MTi.h.

float Xsens::MTi::eroll [private]

Definition at line 220 of file MTi.h.

float Xsens::MTi::eyaw [private]

Definition at line 220 of file MTi.h.

float Xsens::MTi::gyrX [private]

Definition at line 216 of file MTi.h.

float Xsens::MTi::gyrY [private]

Definition at line 216 of file MTi.h.

float Xsens::MTi::gyrZ [private]

Definition at line 216 of file MTi.h.

Definition at line 210 of file MTi.h.

float Xsens::MTi::magX [private]

Definition at line 217 of file MTi.h.

float Xsens::MTi::magY [private]

Definition at line 217 of file MTi.h.

float Xsens::MTi::magZ [private]

Definition at line 217 of file MTi.h.

float Xsens::MTi::mAltitude [private]

Definition at line 223 of file MTi.h.

uint32_t Xsens::MTi::mDeviceID [private]

Definition at line 205 of file MTi.h.

std::string Xsens::MTi::mFrameID [private]

Definition at line 189 of file MTi.h.

uint32_t Xsens::MTi::mHorizontalAccuracy [private]

Definition at line 227 of file MTi.h.

Definition at line 208 of file MTi.h.

float Xsens::MTi::mLatitude [private]

Definition at line 223 of file MTi.h.

float Xsens::MTi::mLongitude [private]

Definition at line 223 of file MTi.h.

std::string Xsens::MTi::mRosNamespace [private]

Definition at line 190 of file MTi.h.

Definition at line 187 of file MTi.h.

std::vector<unsigned char> Xsens::MTi::mScenarioData [private]

Definition at line 186 of file MTi.h.

unsigned char Xsens::MTi::mStatus [private]

Definition at line 226 of file MTi.h.

float Xsens::MTi::mTemperature [private]

Definition at line 218 of file MTi.h.

float Xsens::MTi::mVelocityDown [private]

Definition at line 224 of file MTi.h.

float Xsens::MTi::mVelocityEast [private]

Definition at line 224 of file MTi.h.

float Xsens::MTi::mVelocityNorth [private]

Definition at line 224 of file MTi.h.

float Xsens::MTi::mVelocityX [private]

Definition at line 225 of file MTi.h.

float Xsens::MTi::mVelocityY [private]

Definition at line 225 of file MTi.h.

float Xsens::MTi::mVelocityZ [private]

Definition at line 225 of file MTi.h.

uint32_t Xsens::MTi::mVerticalAccuracy [private]

Definition at line 227 of file MTi.h.

int Xsens::MTi::numOfBytes [private]

Definition at line 204 of file MTi.h.

Definition at line 179 of file MTi.h.

Definition at line 183 of file MTi.h.

std::vector<unsigned char> Xsens::MTi::outputModeData [private]

Definition at line 178 of file MTi.h.

std::vector<unsigned char> Xsens::MTi::outputSettingsData [private]

Definition at line 182 of file MTi.h.

std::vector<unsigned char> Xsens::MTi::package [private]

Definition at line 194 of file MTi.h.

int Xsens::MTi::packageIndex [private]

Definition at line 198 of file MTi.h.

Definition at line 196 of file MTi.h.

Definition at line 197 of file MTi.h.

Definition at line 195 of file MTi.h.

float Xsens::MTi::q0 [private]

Definition at line 219 of file MTi.h.

float Xsens::MTi::q1 [private]

Definition at line 219 of file MTi.h.

float Xsens::MTi::q2 [private]

Definition at line 219 of file MTi.h.

float Xsens::MTi::q3 [private]

Definition at line 219 of file MTi.h.

std::vector<MTMessage> Xsens::MTi::queue [private]

Definition at line 231 of file MTi.h.

Definition at line 232 of file MTi.h.

Definition at line 233 of file MTi.h.

Definition at line 234 of file MTi.h.

Definition at line 175 of file MTi.h.

geometry_msgs::PoseStamped Xsens::MTi::source_pose [private]

Definition at line 211 of file MTi.h.

geometry_msgs::PoseStamped Xsens::MTi::target_pose [private]

Definition at line 212 of file MTi.h.

unsigned int Xsens::MTi::ts [private]

Definition at line 221 of file MTi.h.

float Xsens::MTi::yawCompensation [private]

Definition at line 202 of file MTi.h.


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


lse_xsens_mti
Author(s): Gonçalo Cabrita, Nicolas Vignard
autogenerated on Mon Jan 6 2014 11:28:04