mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
sensors/vehicle_magnetometer: add SENS_MAG_AUTOCAL to enable initial auto cal
This commit is contained in:
parent
8fbf79527f
commit
2190f66096
@ -105,3 +105,15 @@ PARAM_DEFINE_FLOAT(SENS_MAG_RATE, 50.0f);
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_MAG_MODE, 1);
|
||||
|
||||
/**
|
||||
* Magnetometer auto calibration
|
||||
*
|
||||
* Automatically initialize magnetometer calibration from bias estimate if available.
|
||||
*
|
||||
* @boolean
|
||||
*
|
||||
* @category system
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_MAG_AUTOCAL, 0);
|
||||
|
||||
@ -183,7 +183,7 @@ void VehicleMagnetometer::UpdateMagBiasEstimate()
|
||||
_calibration_estimator_bias[mag_index] = bias;
|
||||
|
||||
// set initial mag calibration if disarmed, mag uncalibrated, and valid estimated bias available
|
||||
if (!_armed && mag_bias_est.stable[mag_index]
|
||||
if (_param_sens_mag_autocal.get() && !_armed && mag_bias_est.stable[mag_index]
|
||||
&& (_calibration[mag_index].device_id() != 0) && !_calibration[mag_index].calibrated()) {
|
||||
|
||||
if (_calibration[mag_index].calibration_index() < 0) {
|
||||
|
||||
@ -171,7 +171,8 @@ private:
|
||||
DEFINE_PARAMETERS(
|
||||
(ParamInt<px4::params::CAL_MAG_COMP_TYP>) _param_mag_comp_typ,
|
||||
(ParamBool<px4::params::SENS_MAG_MODE>) _param_sens_mag_mode,
|
||||
(ParamFloat<px4::params::SENS_MAG_RATE>) _param_sens_mag_rate
|
||||
(ParamFloat<px4::params::SENS_MAG_RATE>) _param_sens_mag_rate,
|
||||
(ParamBool<px4::params::SENS_MAG_AUTOCAL>) _param_sens_mag_autocal
|
||||
)
|
||||
};
|
||||
}; // namespace sensors
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user