Classes | Public Member Functions | Public Attributes | Private Types | Private Member Functions | Private Attributes | List of all members
imu_3dm_gx4::Imu Class Reference

Imu Interface to the Microstrain 3DM-GX4-25 IMU. More...

#include <imu.hpp>

Classes

struct  command_error
 command_error Generated when device replies with NACK. More...
 
struct  DiagnosticFields
 DiagnosticFields struct (See 3DM documentation for these fields) More...
 
struct  FilterData
 FilterData Estimator readings produced by the sensor. More...
 
struct  IMUData
 IMUData IMU readings produced by the sensor. More...
 
struct  Info
 Info Structure generated by the getDeviceInfo command. More...
 
struct  io_error
 io_error Generated when a low-level IO command fails. More...
 
struct  Packet
 
struct  timeout_error
 timeout_error Generated when read or write times out, usually indicates device hang up. More...
 

Public Member Functions

struct imu_3dm_gx4::Imu::Packet __attribute__ ((packed))
 
struct imu_3dm_gx4::Imu::DiagnosticFields __attribute__ ((packed))
 
void connect ()
 connect Open a file descriptor to the serial device. More...
 
void disconnect ()
 disconnect Close the file descriptor, sending the IDLE command first. More...
 
void enableBiasEstimation (bool enabled)
 enableBiasEstimation Enable gyroscope bias estimation More...
 
void enableFilterStream (bool enabled)
 enableFilterStream Enable/disable streaming of estimation filter data. More...
 
void enableIMUStream (bool enabled)
 enableIMUStream Enable/disable streaming of IMU data More...
 
void enableMeasurements (bool accel, bool magnetometer)
 enableMeasurements Set which measurements to enable in the filter More...
 
void getDeviceInfo (Imu::Info &info)
 getDeviceInfo Get hardware information about the device. More...
 
void getDiagnosticInfo (Imu::DiagnosticFields &fields)
 getDiagnosticInfo Get diagnostic information from the IMU. More...
 
void getFilterDataBaseRate (uint16_t &baseRate)
 getFilterDataBaseRate Get the filter data base rate (should be 500) More...
 
void getIMUDataBaseRate (uint16_t &baseRate)
 getIMUDataBaseRate Get the imu data base rate (should be 1000) More...
 
void idle (bool needReply=true)
 idle Switch the device to idle mode. More...
 
 Imu (const std::string &device, bool verbose)
 Imu Constructor. More...
 
void ping ()
 ping Ping the device. More...
 
void resume ()
 resume Resume the device. More...
 
void runOnce ()
 runOnce Poll for input and read packets if available. More...
 
void selectBaudRate (unsigned int baud)
 selectBaudRate Select baud rate. More...
 
void setFilterDataCallback (const std::function< void(const Imu::FilterData &)> &)
 Set the onboard filter data callback. More...
 
void setFilterDataRate (uint16_t decimation, const std::bitset< 4 > &sources)
 setFilterDataRate Set estimator data rate for different sources. More...
 
void setHardIronOffset (float offset[3])
 setHardIronOffset Set the hard-iron bias vector for the magnetometer. More...
 
void setIMUDataCallback (const std::function< void(const Imu::IMUData &)> &)
 Set the IMU data callback. More...
 
void setIMUDataRate (uint16_t decimation, const std::bitset< 4 > &sources)
 setIMUDataRate Set imu data rate for different sources. More...
 
void setSoftIronMatrix (float matrix[9])
 setSoftIronMatrix Set the soft-iron matrix for the magnetometer. More...
 
virtual ~Imu ()
 ~Imu Destructor More...
 

Public Attributes

struct imu_3dm_gx4::Imu::Info __attribute__
 
struct imu_3dm_gx4::Imu::IMUData __attribute__
 

Private Types

enum  { Idle = 0, Reading }
 Called when filter data is ready. More...
 

Private Member Functions

std::size_t handleByte (const uint8_t &byte, bool &found)
 
int handleRead (size_t)
 
 Imu (const Imu &)=delete
 
Imuoperator= (const Imu &)=delete
 
int pollInput (unsigned int to)
 
void processPacket ()
 
void receiveResponse (const Packet &command, unsigned int to)
 
void sendCommand (const Packet &p, bool readReply=true)
 
void sendPacket (const Packet &p, unsigned int to)
 
bool termiosBaudRate (unsigned int baud)
 
int writePacket (const Packet &p, unsigned int to)
 

Private Attributes

std::vector< uint8_t > buffer_
 
const std::string device_
 
size_t dstIndex_
 
int fd_
 
std::function< void(const Imu::FilterData &)> filterDataCallback_
 Called with IMU data is ready. More...
 
std::function< void(const Imu::IMUData &)> imuDataCallback_
 
Packet packet_
 
std::deque< uint8_t > queue_
 
unsigned int rwTimeout_
 
size_t srcIndex_
 
enum imu_3dm_gx4::Imu:: { ... }  state_
 Called when filter data is ready. More...
 
const bool verbose_
 

Detailed Description

Imu Interface to the Microstrain 3DM-GX4-25 IMU.

See also
http://www.microstrain.com/inertial/3dm-gx4-25
Author
Gareth Cross
Note
Error handling: All methods which communicate with the device can throw the exceptions below: io_error, timeout_error, command_error and std::runtime_error. Additional exceptions are indicated on specific functions.

Definition at line 43 of file imu.hpp.

Member Enumeration Documentation

anonymous enum
private

Called when filter data is ready.

Enumerator
Idle 
Reading 

Definition at line 431 of file imu.hpp.

Constructor & Destructor Documentation

Imu::Imu ( const std::string &  device,
bool  verbose 
)

Imu Constructor.

Parameters
devicePath to the device in /dev, eg. /dev/ttyACM0
verboseIf true, packet reads are logged to console.

Definition at line 396 of file imu.cpp.

Imu::~Imu ( )
virtual

~Imu Destructor

Note
Calls disconnect() automatically.

Definition at line 405 of file imu.cpp.

imu_3dm_gx4::Imu::Imu ( const Imu )
privatedelete

Member Function Documentation

struct imu_3dm_gx4::Imu::Packet imu_3dm_gx4::Imu::__attribute__ ( (packed)  )
struct imu_3dm_gx4::Imu::DiagnosticFields imu_3dm_gx4::Imu::__attribute__ ( (packed)  )
void Imu::connect ( )

connect Open a file descriptor to the serial device.

Exceptions
runtime_errorif already open or path is invalid. io_error for termios failures.

Definition at line 407 of file imu.cpp.

void Imu::disconnect ( )

disconnect Close the file descriptor, sending the IDLE command first.

Definition at line 468 of file imu.cpp.

void Imu::enableBiasEstimation ( bool  enabled)

enableBiasEstimation Enable gyroscope bias estimation

Parameters
enabledIf true, bias estimation is enabled

Definition at line 816 of file imu.cpp.

void Imu::enableFilterStream ( bool  enabled)

enableFilterStream Enable/disable streaming of estimation filter data.

Parameters
enabledIf true, streaming is enabled.

Definition at line 869 of file imu.cpp.

void Imu::enableIMUStream ( bool  enabled)

enableIMUStream Enable/disable streaming of IMU data

Parameters
enabledIf true, streaming is enabled.

Definition at line 855 of file imu.cpp.

void Imu::enableMeasurements ( bool  accel,
bool  magnetometer 
)

enableMeasurements Set which measurements to enable in the filter

Parameters
accelIf true, acceleration measurements are enabled
magnetometerIf true, magnetometer measurements are enabled.

Definition at line 799 of file imu.cpp.

void Imu::getDeviceInfo ( Imu::Info info)

getDeviceInfo Get hardware information about the device.

Parameters
infoStruct into which information is placed.

Definition at line 664 of file imu.cpp.

void Imu::getDiagnosticInfo ( Imu::DiagnosticFields fields)

getDiagnosticInfo Get diagnostic information from the IMU.

Parameters
fieldsOn success, a filled out DiagnosticFields.

Definition at line 719 of file imu.cpp.

void Imu::getFilterDataBaseRate ( uint16_t &  baseRate)

getFilterDataBaseRate Get the filter data base rate (should be 500)

Parameters
baseRateOn success, the base rate in Hz

Definition at line 708 of file imu.cpp.

void Imu::getIMUDataBaseRate ( uint16_t &  baseRate)

getIMUDataBaseRate Get the imu data base rate (should be 1000)

Parameters
baseRateOn success, the base rate in Hz

Definition at line 693 of file imu.cpp.

std::size_t Imu::handleByte ( const uint8_t &  byte,
bool &  found 
)
private
Note
handleByte will interpret a single byte. It will return the number of bytes which can be cleared from the queue. On early failure, this will always be 1 - ie. kSyncMSB should be cleared from the queue. On success, the total length of the valid packet should be cleared.

Definition at line 927 of file imu.cpp.

int Imu::handleRead ( size_t  bytes_transferred)
private

Definition at line 1004 of file imu.cpp.

void Imu::idle ( bool  needReply = true)

idle Switch the device to idle mode.

Parameters
needReply,iftrue we wait for reply.

Definition at line 644 of file imu.cpp.

Imu& imu_3dm_gx4::Imu::operator= ( const Imu )
privatedelete
void Imu::ping ( )

ping Ping the device.

Definition at line 634 of file imu.cpp.

int Imu::pollInput ( unsigned int  to)
private

Definition at line 893 of file imu.cpp.

void Imu::processPacket ( )
private

Definition at line 1038 of file imu.cpp.

void Imu::receiveResponse ( const Packet command,
unsigned int  to 
)
private

Definition at line 1176 of file imu.cpp.

void Imu::resume ( )

resume Resume the device.

Definition at line 654 of file imu.cpp.

void Imu::runOnce ( )

runOnce Poll for input and read packets if available.

Definition at line 520 of file imu.cpp.

void Imu::selectBaudRate ( unsigned int  baud)

selectBaudRate Select baud rate.

Parameters
baudThe desired baud rate. Supported values are: 9600,19200,115200,230400,460800,921600.
Note
This command will attempt to communicate w/ the device using all possible baud rates. Once the current baud rate is determined, it will switch to 'baud' and send the UART command.
Exceptions
std::runtime_errorfor invalid baud rates.

Definition at line 528 of file imu.cpp.

void Imu::sendCommand ( const Packet p,
bool  readReply = true 
)
private

Definition at line 1212 of file imu.cpp.

void Imu::sendPacket ( const Packet p,
unsigned int  to 
)
private

Definition at line 1167 of file imu.cpp.

void Imu::setFilterDataCallback ( const std::function< void(const Imu::FilterData &)> &  cb)

Set the onboard filter data callback.

Note
The filter data is called every time new orientation data is read.

Definition at line 888 of file imu.cpp.

void Imu::setFilterDataRate ( uint16_t  decimation,
const std::bitset< 4 > &  sources 
)

setFilterDataRate Set estimator data rate for different sources.

Parameters
decimationDenominator in the update rate value: 500/x
sourcesSources to apply this rate to. May be a bitwise combination of the values: Quaternion, GyroBias, AngleUncertainty, BiasUncertainty
Exceptions
invalid_argumentif an invalid source is requested.

Definition at line 771 of file imu.cpp.

void Imu::setHardIronOffset ( float  offset[3])

setHardIronOffset Set the hard-iron bias vector for the magnetometer.

Parameters
offset3x1 vector, units of gauss.

Definition at line 830 of file imu.cpp.

void Imu::setIMUDataCallback ( const std::function< void(const Imu::IMUData &)> &  cb)

Set the IMU data callback.

Note
The IMU data callback is called every time new IMU data is read.

Definition at line 884 of file imu.cpp.

void Imu::setIMUDataRate ( uint16_t  decimation,
const std::bitset< 4 > &  sources 
)

setIMUDataRate Set imu data rate for different sources.

Parameters
decimationDenominator in the update rate value: 1000/x
sourcesSources to apply this rate to. May be a bitwise combination of the values: Accelerometer, Gyroscope, Magnetometer, Barometer
Exceptions
invalid_argumentif an invalid source is requested.

Definition at line 741 of file imu.cpp.

void Imu::setSoftIronMatrix ( float  matrix[9])

setSoftIronMatrix Set the soft-iron matrix for the magnetometer.

Parameters
matrix3x3 row-major matrix, default should be identity.

Definition at line 841 of file imu.cpp.

bool Imu::termiosBaudRate ( unsigned int  baud)
private

Definition at line 477 of file imu.cpp.

int Imu::writePacket ( const Packet p,
unsigned int  to 
)
private

Definition at line 1126 of file imu.cpp.

Member Data Documentation

struct imu_3dm_gx4::Imu::Info imu_3dm_gx4::Imu::__attribute__
struct imu_3dm_gx4::Imu::IMUData imu_3dm_gx4::Imu::__attribute__
std::vector<uint8_t> imu_3dm_gx4::Imu::buffer_
private

Definition at line 422 of file imu.hpp.

const std::string imu_3dm_gx4::Imu::device_
private

Definition at line 417 of file imu.hpp.

size_t imu_3dm_gx4::Imu::dstIndex_
private

Definition at line 424 of file imu.hpp.

int imu_3dm_gx4::Imu::fd_
private

Definition at line 419 of file imu.hpp.

std::function<void(const Imu::FilterData &)> imu_3dm_gx4::Imu::filterDataCallback_
private

Called with IMU data is ready.

Definition at line 429 of file imu.hpp.

std::function<void(const Imu::IMUData &)> imu_3dm_gx4::Imu::imuDataCallback_
private

Definition at line 427 of file imu.hpp.

Packet imu_3dm_gx4::Imu::packet_
private

Definition at line 432 of file imu.hpp.

std::deque<uint8_t> imu_3dm_gx4::Imu::queue_
private

Definition at line 423 of file imu.hpp.

unsigned int imu_3dm_gx4::Imu::rwTimeout_
private

Definition at line 420 of file imu.hpp.

size_t imu_3dm_gx4::Imu::srcIndex_
private

Definition at line 424 of file imu.hpp.

enum { ... } imu_3dm_gx4::Imu::state_

Called when filter data is ready.

const bool imu_3dm_gx4::Imu::verbose_
private

Definition at line 418 of file imu.hpp.


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


thormang3_imu_3dm_gx4
Author(s): Gareth Cross, SCH
autogenerated on Mon Jun 10 2019 15:26:53