mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Motors: setup RC speed for tailsitters
This commit is contained in:
parent
1db3b31686
commit
f571b34fd7
@ -35,6 +35,15 @@ void AP_MotorsTailsitter::init(motor_frame_class frame_class, motor_frame_type f
|
||||
_flags.initialised_ok = (frame_class == MOTOR_FRAME_TAILSITTER);
|
||||
}
|
||||
|
||||
|
||||
/// Constructor
|
||||
AP_MotorsTailsitter::AP_MotorsTailsitter(uint16_t loop_rate, uint16_t speed_hz) :
|
||||
AP_MotorsMulticopter(loop_rate, speed_hz)
|
||||
{
|
||||
SRV_Channels::set_rc_frequency(SRV_Channel::k_throttleLeft, speed_hz);
|
||||
SRV_Channels::set_rc_frequency(SRV_Channel::k_throttleRight, speed_hz);
|
||||
}
|
||||
|
||||
void AP_MotorsTailsitter::output_to_motors()
|
||||
{
|
||||
if (!_flags.initialised_ok) {
|
||||
|
@ -12,10 +12,7 @@ class AP_MotorsTailsitter : public AP_MotorsMulticopter {
|
||||
public:
|
||||
|
||||
/// Constructor
|
||||
AP_MotorsTailsitter(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
|
||||
AP_MotorsMulticopter(loop_rate, speed_hz)
|
||||
{
|
||||
};
|
||||
AP_MotorsTailsitter(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT);
|
||||
|
||||
// init
|
||||
void init(motor_frame_class frame_class, motor_frame_type frame_type);
|
||||
|
Loading…
Reference in New Issue
Block a user