2525static pbdrv_imu_dev_t * imu_dev ;
2626static pbdrv_imu_config_t * imu_config ;
2727
28+ // Cached sensor values that can be read at any time without polling again.
29+ static pbio_geometry_xyz_t angular_velocity_uncalibrated ; // deg/s, in hub frame
30+ static pbio_geometry_xyz_t angular_velocity_calibrated ; // deg/s, in hub frame, already adjusted for bias and scale.
31+ static pbio_geometry_xyz_t acceleration_uncalibrated ; // mm/s^2, in hub frame
32+ static pbio_geometry_xyz_t acceleration_calibrated ; // mm/s^2, in hub frame
33+ static pbio_geometry_xyz_t gyro_bias ; // Starts at value from settings, then updated when stationary.
34+ static pbio_geometry_xyz_t single_axis_rotation ; // deg, in hub frame
35+
2836// Asynchronously loaded on boot. Cannot be used until loaded.
2937static pbio_imu_persistent_settings_t * persistent_settings = NULL ;
3038
@@ -57,9 +65,10 @@ void pbio_imu_set_default_settings(pbio_imu_persistent_settings_t *settings) {
5765 settings -> flags = 0 ;
5866 settings -> gyro_stationary_threshold = 3.0f ;
5967 settings -> accel_stationary_threshold = 2500.0f ;
60- settings -> heading_correction = 360.0f ;
6168 settings -> gravity_pos .x = settings -> gravity_pos .y = settings -> gravity_pos .z = standard_gravity ;
6269 settings -> gravity_neg .x = settings -> gravity_neg .y = settings -> gravity_neg .z = - standard_gravity ;
70+ settings -> angular_velocity_bias_start .x = settings -> angular_velocity_bias_start .y = settings -> angular_velocity_bias_start .z = 0.0f ;
71+ settings -> angular_velocity_scale .x = settings -> angular_velocity_scale .y = settings -> angular_velocity_scale .z = 360.0f ;
6372 pbio_imu_apply_pbdrv_settings (settings );
6473}
6574
@@ -71,38 +80,40 @@ void pbio_imu_set_default_settings(pbio_imu_persistent_settings_t *settings) {
7180void pbio_imu_apply_loaded_settings (pbio_imu_persistent_settings_t * settings ) {
7281 // This is called on load, so we can now access the settings directly.
7382 persistent_settings = settings ;
83+
84+ // The saved angular velocity bias only sets the initial value. We still
85+ // update the bias continuously from stationary data.
86+ gyro_bias .x = settings -> angular_velocity_bias_start .x ;
87+ gyro_bias .y = settings -> angular_velocity_bias_start .y ;
88+ gyro_bias .z = settings -> angular_velocity_bias_start .z ;
89+
7490 pbio_imu_apply_pbdrv_settings (settings );
7591}
7692
77- // Cached sensor values that can be read at any time without polling again.
78- static pbio_geometry_xyz_t angular_velocity ; // deg/s, in hub frame, already adjusted for bias.
79- static pbio_geometry_xyz_t acceleration_uncalibrated ; // mm/s^2, in hub frame
80- static pbio_geometry_xyz_t acceleration_calibrated ; // mm/s^2, in hub frame
81- static pbio_geometry_xyz_t gyro_bias ;
82- static pbio_geometry_xyz_t single_axis_rotation ; // deg, in hub frame
83-
8493// Called by driver to process one frame of unfiltered gyro and accelerometer data.
8594static void pbio_imu_handle_frame_data_func (int16_t * data ) {
86- for (uint8_t i = 0 ; i < PBIO_ARRAY_SIZE (angular_velocity .values ); i ++ ) {
95+ for (uint8_t i = 0 ; i < PBIO_ARRAY_SIZE (angular_velocity_calibrated .values ); i ++ ) {
8796 // Update angular velocity and acceleration cache so user can read them.
88- angular_velocity .values [i ] = data [i ] * imu_config -> gyro_scale - gyro_bias . values [ i ] ;
97+ angular_velocity_uncalibrated .values [i ] = data [i ] * imu_config -> gyro_scale ;
8998 acceleration_uncalibrated .values [i ] = data [i + 3 ] * imu_config -> accel_scale ;
9099
91100 // Once settings loaded, maintain calibrated cached values.
92101 if (persistent_settings ) {
93102 float acceleration_offset = (persistent_settings -> gravity_pos .values [i ] + persistent_settings -> gravity_neg .values [i ]) / 2 ;
94103 float acceleration_scale = (persistent_settings -> gravity_pos .values [i ] - persistent_settings -> gravity_neg .values [i ]) / 2 ;
95104 acceleration_calibrated .values [i ] = (acceleration_uncalibrated .values [i ] - acceleration_offset ) * standard_gravity / acceleration_scale ;
105+ angular_velocity_calibrated .values [i ] = (angular_velocity_uncalibrated .values [i ] - gyro_bias .values [i ]) * 360.0f / persistent_settings -> angular_velocity_scale .values [i ];
96106 } else {
97107 acceleration_calibrated .values [i ] = acceleration_uncalibrated .values [i ];
108+ angular_velocity_calibrated .values [i ] = angular_velocity_uncalibrated .values [i ];
98109 }
99110
100111 // Update "heading" on all axes. This is not useful for 3D attitude
101112 // estimation, but it allows the user to get a 1D heading even with
102113 // the hub mounted at an arbitrary orientation. Such a 1D heading
103114 // is numerically more accurate, which is useful in drive base
104115 // applications so long as the vehicle drives on a flat surface.
105- single_axis_rotation .values [i ] += angular_velocity .values [i ] * imu_config -> sample_time ;
116+ single_axis_rotation .values [i ] += angular_velocity_calibrated .values [i ] * imu_config -> sample_time ;
106117 }
107118}
108119
@@ -235,20 +246,23 @@ pbio_error_t pbio_imu_set_settings(pbio_imu_persistent_settings_t *new_settings)
235246
236247 if (new_settings -> flags & PBIO_IMU_SETTINGS_FLAGS_ACCEL_STATIONARY_THRESHOLD_SET ) {
237248 persistent_settings -> accel_stationary_threshold = new_settings -> accel_stationary_threshold ;
238- persistent_settings -> flags |= PBIO_IMU_SETTINGS_FLAGS_ACCEL_STATIONARY_THRESHOLD_SET ;
239249 }
240250
241251 if (new_settings -> flags & PBIO_IMU_SETTINGS_FLAGS_GYRO_STATIONARY_THRESHOLD_SET ) {
242252 persistent_settings -> gyro_stationary_threshold = new_settings -> gyro_stationary_threshold ;
243- persistent_settings -> flags |= PBIO_IMU_SETTINGS_FLAGS_GYRO_STATIONARY_THRESHOLD_SET ;
244253 }
245254
246- if (new_settings -> flags & PBIO_IMU_SETTINGS_FLAGS_GYRO_HEADING_CORRECTION_SET ) {
247- if (new_settings -> heading_correction < 350 || new_settings -> heading_correction > 370 ) {
248- return PBIO_ERROR_INVALID_ARG ;
255+ for (uint8_t i = 0 ; i < 3 ; i ++ ) {
256+ if (new_settings -> flags & PBIO_IMU_SETTINGS_FLAGS_GYRO_BIAS_INITIAL_SET ) {
257+ persistent_settings -> angular_velocity_bias_start .values [i ] = new_settings -> angular_velocity_bias_start .values [i ];
258+ }
259+
260+ if (new_settings -> flags & PBIO_IMU_SETTINGS_FLAGS_GYRO_SCALE_SET ) {
261+ if (new_settings -> angular_velocity_scale .values [i ] < 350 || new_settings -> angular_velocity_scale .values [i ] > 370 ) {
262+ return PBIO_ERROR_INVALID_ARG ;
263+ }
264+ persistent_settings -> angular_velocity_scale .values [i ] = new_settings -> angular_velocity_scale .values [i ];
249265 }
250- persistent_settings -> heading_correction = new_settings -> heading_correction ;
251- persistent_settings -> flags |= PBIO_IMU_SETTINGS_FLAGS_GYRO_HEADING_CORRECTION_SET ;
252266 }
253267
254268 if (new_settings -> flags & PBIO_IMU_SETTINGS_FLAGS_ACCEL_CALIBRATED ) {
@@ -260,13 +274,13 @@ pbio_error_t pbio_imu_set_settings(pbio_imu_persistent_settings_t *new_settings)
260274 pbio_imu_stationary_acceleration_out_of_range (new_settings -> gravity_neg .z , false)) {
261275 return PBIO_ERROR_INVALID_ARG ;
262276 }
263- persistent_settings -> flags |= PBIO_IMU_SETTINGS_FLAGS_ACCEL_CALIBRATED ;
264277 persistent_settings -> gravity_pos = new_settings -> gravity_pos ;
265278 persistent_settings -> gravity_neg = new_settings -> gravity_neg ;
266279 }
267280
268281 // If any settings were changed, request saving.
269282 if (new_settings -> flags ) {
283+ persistent_settings -> flags |= new_settings -> flags ;
270284 pbsys_storage_request_write ();
271285 }
272286
@@ -296,9 +310,11 @@ pbio_error_t pbio_imu_get_settings(pbio_imu_persistent_settings_t **settings) {
296310 * Gets the cached IMU angular velocity in deg/s, compensated for gyro bias.
297311 *
298312 * @param [out] values The angular velocity vector.
313+ * @param [in] calibrated Whether to get calibrated or uncalibrated data.
299314 */
300- void pbio_imu_get_angular_velocity (pbio_geometry_xyz_t * values ) {
301- pbio_geometry_vector_map (& pbio_orientation_base_orientation , & angular_velocity , values );
315+ void pbio_imu_get_angular_velocity (pbio_geometry_xyz_t * values , bool calibrated ) {
316+ pbio_geometry_xyz_t * angular_velocity = calibrated ? & angular_velocity_calibrated : & angular_velocity_uncalibrated ;
317+ pbio_geometry_vector_map (& pbio_orientation_base_orientation , angular_velocity , values );
302318}
303319
304320/**
@@ -359,13 +375,9 @@ static float heading_offset = 0;
359375 * @return Heading angle in the base frame.
360376 */
361377float pbio_imu_get_heading (void ) {
362-
363378 pbio_geometry_xyz_t heading_mapped ;
364379 pbio_geometry_vector_map (& pbio_orientation_base_orientation , & single_axis_rotation , & heading_mapped );
365-
366- float correction = persistent_settings ? (360.0f / persistent_settings -> heading_correction ) : 1.0f ;
367-
368- return - heading_mapped .z * correction - heading_offset ;
380+ return - heading_mapped .z - heading_offset ;
369381}
370382
371383/**
@@ -408,7 +420,7 @@ void pbio_imu_get_heading_scaled(pbio_angle_t *heading, int32_t *heading_rate, i
408420
409421 // The heading rate can be obtained by a simple scale because it always fits.
410422 pbio_geometry_xyz_t angular_rate ;
411- pbio_imu_get_angular_velocity (& angular_rate );
423+ pbio_imu_get_angular_velocity (& angular_rate , true );
412424 * heading_rate = (int32_t )(- angular_rate .z * ctl_steps_per_degree );
413425}
414426
0 commit comments