mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Soaring: make AHRS attitude member variables private
This commit is contained in:
parent
57b1ab3ad9
commit
ba68d0fcbe
@ -280,8 +280,8 @@ void SoaringController::init_thermalling()
|
||||
// New state vector filter will be reset. Thermal location is placed in front of a/c
|
||||
const float init_xr[4] = {_vario.get_trigger_value(),
|
||||
INITIAL_THERMAL_RADIUS,
|
||||
position.x + thermal_distance_ahead * cosf(_ahrs.yaw),
|
||||
position.y + thermal_distance_ahead * sinf(_ahrs.yaw)};
|
||||
position.x + thermal_distance_ahead * cosf(_ahrs.get_yaw()),
|
||||
position.y + thermal_distance_ahead * sinf(_ahrs.get_yaw())};
|
||||
|
||||
const VectorN<float,4> xr{init_xr};
|
||||
|
||||
|
@ -62,7 +62,7 @@ void Variometer::update(const float thermal_bank)
|
||||
float smoothed_climb_rate = _climb_filter.apply(raw_climb_rate, dt);
|
||||
|
||||
// Compute still-air sinkrate
|
||||
float roll = _ahrs.roll;
|
||||
float roll = _ahrs.get_roll();
|
||||
float sinkrate = calculate_aircraft_sinkrate(roll);
|
||||
|
||||
reading = raw_climb_rate + dsp_cor*_aspd_filt_constrained/GRAVITY_MSS + sinkrate;
|
||||
|
Loading…
Reference in New Issue
Block a user