VRBRAIN /AP_BoardConfig: changed definition of PWM_SERVO_MODE_12PWM only for VRBRAIN

This commit is contained in:
LukeMike 2016-07-05 18:57:56 +02:00 committed by Andrew Tridgell
parent bda59b890d
commit 95ae69eb1c

View File

@ -150,7 +150,9 @@ void AP_BoardConfig::init()
{ 4, PWM_SERVO_MODE_4PWM, 2 }, { 4, PWM_SERVO_MODE_4PWM, 2 },
{ 6, PWM_SERVO_MODE_6PWM, 0 }, { 6, PWM_SERVO_MODE_6PWM, 0 },
{ 7, PWM_SERVO_MODE_3PWM1CAP, 2 }, { 7, PWM_SERVO_MODE_3PWM1CAP, 2 },
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
{ 8, PWM_SERVO_MODE_12PWM, 0 }, { 8, PWM_SERVO_MODE_12PWM, 0 },
#endif
}; };
uint8_t mode_parm = (uint8_t)_pwm_count.get(); uint8_t mode_parm = (uint8_t)_pwm_count.get();
uint8_t i; uint8_t i;