AP_Motors: support direct rate outputs for multicopters

This commit is contained in:
Andrew Tridgell 2019-10-15 10:25:51 +11:00
parent 892f2d4256
commit 37566d079f
2 changed files with 16 additions and 1 deletions

View File

@ -255,6 +255,9 @@ void AP_MotorsMulticopter::output()
// output any booster throttle // output any booster throttle
output_boost_throttle(); output_boost_throttle();
// output raw roll/pitch/yaw/thrust
output_rpyt();
}; };
// output booster throttle, if any // output booster throttle, if any
@ -266,6 +269,15 @@ void AP_MotorsMulticopter::output_boost_throttle(void)
} }
} }
// output roll/pitch/yaw/thrust
void AP_MotorsMulticopter::output_rpyt(void)
{
SRV_Channels::set_output_scaled(SRV_Channel::k_roll_out, _roll_in_ff * 4500);
SRV_Channels::set_output_scaled(SRV_Channel::k_pitch_out, _pitch_in_ff * 4500);
SRV_Channels::set_output_scaled(SRV_Channel::k_yaw_out, _yaw_in_ff * 4500);
SRV_Channels::set_output_scaled(SRV_Channel::k_thrust_out, get_throttle() * 1000);
}
// sends minimum values out to the motors // sends minimum values out to the motors
void AP_MotorsMulticopter::output_min() void AP_MotorsMulticopter::output_min()
{ {

View File

@ -133,7 +133,10 @@ protected:
// output booster throttle, if any // output booster throttle, if any
virtual void output_boost_throttle(void); virtual void output_boost_throttle(void);
// output roll/pitch/yaw/thrust
virtual void output_rpyt(void);
// save parameters as part of disarming // save parameters as part of disarming
void save_params_on_disarm() override; void save_params_on_disarm() override;