mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-23 06:07:35 +08:00
sensors delete unused CAL_BOARD_ID
This commit is contained in:
committed by
Lorenz Meier
parent
2a1ecaa13e
commit
8b7de092a2
@@ -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);
|
||||
|
||||
|
||||
@@ -41,13 +41,6 @@
|
||||
* @author Thomas Gubler <thomas@px4.io>
|
||||
*/
|
||||
|
||||
/**
|
||||
* 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);
|
||||
PARAM_DEFINE_FLOAT(IMU_ACCEL_CUTOFF, 30.0f);
|
||||
|
||||
Reference in New Issue
Block a user