mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 19:53:57 -04:00
AP_MotorsTri: revert tail servo to Ch7
This commit is contained in:
parent
182db2ece0
commit
d777166c6f
@ -130,7 +130,7 @@ void AP_MotorsTri::output_min()
|
||||
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
|
||||
uint16_t AP_MotorsTri::get_motor_mask()
|
||||
{
|
||||
// tri copter uses channels 1,2,3 and 4
|
||||
// tri copter uses channels 1,2,4 and 7
|
||||
return (1U << pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1])) |
|
||||
(1U << pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2])) |
|
||||
(1U << pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4])) |
|
||||
|
@ -12,7 +12,7 @@
|
||||
#include "AP_Motors.h"
|
||||
|
||||
// tail servo uses channel 7
|
||||
#define AP_MOTORS_CH_TRI_YAW CH_3
|
||||
#define AP_MOTORS_CH_TRI_YAW CH_7
|
||||
|
||||
/// @class AP_MotorsTri
|
||||
class AP_MotorsTri : public AP_Motors {
|
||||
|
Loading…
Reference in New Issue
Block a user