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 | |
| Imu & | operator= (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_ |
Imu Interface to the Microstrain 3DM-GX4-25 IMU.
|
private |
| Imu::Imu | ( | const std::string & | device, |
| bool | verbose | ||
| ) |
|
virtual |
|
privatedelete |
| 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 | ( | ) |
| void Imu::disconnect | ( | ) |
| void Imu::enableBiasEstimation | ( | bool | enabled | ) |
| void Imu::enableFilterStream | ( | bool | enabled | ) |
| void Imu::enableIMUStream | ( | bool | enabled | ) |
| void Imu::enableMeasurements | ( | bool | accel, |
| bool | magnetometer | ||
| ) |
| void Imu::getDeviceInfo | ( | Imu::Info & | info | ) |
| void Imu::getDiagnosticInfo | ( | Imu::DiagnosticFields & | fields | ) |
getDiagnosticInfo Get diagnostic information from the IMU.
| fields | On success, a filled out DiagnosticFields. |
| void Imu::getFilterDataBaseRate | ( | uint16_t & | baseRate | ) |
| void Imu::getIMUDataBaseRate | ( | uint16_t & | baseRate | ) |
|
private |
| void Imu::idle | ( | bool | needReply = true | ) |
|
private |
| void Imu::runOnce | ( | ) |
| void Imu::selectBaudRate | ( | unsigned int | baud | ) |
selectBaudRate Select baud rate.
| baud | The desired baud rate. Supported values are: 9600,19200,115200,230400,460800,921600. |
| std::runtime_error | for invalid baud rates. |
|
private |
|
private |
| void Imu::setFilterDataCallback | ( | const std::function< void(const Imu::FilterData &)> & | cb | ) |
| void Imu::setFilterDataRate | ( | uint16_t | decimation, |
| const std::bitset< 4 > & | sources | ||
| ) |
setFilterDataRate Set estimator data rate for different sources.
| decimation | Denominator in the update rate value: 500/x |
| sources | Sources to apply this rate to. May be a bitwise combination of the values: Quaternion, GyroBias, AngleUncertainty, BiasUncertainty |
| invalid_argument | if an invalid source is requested. |
| void Imu::setHardIronOffset | ( | float | offset[3] | ) |
| void Imu::setIMUDataCallback | ( | const std::function< void(const Imu::IMUData &)> & | cb | ) |
| void Imu::setIMUDataRate | ( | uint16_t | decimation, |
| const std::bitset< 4 > & | sources | ||
| ) |
setIMUDataRate Set imu data rate for different sources.
| decimation | Denominator in the update rate value: 1000/x |
| sources | Sources to apply this rate to. May be a bitwise combination of the values: Accelerometer, Gyroscope, Magnetometer, Barometer |
| invalid_argument | if an invalid source is requested. |
| void Imu::setSoftIronMatrix | ( | float | matrix[9] | ) |
|
private |
| struct imu_3dm_gx4::Imu::Info imu_3dm_gx4::Imu::__attribute__ |
| struct imu_3dm_gx4::Imu::IMUData imu_3dm_gx4::Imu::__attribute__ |
|
private |
|
private |
| enum { ... } imu_3dm_gx4::Imu::state_ |
Called when filter data is ready.