Skip to content
Snippets Groups Projects
Commit 2cd6d986 authored by Randy Mackay's avatar Randy Mackay
Browse files

TradHeli: call passthrough_bf_roll_pitch_rate_yaw

parent 691a3d81
No related branches found
No related tags found
No related merge requests found
...@@ -39,14 +39,15 @@ static void heli_acro_run() ...@@ -39,14 +39,15 @@ static void heli_acro_run()
if (!motors.has_flybar()){ 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);
// run attitude controller
attitude_control.rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw);
}else{ }else{
// flybar helis only need yaw rate control // flybar helis only need yaw rate control
get_pilot_desired_yaw_rate(g.rc_4.control_in, target_yaw); get_pilot_desired_yaw_rate(g.rc_4.control_in, target_yaw);
// run attitude controller
attitude_control.passthrough_bf_roll_pitch_rate_yaw(g.rc_1.control_in, g.rc_2.control_in, target_yaw);
} }
// run attitude controller
attitude_control.rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw);
// output pilot's throttle without angle boost // output pilot's throttle without angle boost
attitude_control.set_throttle_out(g.rc_3.control_in, false); attitude_control.set_throttle_out(g.rc_3.control_in, false);
} }
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment