Skip to content

Commit

Permalink
VehicleIMU: move setting of _notify_clipping from constructor to Para…
Browse files Browse the repository at this point in the history
…metersUpdate()

Signed-off-by: Silvan Fuhrer <[email protected]>
  • Loading branch information
sfuhrer authored and dagar committed Nov 13, 2024
1 parent ea1a6a3 commit f9c4c8b
Showing 1 changed file with 2 additions and 3 deletions.
5 changes: 2 additions & 3 deletions src/modules/sensors/vehicle_imu/VehicleIMU.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,9 +69,6 @@ VehicleIMU::VehicleIMU(int instance, uint8_t accel_index, uint8_t gyro_index, co
// schedule conservatively until the actual accel & gyro rates are known
_sensor_gyro_sub.set_required_updates(sensor_gyro_s::ORB_QUEUE_LENGTH / 2);
#endif

_notify_clipping = _param_sens_imu_notify_clipping.get();

// advertise immediately to ensure consistent ordering
_vehicle_imu_pub.advertise();
_vehicle_imu_status_pub.advertise();
Expand Down Expand Up @@ -127,6 +124,8 @@ bool VehicleIMU::ParametersUpdate(bool force)
_accel_calibration.ParametersUpdate();
_gyro_calibration.ParametersUpdate();

_notify_clipping = _param_sens_imu_notify_clipping.get();

if (accel_calibration_count != _accel_calibration.calibration_count()) {
// if calibration changed reset any existing learned calibration
_accel_cal_available = false;
Expand Down

0 comments on commit f9c4c8b

Please sign in to comment.