mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_L1_Control: make AHRS attitude member variables private
This commit is contained in:
parent
a81b229997
commit
91fbe46466
@ -56,9 +56,9 @@ const AP_Param::GroupInfo AP_L1_Control::var_info[] = {
|
||||
float AP_L1_Control::get_yaw() const
|
||||
{
|
||||
if (_reverse) {
|
||||
return wrap_PI(M_PI + _ahrs.yaw);
|
||||
return wrap_PI(M_PI + _ahrs.get_yaw());
|
||||
}
|
||||
return _ahrs.yaw;
|
||||
return _ahrs.get_yaw();
|
||||
}
|
||||
|
||||
/*
|
||||
@ -88,7 +88,7 @@ int32_t AP_L1_Control::nav_roll_cd(void) const
|
||||
Made changes to avoid zero division as proposed by Andrew Tridgell: https://github.com/ArduPilot/ardupilot/pull/24331#discussion_r1267798397
|
||||
*/
|
||||
float pitchLimL1 = radians(60); // Suggestion: constraint may be modified to pitch limits if their absolute values are less than 90 degree and more than 60 degrees.
|
||||
float pitchL1 = constrain_float(_ahrs.pitch,-pitchLimL1,pitchLimL1);
|
||||
float pitchL1 = constrain_float(_ahrs.get_pitch(),-pitchLimL1,pitchLimL1);
|
||||
ret = degrees(atanf(_latAccDem * (1.0f/(GRAVITY_MSS * cosf(pitchL1))))) * 100.0f;
|
||||
ret = constrain_float(ret, -9000, 9000);
|
||||
return ret;
|
||||
@ -396,7 +396,7 @@ void AP_L1_Control::update_loiter(const Location ¢er_WP, float radius, int8_
|
||||
A_air_unit = A_air.normalized();
|
||||
} else {
|
||||
if (_groundspeed_vector.length() < 0.1f) {
|
||||
A_air_unit = Vector2f(cosf(_ahrs.yaw), sinf(_ahrs.yaw));
|
||||
A_air_unit = Vector2f(cosf(_ahrs.get_yaw()), sinf(_ahrs.get_yaw()));
|
||||
} else {
|
||||
A_air_unit = _groundspeed_vector.normalized();
|
||||
}
|
||||
@ -504,7 +504,7 @@ void AP_L1_Control::update_level_flight(void)
|
||||
{
|
||||
// copy to _target_bearing_cd and _nav_bearing
|
||||
_target_bearing_cd = _ahrs.yaw_sensor;
|
||||
_nav_bearing = _ahrs.yaw;
|
||||
_nav_bearing = _ahrs.get_yaw();
|
||||
_bearing_error = 0;
|
||||
_crosstrack_error = 0;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user