mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-25 01:03:59 -04:00
TradHeli: Add yaw-only rate request function for flybar acro mode.
This commit is contained in:
parent
1becab3eed
commit
32cb2bbce1
@ -34,13 +34,15 @@ static void heli_acro_run()
|
|||||||
if(motors.armed() && heli_flags.init_targets_on_arming) {
|
if(motors.armed() && heli_flags.init_targets_on_arming) {
|
||||||
heli_flags.init_targets_on_arming=false;
|
heli_flags.init_targets_on_arming=false;
|
||||||
attitude_control.relax_bf_rate_controller();
|
attitude_control.relax_bf_rate_controller();
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// To-Do: add support for flybarred helis
|
if (!motors.has_flybar()){
|
||||||
|
// convert the input to the desired body frame rate
|
||||||
// convert the input to the desired body frame rate
|
get_pilot_desired_angle_rates(g.rc_1.control_in, g.rc_2.control_in, g.rc_4.control_in, target_roll, target_pitch, target_yaw);
|
||||||
get_pilot_desired_angle_rates(g.rc_1.control_in, g.rc_2.control_in, g.rc_4.control_in, target_roll, target_pitch, target_yaw);
|
}else{
|
||||||
|
// flybar helis only need yaw rate control
|
||||||
|
get_pilot_desired_yaw_rate(g.rc_4.control_in, target_yaw);
|
||||||
|
}
|
||||||
|
|
||||||
// run attitude controller
|
// run attitude controller
|
||||||
attitude_control.rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw);
|
attitude_control.rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw);
|
||||||
@ -49,4 +51,15 @@ static void heli_acro_run()
|
|||||||
attitude_control.set_throttle_out(g.rc_3.control_in, false);
|
attitude_control.set_throttle_out(g.rc_3.control_in, false);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// get_pilot_desired_yaw_rate - transform pilot's yaw input into a desired yaw angle rate
|
||||||
|
// returns desired yaw rate in centi-degrees-per-second
|
||||||
|
static void get_pilot_desired_yaw_rate(int16_t yaw_in, float &yaw_out)
|
||||||
|
{
|
||||||
|
// calculate rate request
|
||||||
|
float rate_bf_yaw_request = yaw_in * g.acro_yaw_p;
|
||||||
|
|
||||||
|
// hand back rate request
|
||||||
|
yaw_out = rate_bf_yaw_request;
|
||||||
|
}
|
||||||
|
|
||||||
#endif //HELI_FRAME
|
#endif //HELI_FRAME
|
||||||
|
Loading…
Reference in New Issue
Block a user