mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_Motors: support direct rate outputs for multicopters
This commit is contained in:
parent
892f2d4256
commit
37566d079f
@ -255,6 +255,9 @@ void AP_MotorsMulticopter::output()
|
||||
|
||||
// output any booster throttle
|
||||
output_boost_throttle();
|
||||
|
||||
// output raw roll/pitch/yaw/thrust
|
||||
output_rpyt();
|
||||
};
|
||||
|
||||
// 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
|
||||
void AP_MotorsMulticopter::output_min()
|
||||
{
|
||||
|
@ -133,7 +133,10 @@ protected:
|
||||
|
||||
// output booster throttle, if any
|
||||
virtual void output_boost_throttle(void);
|
||||
|
||||
|
||||
// output roll/pitch/yaw/thrust
|
||||
virtual void output_rpyt(void);
|
||||
|
||||
// save parameters as part of disarming
|
||||
void save_params_on_disarm() override;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user