Skip to content

Commit 8dc43f3

Browse files
committed
pbio/imu: Allow reading uncalibrated rotation.
This makes the calibration user routine simpler, so we can do everything from raw data.
1 parent 967a4d7 commit 8dc43f3

File tree

3 files changed

+42
-13
lines changed

3 files changed

+42
-13
lines changed

lib/pbio/include/pbio/imu.h

Lines changed: 16 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -124,7 +124,7 @@ void pbio_imu_get_acceleration(pbio_geometry_xyz_t *values, bool calibrated);
124124

125125
void pbio_imu_get_tilt_vector(pbio_geometry_xyz_t *values);
126126

127-
pbio_error_t pbio_imu_get_single_axis_rotation(pbio_geometry_xyz_t *axis, float *angle);
127+
pbio_error_t pbio_imu_get_single_axis_rotation(pbio_geometry_xyz_t *axis, float *angle, bool calibrated);
128128

129129
pbio_geometry_side_t pbio_imu_get_up_side(bool calibrated);
130130

@@ -134,7 +134,7 @@ void pbio_imu_set_heading(float desired_heading);
134134

135135
void pbio_imu_get_heading_scaled(pbio_imu_heading_type_t type, pbio_angle_t *heading, int32_t *heading_rate, int32_t ctl_steps_per_degree);
136136

137-
void pbio_orientation_imu_get_rotation(pbio_geometry_matrix_3x3_t *rotation);
137+
void pbio_orientation_imu_get_orientation(pbio_geometry_matrix_3x3_t *rotation);
138138

139139
#else // PBIO_CONFIG_IMU
140140

@@ -148,18 +148,22 @@ static inline void pbio_imu_apply_loaded_settings(pbio_imu_persistent_settings_t
148148
}
149149

150150
static inline pbio_error_t pbio_imu_set_base_orientation(pbio_geometry_xyz_t *x_axis, pbio_geometry_xyz_t *z_axis) {
151-
return PBIO_ERROR_NOT_IMPLEMENTED;
151+
return PBIO_ERROR_NOT_SUPPORTED;
152152
}
153153

154154
static inline bool pbio_imu_is_stationary(void) {
155155
return false;
156156
}
157157

158+
static inline bool pbio_imu_is_ready(void) {
159+
return false;
160+
}
161+
158162
static inline pbio_error_t pbio_imu_get_settings(pbio_imu_persistent_settings_t **settings) {
159163
return PBIO_ERROR_NOT_SUPPORTED;
160164
}
161165

162-
static inline pbio_error_t pbio_imu_set_settings(float angular_velocity, float acceleration, float heading_correction, bool request_save) {
166+
static inline pbio_error_t pbio_imu_set_settings(pbio_imu_persistent_settings_t *new_settings) {
163167
return PBIO_ERROR_NOT_SUPPORTED;
164168
}
165169

@@ -169,6 +173,13 @@ static inline void pbio_imu_get_angular_velocity(pbio_geometry_xyz_t *values, bo
169173
static inline void pbio_imu_get_acceleration(pbio_geometry_xyz_t *values, bool calibrated) {
170174
}
171175

176+
static inline void pbio_imu_get_tilt_vector(pbio_geometry_xyz_t *values) {
177+
}
178+
179+
static inline pbio_error_t pbio_imu_get_single_axis_rotation(pbio_geometry_xyz_t *axis, float *angle, bool calibrated) {
180+
return PBIO_ERROR_NOT_SUPPORTED;
181+
}
182+
172183
static inline pbio_geometry_side_t pbio_imu_get_up_side(bool calibrated) {
173184
return PBIO_GEOMETRY_SIDE_TOP;
174185
}
@@ -183,7 +194,7 @@ static inline void pbio_imu_set_heading(float desired_heading) {
183194
static inline void pbio_imu_get_heading_scaled(pbio_imu_heading_type_t type, pbio_angle_t *heading, int32_t *heading_rate, int32_t ctl_steps_per_degree) {
184195
}
185196

186-
static inline void pbio_orientation_imu_get_rotation(pbio_geometry_matrix_3x3_t *rotation) {
197+
static inline void pbio_orientation_imu_get_orientation(pbio_geometry_matrix_3x3_t *rotation) {
187198
}
188199

189200

lib/pbio/src/imu.c

Lines changed: 22 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -522,6 +522,9 @@ pbio_error_t pbio_imu_set_settings(pbio_imu_persistent_settings_t *new_settings)
522522
}
523523

524524
if (new_settings->flags & PBIO_IMU_SETTINGS_FLAGS_HEADING_CORRECTION_1D_SET) {
525+
if (new_settings->heading_correction_1d < 350 || new_settings->heading_correction_1d > 370) {
526+
return PBIO_ERROR_INVALID_ARG;
527+
}
525528
persistent_settings->heading_correction_1d = new_settings->heading_correction_1d;
526529
}
527530

@@ -597,16 +600,30 @@ void pbio_imu_get_tilt_vector(pbio_geometry_xyz_t *values) {
597600
*
598601
* @param [in] axis The axis to project the rotation onto.
599602
* @param [out] angle The angle of rotation in degrees.
603+
* @param [in] calibrated Whether to use the adjusted scale (true) or the raw scale (false).
600604
* @return ::PBIO_SUCCESS on success, ::PBIO_ERROR_INVALID_ARG if axis has zero length.
601605
*/
602-
pbio_error_t pbio_imu_get_single_axis_rotation(pbio_geometry_xyz_t *axis, float *angle) {
606+
pbio_error_t pbio_imu_get_single_axis_rotation(pbio_geometry_xyz_t *axis, float *angle, bool calibrated) {
607+
608+
// Local copy so we can change it in-place.
609+
pbio_geometry_xyz_t axis_rotation = single_axis_rotation;
610+
if (!calibrated) {
611+
// In this context, calibrated means that the angular velocity values
612+
// were scaled by the user calibration factors before integrating. This
613+
// is done within the update loop since we need it for 3D integration.
614+
// Since this method only returns the separate 1D rotations, we can
615+
// undo this scaling here to get the "uncalibrated" values.
616+
for (uint8_t i = 0; i < PBIO_ARRAY_SIZE(axis_rotation.values); i++) {
617+
axis_rotation.values[i] *= persistent_settings->angular_velocity_scale.values[i] / 360.0f;
618+
}
619+
}
603620

604621
// Transform the single axis rotations to the robot frame.
605-
pbio_geometry_xyz_t rotation;
606-
pbio_geometry_vector_map(&pbio_imu_base_orientation, &single_axis_rotation, &rotation);
622+
pbio_geometry_xyz_t rotation_user;
623+
pbio_geometry_vector_map(&pbio_imu_base_orientation, &axis_rotation, &rotation_user);
607624

608625
// Get the requested scalar rotation along the given axis.
609-
return pbio_geometry_vector_project(axis, &rotation, angle);
626+
return pbio_geometry_vector_project(axis, &rotation_user, angle);
610627
}
611628

612629
/**
@@ -711,7 +728,7 @@ void pbio_imu_get_heading_scaled(pbio_imu_heading_type_t type, pbio_angle_t *hea
711728
*
712729
* @param [out] rotation The rotation matrix
713730
*/
714-
void pbio_orientation_imu_get_rotation(pbio_geometry_matrix_3x3_t *rotation) {
731+
void pbio_orientation_imu_get_orientation(pbio_geometry_matrix_3x3_t *rotation) {
715732
*rotation = pbio_imu_rotation;
716733
}
717734

pybricks/common/pb_type_imu.c

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -154,7 +154,8 @@ static MP_DEFINE_CONST_FUN_OBJ_KW(pb_type_imu_angular_velocity_obj, 1, pb_type_i
154154
static mp_obj_t pb_type_imu_rotation(size_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
155155
PB_PARSE_ARGS_METHOD(n_args, pos_args, kw_args,
156156
pb_type_imu_obj_t, self,
157-
PB_ARG_DEFAULT_NONE(axis));
157+
PB_ARG_DEFAULT_NONE(axis),
158+
PB_ARG_DEFAULT_TRUE(calibrated));
158159

159160
(void)self;
160161

@@ -163,7 +164,7 @@ static mp_obj_t pb_type_imu_rotation(size_t n_args, const mp_obj_t *pos_args, mp
163164
pb_type_imu_extract_axis(axis_in, &axis);
164165

165166
float rotation_angle;
166-
pb_assert(pbio_imu_get_single_axis_rotation(&axis, &rotation_angle));
167+
pb_assert(pbio_imu_get_single_axis_rotation(&axis, &rotation_angle, mp_obj_is_true(calibrated_in)));
167168
return mp_obj_new_float_from_f(rotation_angle);
168169
}
169170
static MP_DEFINE_CONST_FUN_OBJ_KW(pb_type_imu_rotation_obj, 1, pb_type_imu_rotation);
@@ -318,7 +319,7 @@ STATIC mp_obj_t common_IMU_orientation(mp_obj_t self_in) {
318319
pb_type_Matrix_obj_t *matrix = MP_OBJ_TO_PTR(pb_type_Matrix_make_bitmap(3, 3, 1.0f, 0));
319320

320321
pbio_geometry_matrix_3x3_t orientation;
321-
pbio_orientation_imu_get_rotation(&orientation);
322+
pbio_orientation_imu_get_orientation(&orientation);
322323

323324
memcpy(matrix->data, orientation.values, sizeof(orientation.values));
324325

0 commit comments

Comments
 (0)