mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Copter: add angle inputs to Loiter
This commit is contained in:
parent
9544b1763b
commit
1540f98888
@ -69,6 +69,8 @@ void Copter::ModeLoiter::precision_loiter_xy()
|
|||||||
void Copter::ModeLoiter::run()
|
void Copter::ModeLoiter::run()
|
||||||
{
|
{
|
||||||
LoiterModeState loiter_state;
|
LoiterModeState loiter_state;
|
||||||
|
|
||||||
|
float target_roll, target_pitch;
|
||||||
float target_yaw_rate = 0.0f;
|
float target_yaw_rate = 0.0f;
|
||||||
float target_climb_rate = 0.0f;
|
float target_climb_rate = 0.0f;
|
||||||
float takeoff_climb_rate = 0.0f;
|
float takeoff_climb_rate = 0.0f;
|
||||||
@ -82,8 +84,12 @@ void Copter::ModeLoiter::run()
|
|||||||
// apply SIMPLE mode transform to pilot inputs
|
// apply SIMPLE mode transform to pilot inputs
|
||||||
update_simple_mode();
|
update_simple_mode();
|
||||||
|
|
||||||
|
// convert pilot input to lean angles
|
||||||
|
// ToDo: convert get_pilot_desired_lean_angles to return angles as floats
|
||||||
|
get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, wp_nav->get_loiter_angle_max_cd());
|
||||||
|
|
||||||
// process pilot's roll and pitch input
|
// process pilot's roll and pitch input
|
||||||
wp_nav->set_pilot_desired_acceleration(channel_roll->get_control_in(), channel_pitch->get_control_in());
|
wp_nav->set_pilot_desired_acceleration(target_roll, target_pitch);
|
||||||
|
|
||||||
// get pilot's desired yaw rate
|
// get pilot's desired yaw rate
|
||||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
|
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
|
||||||
|
Loading…
Reference in New Issue
Block a user