mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: use floats for roll/pitch
Otherwise we're taking floats, making them int32 and then making them floats again when calling the attitude controller
This commit is contained in:
parent
6364e6d4c1
commit
5db75b313d
@ -557,8 +557,8 @@ void Copter::Mode::land_run_horizontal_control()
|
||||
// run loiter controller
|
||||
loiter_nav->update();
|
||||
|
||||
int32_t nav_roll = loiter_nav->get_roll();
|
||||
int32_t nav_pitch = loiter_nav->get_pitch();
|
||||
float nav_roll = loiter_nav->get_roll();
|
||||
float nav_pitch = loiter_nav->get_pitch();
|
||||
|
||||
if (g2.wp_navalt_min > 0) {
|
||||
// user has requested an altitude below which navigation
|
||||
|
Loading…
Reference in New Issue
Block a user