mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AC_PrecLand: add ACC_P_NSE parameter
This commit is contained in:
parent
5dd5c22c39
commit
8f1d122766
@ -57,7 +57,12 @@ const AP_Param::GroupInfo AC_PrecLand::var_info[] = {
|
|||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("EST_TYPE", 5, AC_PrecLand, _estimator_type, 1),
|
AP_GROUPINFO("EST_TYPE", 5, AC_PrecLand, _estimator_type, 1),
|
||||||
|
|
||||||
// 6 RESERVED for ACC_NSE
|
// @Param: ACC_P_NSE
|
||||||
|
// @DisplayName: Kalman Filter Accelerometer Noise
|
||||||
|
// @Description: Kalman Filter Accelerometer Noise, higher values weight the input from the camera more, accels less
|
||||||
|
// @Range: 0.5 5
|
||||||
|
// @User: Advanceds
|
||||||
|
AP_GROUPINFO("ACC_P_NSE", 6, AC_PrecLand, _accel_noise, 2.5f),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
@ -249,8 +254,8 @@ void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_va
|
|||||||
const float& dt = inertial_data_delayed.dt;
|
const float& dt = inertial_data_delayed.dt;
|
||||||
const Vector3f& vehicleDelVel = inertial_data_delayed.correctedVehicleDeltaVelocityNED;
|
const Vector3f& vehicleDelVel = inertial_data_delayed.correctedVehicleDeltaVelocityNED;
|
||||||
|
|
||||||
_ekf_x.predict(dt, -vehicleDelVel.x, 0.5f*dt);
|
_ekf_x.predict(dt, -vehicleDelVel.x, _accel_noise*dt);
|
||||||
_ekf_y.predict(dt, -vehicleDelVel.y, 0.5f*dt);
|
_ekf_y.predict(dt, -vehicleDelVel.y, _accel_noise*dt);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Update if a new LOS measurement is available
|
// Update if a new LOS measurement is available
|
||||||
|
@ -108,6 +108,7 @@ private:
|
|||||||
AP_Float _yaw_align; // Yaw angle from body x-axis to sensor x-axis.
|
AP_Float _yaw_align; // Yaw angle from body x-axis to sensor x-axis.
|
||||||
AP_Float _land_ofs_cm_x; // Desired landing position of the camera forward of the target in vehicle body frame
|
AP_Float _land_ofs_cm_x; // Desired landing position of the camera forward of the target in vehicle body frame
|
||||||
AP_Float _land_ofs_cm_y; // Desired landing position of the camera right of the target in vehicle body frame
|
AP_Float _land_ofs_cm_y; // Desired landing position of the camera right of the target in vehicle body frame
|
||||||
|
AP_Float _accel_noise; // accelometer process noise
|
||||||
|
|
||||||
uint32_t _last_update_ms; // system time in millisecond when update was last called
|
uint32_t _last_update_ms; // system time in millisecond when update was last called
|
||||||
bool _target_acquired; // true if target has been seen recently
|
bool _target_acquired; // true if target has been seen recently
|
||||||
|
Loading…
Reference in New Issue
Block a user