AP_Periph: cope with GCS enabled for ESC telem
thanks Tom!
This commit is contained in:
parent
c9b35ccfc8
commit
75959450ca
@ -307,7 +307,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
||||
// @RebootRequired: True
|
||||
GSCALAR(esc_pwm_type, "ESC_PWM_TYPE", 0),
|
||||
|
||||
#if HAL_WITH_ESC_TELEM
|
||||
#if HAL_WITH_ESC_TELEM && !HAL_GCS_ENABLED
|
||||
// @Param: ESC_TELEM_PORT
|
||||
// @DisplayName: ESC Telemetry Serial Port
|
||||
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to ESC Telemetry
|
||||
|
@ -106,7 +106,7 @@ public:
|
||||
|
||||
#ifdef HAL_PERIPH_ENABLE_RC_OUT
|
||||
AP_Int8 esc_pwm_type;
|
||||
#if HAL_WITH_ESC_TELEM
|
||||
#if HAL_WITH_ESC_TELEM && !HAL_GCS_ENABLED
|
||||
AP_Int8 esc_telem_port;
|
||||
#endif
|
||||
#endif
|
||||
|
@ -31,9 +31,11 @@ void AP_Periph_FW::rcout_init()
|
||||
// start up with safety enabled. This disables the pwm output until we receive an packet from the rempte system
|
||||
hal.rcout->force_safety_on();
|
||||
|
||||
#if HAL_WITH_ESC_TELEM && !HAL_GCS_ENABLED
|
||||
if (g.esc_telem_port >= 0) {
|
||||
serial_manager.set_protocol_and_baud(g.esc_telem_port, AP_SerialManager::SerialProtocol_ESCTelemetry, 115200);
|
||||
}
|
||||
#endif
|
||||
|
||||
SRV_Channels::init();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user