Example setup program for the 3DM-CV7-INS, and 3DM-GV7-INS using C++.
More...
|
static void | logCallback (void *_user, const microstrain_log_level _level, const char *_format, va_list _args) |
| Custom logging callback for MIP SDK message formatting and output. More...
|
|
static void | captureGyroBias (mip::Interface &_device) |
| Captures and configures device gyro bias. More...
|
|
static void | configureFilterMessageFormat (mip::Interface &_device) |
| Configures message format for filter data streaming. More...
|
|
static void | configureExternalAidingHeading (mip::Interface &_device) |
| Configures a heading reference frame for external aiding measurements. More...
|
|
static void | configureExternalAidingGnssAntenna (mip::Interface &_device) |
| Configures a GNSS antenna reference frame for external aiding measurements. More...
|
|
static void | configureExternalAidingNedVelocity (mip::Interface &_device) |
| Configures a body frame velocity reference frame for external aiding measurements. More...
|
|
static void | initializeFilter (mip::Interface &_device) |
| Initializes and resets the navigation filter. More...
|
|
static void | displayFilterState (const mip::data_filter::FilterMode _filterState) |
| Displays the current filter state when changes occur. More...
|
|
static mip::Timestamp | getCurrentTimestamp () |
| Gets the current system timestamp in milliseconds. More...
|
|
static void | initializeDevice (mip::Interface &_device) |
| Initializes and configures a MIP device interface. More...
|
|
static void | sendSimulatedHeadingData (mip::Interface &_device, const mip::commands_aiding::Time &_aidingTime) |
| Sends simulated external heading measurements to the device. More...
|
|
static void | sendSimulatedPositionData (mip::Interface &_device, const mip::commands_aiding::Time &_aidingTime) |
| Sends simulated external position measurements to the device. More...
|
|
static void | sendSimulatedNedVelocityData (mip::Interface &_device, const mip::commands_aiding::Time &_aidingTime) |
| Sends simulated external NED velocity measurements to the device. More...
|
|
static void | sendSimulatedVehicleFrameVelocityData (mip::Interface &_device, const mip::commands_aiding::Time &_aidingTime) |
| Sends simulated external vehicle frame velocity measurements to the device. More...
|
|
static void | terminate (microstrain::Connection *_connection, const char *_message, const bool _successful) |
| Handles graceful program termination and cleanup. More...
|
|
static void | terminate (mip::Interface &_device, const mip::CmdResult _cmdResult, const char *_format,...) |
| Handles graceful program termination and command failure cleanup. More...
|
|
This example shows a basic setup to configure the navigation filter with external heading, and GNSS position and velocity as the heading sources to stream filter data using simulated external aiding measurements for the 3DM-CV7-INS, and 3DM-GV7-INS using C++. This is not an exhaustive example of all settings for those devices. If this example does not meet your specific setup needs, please consult the MIP SDK API documentation for the proper commands.
License
- Copyright
- Copyright (c) 2025 MicroStrain by HBK Licensed under MIT License
◆ logCallback()
static void logCallback |
( |
void * |
_user, |
|
|
const microstrain_log_level |
_level, |
|
|
const char * |
_format, |
|
|
va_list |
_args |
|
) |
| |
|
static |
Processes and formats log messages from the MIP SDK based on severity level. Routes messages to appropriate output streams - errors and fatal messages go to stderr while other levels go to stdout. Each message is prefixed with its severity level name.
- Parameters
-
_user | Pointer to user data (unused in this implementation) |
_level | Log message severity level from microstrain_log_level enum |
_format | Printf-style format string for the message |
_args | Variable argument list containing message parameters |
◆ captureGyroBias()
- Parameters
-
_device | Reference to the initialized MIP device interface |
◆ configureFilterMessageFormat()
Sets up filter data output by:
- Querying device base rate
- Validating desired sample rate against base rate
- Calculating proper decimation
- Configuring message format with:
- GPS timestamp
- Filter status
- LLH position
- NED velocity
- Euler angles
- Parameters
-
_device | Reference to the initialized MIP device interface |
◆ configureExternalAidingHeading()
static void configureExternalAidingHeading |
( |
mip::Interface & |
_device | ) |
|
|
static |
Sets up a heading reference frame for external sensor data:
- Translation: [0, 0, 0] m
- Rotation: [0, 0, 0] deg (no rotation)
The frame is configured with tracking enabled and uses an Euler angle rotation format.
- Parameters
-
_device | Reference to the initialized MIP device interface |
- Note
- This function is typically called during device initialization to establish the coordinate system relationships for external measurements. Frame IDs correspond to those used in external measurement functions.
◆ configureExternalAidingGnssAntenna()
static void configureExternalAidingGnssAntenna |
( |
mip::Interface & |
_device | ) |
|
|
static |
Sets up a GNSS antenna reference frame for external sensor data:
- Translation: [0, 1, 0] m (1m offset in Y-axis)
- Rotation: [0, 0, 0] deg (no rotation)
The frame is configured with tracking enabled and uses an Euler angle rotation format.
- Parameters
-
_device | Reference to the initialized MIP device interface |
- Note
- This function is typically called during device initialization to establish the coordinate system relationships for external measurements. Frame IDs correspond to those used in external measurement functions.
◆ configureExternalAidingNedVelocity()
static void configureExternalAidingNedVelocity |
( |
mip::Interface & |
_device | ) |
|
|
static |
Sets up a body frame velocity reference frame for external sensor data:
- Translation: [1, 0, 0] m (1m offset in X-axis)
- Rotation: [0, 0, 90] deg (90 deg yaw rotation)
The frame is configured with tracking enabled and uses an Euler angle rotation format.
- Parameters
-
_device | Reference to the initialized MIP device interface |
- Note
- This function is typically called during device initialization to establish the coordinate system relationships for external measurements. Frame IDs correspond to those used in external measurement functions.
◆ initializeFilter()
Configures the navigation filter by:
- Enabling GNSS position and velocity aiding measurements
- Enabling external heading aiding measurements
- Configuring filter initialization settings:
- Setting initial position and velocity to zero
- Enabling automatic position/velocity/attitude determination
- Configuring external aiding kinematic alignment
- Resetting the filter to apply new settings
- Parameters
-
_device | Reference to the initialized MIP device interface |
◆ displayFilterState()
Outputs readable messages for filter state transitions:
- Initialization mode
- Vertical gyro mode
- AHRS mode
- Full navigation mode
- Parameters
-
_filterState | Current filter mode from the MIP device interface |
◆ getCurrentTimestamp()
Provides system time measurement using std::chrono for milliseconds since epoch. Uses system_clock to get wall-clock time that corresponds to calendar time and can be synchronized with external time sources.
- Note
- Update this function to use a different time source if needed for your specific application requirements
- Returns
- Current timestamp in milliseconds since epoch
◆ initializeDevice()
Performs a complete device initialization sequence:
- Verifies device communication with a ping command
- Sets the device to idle mode to ensure reliable configuration
- Queries and displays detailed device information
- Loads default device settings for a known state
- Parameters
-
_device | Reference to a MIP device interface to initialize |
◆ sendSimulatedHeadingData()
Provides simulated true heading data to the device for filter aiding. Uses fixed values:
- Heading: 0.0 deg (North)
- Uncertainty: 0.001 radians
- Parameters
-
_device | Reference to the initialized MIP device interface |
_aidingTime | Reference to the timestamp for the external measurement |
- Note
- Issues warning if the command fails but does not terminate execution. Used for testing external aiding functionality with known data.
◆ sendSimulatedPositionData()
Provides simulated LLH position data to the device for filter aiding. Uses fixed coordinates for MicroStrain headquarters:
- Latitude: 44.437 deg N
- Longitude: 73.106 deg W
- Height: 122.0 m
- Uncertainty: 1.0 m in all axes
- Parameters
-
_device | Reference to the initialized MIP device interface |
_aidingTime | Reference to the timestamp for the external measurement |
- Note
- Issues warning if the command fails but does not terminate execution. Used for testing external aiding functionality with a known location.
◆ sendSimulatedNedVelocityData()
Provides simulated North-East-Down velocity data to the device for filter aiding. Uses stationary target values:
- Velocity: [0, 0, 0] m/s (stationary)
- Uncertainty: 0.1 m/s in all axes
- Parameters
-
_device | Reference to the initialized MIP device interface |
_aidingTime | Reference to the timestamp for the external measurement |
- Note
- Issues warning if the command fails but does not terminate execution. Used for testing external aiding functionality with stationary data.
◆ sendSimulatedVehicleFrameVelocityData()
Provides simulated body-frame velocity data to the device for filter aiding. Uses stationary target values:
- Velocity: [0, 0, 0] m/s (stationary in body frame)
- Uncertainty: 0.1 m/s in all axes
- Parameters
-
_device | Reference to the initialized MIP device interface |
_aidingTime | Reference to the timestamp for the external measurement |
- Note
- Issues warning if the command fails but does not terminate execution. Used for testing external aiding functionality with vehicle-relative data.
◆ terminate() [1/2]
Handles graceful shutdown when errors occur:
- Outputs provided error message
- Closes device connection if open
- Exits with appropriate status code
- Parameters
-
_connection | Pointer to the device connection to close |
_message | Error message to display |
_successful | Whether termination is due to success or failure |
◆ terminate() [2/2]
Handles command failure scenarios:
- Formats and displays an error message with command result
- Closes device connection
- Exits with failure status
- Parameters
-
_device | MIP device interface for the command that failed |
_cmdResult | Result code from a failed command |
_format | Printf-style format string for error message |
... | Variable arguments for format string |
◆ PORT_NAME
constexpr const char* PORT_NAME = "/dev/ttyACM0" |
|
staticconstexpr |
◆ BAUDRATE
constexpr uint32_t BAUDRATE = 115200 |
|
staticconstexpr |
- Note
- For native serial connections this needs to be 115200 due to the device default settings command Use mip::commands_base::*CommSpeed() to write and save the baudrate on the device
◆ SAMPLE_RATE_HZ
constexpr uint16_t SAMPLE_RATE_HZ = 1 |
|
staticconstexpr |
◆ RUN_TIME_SECONDS
constexpr uint32_t RUN_TIME_SECONDS = 30 |
|
staticconstexpr |
◆ TIME_OF_ARRIVAL_LATENCY_NS
constexpr uint64_t TIME_OF_ARRIVAL_LATENCY_NS = 100 * 1000000 |
|
staticconstexpr |
- Note
- This is the time it takes to package the command before it arrives and is typically around 100 ms
◆ HEADING_FRAME_CONFIG_ID
constexpr uint8_t HEADING_FRAME_CONFIG_ID = 1 |
|
staticconstexpr |
◆ GNSS_FRAME_CONFIG_ID
constexpr uint8_t GNSS_FRAME_CONFIG_ID = 2 |
|
staticconstexpr |
◆ BODY_VELOCITY_FRAME_CONFIG_ID
constexpr uint8_t BODY_VELOCITY_FRAME_CONFIG_ID = 3 |
|
staticconstexpr |