mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 17:48:35 -04:00
AP_L1_Control: Set the gravitational acceleration value to the defined value
This commit is contained in:
parent
441be7e04b
commit
2eee8e389d
@ -79,7 +79,7 @@ int32_t AP_L1_Control::get_yaw_sensor() const
|
|||||||
int32_t AP_L1_Control::nav_roll_cd(void) const
|
int32_t AP_L1_Control::nav_roll_cd(void) const
|
||||||
{
|
{
|
||||||
float ret;
|
float ret;
|
||||||
ret = cosf(_ahrs.pitch)*degrees(atanf(_latAccDem * 0.101972f) * 100.0f); // 0.101972 = 1/9.81
|
ret = cosf(_ahrs.pitch)*degrees(atanf(_latAccDem * (1.0f/GRAVITY_MSS)) * 100.0f);
|
||||||
ret = constrain_float(ret, -9000, 9000);
|
ret = constrain_float(ret, -9000, 9000);
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user