diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp index 5c54bfe69d..ffd6002225 100644 --- a/src/modules/commander/gyro_calibration.cpp +++ b/src/modules/commander/gyro_calibration.cpp @@ -499,13 +499,6 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub) } } - /* store board ID */ - uuid_uint32_t mcu_id; - board_get_uuid32(mcu_id); - - /* store last 32bit number - not unique, but unique in a given set */ - (void)param_set(param_find("CAL_BOARD_ID"), &mcu_id[PX4_CPU_UUID_WORD32_UNIQUE_H]); - /* if there is a any preflight-check system response, let the barrage of messages through */ usleep(200000); diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index ee84e8a3f5..cc3f2bf83c 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -41,13 +41,6 @@ * @author Thomas Gubler */ -/** - * ID of the board this parameter set was calibrated on. - * - * @group Sensor Calibration - */ -PARAM_DEFINE_INT32(CAL_BOARD_ID, 0); - /** * ID of the Gyro that the calibration is for. * @@ -1173,4 +1166,4 @@ PARAM_DEFINE_FLOAT(IMU_GYRO_CUTOFF, 30.0f); * @reboot_required true * @group Sensor Calibration */ -PARAM_DEFINE_FLOAT(IMU_ACCEL_CUTOFF, 30.0f); \ No newline at end of file +PARAM_DEFINE_FLOAT(IMU_ACCEL_CUTOFF, 30.0f);