mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: loiter mode gets roll and pitch from loiter_nav
both wp_nav and loiter_nav's get_roll() and get_pitch() simply get their values from the same underlying position controller
This commit is contained in:
parent
94738c3f86
commit
29d05dfeac
@ -122,7 +122,7 @@ void Copter::ModeLoiter::run()
|
|||||||
attitude_control->set_yaw_target_to_current_heading();
|
attitude_control->set_yaw_target_to_current_heading();
|
||||||
pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
|
pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
|
||||||
loiter_nav->init_target();
|
loiter_nav->init_target();
|
||||||
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate);
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(loiter_nav->get_roll(), loiter_nav->get_pitch(), target_yaw_rate);
|
||||||
pos_control->update_z_controller();
|
pos_control->update_z_controller();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user