|
| 1 | +# MicroStrain (INS, IMU, VRU, AHRS) |
| 2 | + |
| 3 | +MicroStrain by HBK provides high-performance inertial sensors engineered for reliability and precision in challenging environments. |
| 4 | +Widely used across industries like aerospace, robotics, industrial automation, and research, MicroStrain sensors are optimized for real-time, accurate motion tracking and orientation data. |
| 5 | + |
| 6 | + |
| 7 | + |
| 8 | +The driver currently supports the following hardware: |
| 9 | + |
| 10 | +- [`MicroStrain CV7-AR`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/vertical-reference-units--vru-/3dm-cv7-ar): Inertial Measurement Unit (IMU) and Vertical Reference Unit (VRU) |
| 11 | +- [`MicroStrain CV7-AHRS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/attitude-and-heading-reference-systems--ahrs-/3dm-cv7-ahrs): Inertial Measurement Unit (IMU) and Attitude Heading Reference System (AHRS) |
| 12 | +- [`MicroStrain CV7-INS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/inertial-navigation-systems--ins-/3dm-cv7-ins): Inertial Measurement Unit (IMU) and Inertial Navigation System (INS). |
| 13 | +- [`MicroStrain CV7-GNSS/INS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/inertial-navigation-systems--ins-/3dm-cv7-gnss-ins): Inertial Measurement Unit (IMU) and Inertial Navigation System (INS) combined with dual multiband (GNSS) receivers. |
| 14 | + |
| 15 | +PX4 can use these sensors to provide raw IMU data for EKF2 or to replace EKF2 as an external INS. |
| 16 | +For more information, including user manuals and datasheets, please refer to the sensors product page. |
| 17 | + |
| 18 | +## Where to Buy |
| 19 | + |
| 20 | +MicroStrain sensors can be purchased through HBK's official [MicroStrain product page](https://www.hbkworld.com/en/products/transducers/inertial-sensors) or through authorized distributors globally. |
| 21 | +For large orders, custom requirements, or technical inquiries, reach out directly to [sales](https://www.hbkworld.com/en/contact-us/contact-sales-microstrain) |
| 22 | + |
| 23 | +## Hardware Setup |
| 24 | + |
| 25 | +### Wiring |
| 26 | + |
| 27 | +Connect the main UART port of the MicroStrain sensor to any unused serial port on the flight controller. |
| 28 | +This port needs to be specified while starting the device. |
| 29 | + |
| 30 | +### Mounting |
| 31 | + |
| 32 | +The MicroStrain sensor can be mounted in any orientation. |
| 33 | +The default coordinate system uses X for the front, Y for the right, and Z for down, with directions marked on the device. |
| 34 | + |
| 35 | +## Firmware Configuration |
| 36 | + |
| 37 | +### PX4 Configuration |
| 38 | + |
| 39 | +To use the MicroStrain driver: |
| 40 | + |
| 41 | +1. Include the module in firmware in the [kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) by setting the kconfig variables: `CONFIG_DRIVERS_INS_MICROSTRAIN` or `CONFIG_COMMON_INS`. |
| 42 | +2. Configure the driver mode by setting [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) |
| 43 | + |
| 44 | + - To use the MicroStrain sensor to provide raw IMU data to EKF2 |
| 45 | + |
| 46 | + 1. Set [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) to 0 |
| 47 | + 2. Update the [EKF2_MULTI_IMU](../advanced_config/parameter_reference.md#EKF2_MULTI_IMU) parameter to account for the added MicroStrain sensor. |
| 48 | + 3. Enable EKF2 by setting [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN) to 1 |
| 49 | + 4. To prioritize MicroStrain sensor output, adjust the priority level of individual sensors from 0-100 using the following parameters: |
| 50 | + |
| 51 | + - [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO) |
| 52 | + - [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO) |
| 53 | + - [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO) |
| 54 | + - [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO) |
| 55 | + |
| 56 | + where `n` corresponds to the index of the corresponding sensor. |
| 57 | + |
| 58 | + ::: tip |
| 59 | + Sensors can be identified by their device id, which can be found by checking the parameters: |
| 60 | + |
| 61 | + - [CAL_ACCn_ID](../advanced_config/parameter_reference.md#CAL_ACC0_ID) |
| 62 | + - [CAL_GYROn_ID](../advanced_config/parameter_reference.md#CAL_GYRO0_ID) |
| 63 | + - [CAL_MAGn_ID](../advanced_config/parameter_reference.md#CAL_MAG0_ID) |
| 64 | + - [CAL_BAROn_ID](../advanced_config/parameter_reference.md#CAL_BARO0_ID) |
| 65 | + |
| 66 | + ::: |
| 67 | + |
| 68 | + - To use the MicroStrain sensor as an external INS |
| 69 | + 1. Set [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) to 1 |
| 70 | + 2. Disable EKF2 by setting [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN) to 0 |
| 71 | + |
| 72 | +3. Reboot and start the driver |
| 73 | + - `microstrain start -d <port>` |
| 74 | + - To start the driver automatically when the flight controller powers on, set [SENS_MS_CFG](../advanced_config/parameter_reference.md#SENS_MS_CFG) to the sensor’s connected port. |
| 75 | + |
| 76 | +## MicroStrain Configuration |
| 77 | + |
| 78 | +1. Rates: |
| 79 | + |
| 80 | + - By default, accel and gyro data are published at 500 Hz, magnetometer at 50 Hz, and barometric pressure at 50 Hz. |
| 81 | + This can be changed by adjusting the following parameters: |
| 82 | + |
| 83 | + - [MS_IMU_RATE_HZ](../advanced_config/parameter_reference.md#MS_IMU_RATE_HZ) |
| 84 | + - [MS_MAG_RATE_HZ](../advanced_config/parameter_reference.md#MS_MAG_RATE_HZ) |
| 85 | + - [MS_BARO_RATE_HZ](../advanced_config/parameter_reference.md#MS_BARO_RATE_HZ) |
| 86 | + |
| 87 | + - Global position, local position, attitude and odometry will be published at 250 Hz by default. |
| 88 | + This can be configured via: |
| 89 | + |
| 90 | + - [MS_FILT_RATE_HZ](../advanced_config/parameter_reference.md#MS_FILT_RATE_HZ) |
| 91 | + |
| 92 | + - For the CV7-GNSS/INS, the GNSS receiver 1 and 2 will publish data at 5Hz by default. |
| 93 | + This can be changed using: |
| 94 | + |
| 95 | + - [MS_GNSS_RATE_HZ](../advanced_config/parameter_reference.md#MS_GNSS_RATE_HZ) |
| 96 | + |
| 97 | + - The driver will automatically configure data outputs based on the specific sensor model and available data streams. |
| 98 | + - The driver is scheduled to run at twice the fastest configured data rate. |
| 99 | + |
| 100 | +2. Aiding measurements: |
| 101 | + |
| 102 | + - If supported, GNSS position and velocity aiding are always enabled. |
| 103 | + - Internal/external magnetometer and heading aiding, as well as optical flow aiding, are disabled by default. They can be enabled using the following parameters: |
| 104 | + |
| 105 | + - [MS_INT_MAG_EN](../advanced_config/parameter_reference.md#MS_INT_MAG_EN) |
| 106 | + - [MS_INT_HEAD_EN](../advanced_config/parameter_reference.md#MS_INT_HEAD_EN) |
| 107 | + - [MS_EXT_HEAD_EN](../advanced_config/parameter_reference.md#MS_EXT_HEAD_EN) |
| 108 | + - [MS_EXT_MAG_EN](../advanced_config/parameter_reference.md#MS_EXT_MAG_EN) |
| 109 | + - [MS_OPT_FLOW_EN](../advanced_config/parameter_reference.md#MS_OPT_FLOW_EN) |
| 110 | + |
| 111 | + - The aiding frames for external sources can be configured using the following parameters: |
| 112 | + |
| 113 | + - [MS_EHEAD_YAW](../advanced_config/parameter_reference.md#MS_EHEAD_YAW) |
| 114 | + - [MS_EMAG_ROLL](../advanced_config/parameter_reference.md#MS_EMAG_ROLL) |
| 115 | + - [MS_EMAG_PTCH](../advanced_config/parameter_reference.md#MS_EMAG_PTCH) |
| 116 | + - [MS_EMAG_YAW](../advanced_config/parameter_reference.md#MS_EMAG_YAW) |
| 117 | + - [MS_OFLW_OFF_X](../advanced_config/parameter_reference.md#MS_OFLW_OFF_X) |
| 118 | + - [MS_OFLW_OFF_Y](../advanced_config/parameter_reference.md#MS_OFLW_OFF_Y) |
| 119 | + - [MS_OFLW_OFF_Z](../advanced_config/parameter_reference.md#MS_OFLW_OFF_Z) |
| 120 | + - [SENS_FLOW_ROT](../advanced_config/parameter_reference.md#SENS_FLOW_ROT) |
| 121 | + |
| 122 | + - The uncertainty for optical flow and external magnetometer aiding must be specified using the following parameters: |
| 123 | + |
| 124 | + - [MS_EMAG_UNCERT](../advanced_config/parameter_reference.md#MS_EMAG_UNCERT) |
| 125 | + - [MS_OFLW_UNCERT](../advanced_config/parameter_reference.md#MS_OFLW_UNCERT) |
| 126 | + |
| 127 | + ::: tip |
| 128 | + 1. When optical flow aiding is enabled, the sensor uses the `vehicle_optical_flow_vel` output from the flight controller as a body-frame velocity aiding measurement. |
| 129 | + 2. If the MicroStrain sensor does not support these aiding sources but they are enabled, sensor initialization will fail. |
| 130 | + |
| 131 | + ::: |
| 132 | + |
| 133 | +3. Initial heading alignment: |
| 134 | + |
| 135 | + - Initial heading alignment is set to kinematic by default. This can be changed by adjusting |
| 136 | + |
| 137 | + - [MS_ALIGNMENT](../advanced_config/parameter_reference.md#MS_ALIGNMENT) |
| 138 | + |
| 139 | +4. GNSS Aiding Source Control (GNSS/INS only) |
| 140 | + |
| 141 | + - The Source of the GNSS aiding data can be configured using: |
| 142 | + |
| 143 | + - [MS_GNSS_AID_SRC](../advanced_config/parameter_reference.md#MS_GNSS_AID_SRC) |
| 144 | + |
| 145 | +5. Sensor to vehicle transform: |
| 146 | + |
| 147 | + - If the sensor is mounted in an orientation different from the vehicle frame. A sensor to vehicle transform can be enabled using |
| 148 | + |
| 149 | + - [MS_SVT_EN](../advanced_config/parameter_reference.md#MS_SVT_EN) |
| 150 | + |
| 151 | + - The transform is defined using the following parameters |
| 152 | + |
| 153 | + - [MS_SENSOR_ROLL](../advanced_config/parameter_reference.md#MS_SENSOR_ROLL) |
| 154 | + - [MS_SENSOR_PTCH](../advanced_config/parameter_reference.md#MS_SENSOR_PTCH) |
| 155 | + - [MS_SENSOR_YAW](../advanced_config/parameter_reference.md#MS_SENSOR_YAW) |
| 156 | + |
| 157 | +6. IMU ranges: |
| 158 | + |
| 159 | + - The accelerometer and gyroscope ranges on the device are configurable using: |
| 160 | + |
| 161 | + - [MS_ACCEL_RANGE](../advanced_config/parameter_reference.md#MS_ACCEL_RANGE) |
| 162 | + - [MS_GYRO_RANGE](../advanced_config/parameter_reference.md#MS_GYRO_RANGE) |
| 163 | + |
| 164 | + ::: tip |
| 165 | + Available range settings depend on the specific [sensor](https://www.hbkworld.com/en/products/transducers/inertial-sensors) and can be found in the corresponding user manual. |
| 166 | + By default, the ranges are not changed. |
| 167 | + |
| 168 | + ::: |
| 169 | + |
| 170 | +7. GNSS Lever arm offsets: |
| 171 | + |
| 172 | + - The lever arm offset for the external GNSS receiver can be configured using: |
| 173 | + |
| 174 | + - [MS_GNSS_OFF1_X](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_X) |
| 175 | + - [MS_GNSS_OFF1_Y](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_Y) |
| 176 | + - [MS_GNSS_OFF1_Z](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_Z) |
| 177 | + |
| 178 | + - For dual-antenna configurations, the second GNSS receiver’s offset is configured using: |
| 179 | + |
| 180 | + - [MS_GNSS_OFF2_X](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_X) |
| 181 | + - [MS_GNSS_OFF2_Y](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_Y) |
| 182 | + - [MS_GNSS_OFF2_Z](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_Z) |
| 183 | + |
| 184 | +## Published Data |
| 185 | + |
| 186 | +The MicroStrain driver continuously publishes sensor data to the following uORB topics: |
| 187 | + |
| 188 | +- [sensor_accel](../msg_docs/SensorAccel.md) |
| 189 | +- [sensor_gyro](../msg_docs/SensorGyro.md) |
| 190 | +- [sensor_mag](../msg_docs/SensorMag.md) |
| 191 | +- [sensor_baro](../msg_docs/SensorBaro.md) |
| 192 | + |
| 193 | +For GNSS/INS devices, GPS data is also published to: |
| 194 | + |
| 195 | +- [sensor_gps](../msg_docs/SensorGps.md) |
| 196 | + |
| 197 | +If used as an external INS replacing EKF2, it publishes: |
| 198 | + |
| 199 | +- [vehicle_global_position](../msg_docs/VehicleGlobalPosition.md) |
| 200 | +- [vehicle_local_position](../msg_docs/VehicleLocalPosition.md) |
| 201 | +- [vehicle_attitude](../msg_docs/VehicleAttitude.md) |
| 202 | +- [vehicle_odometry](../msg_docs/VehicleOdometry.md) |
| 203 | + |
| 204 | +otherwise the same data is published to the following topics |
| 205 | + |
| 206 | +- `external_ins_global_position` |
| 207 | +- `external_ins_attitude` |
| 208 | +- `external_ins_local_position` |
| 209 | + |
| 210 | +::: tip |
| 211 | +Published topics can be viewed using the `listener` command. |
| 212 | +::: |
0 commit comments