mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: squash compile warning
This commit is contained in:
parent
61fc5fc703
commit
52a809aa22
|
@ -181,7 +181,7 @@ void AP_RCProtocol_Backend::log_data(AP_RCProtocol::rcprotocol_t prot, uint32_t
|
||||||
#if HAL_LOGGING_ENABLED && AP_RC_CHANNEL_ENABLED
|
#if HAL_LOGGING_ENABLED && AP_RC_CHANNEL_ENABLED
|
||||||
|
|
||||||
#if (CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX)
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX)
|
||||||
if (&rc() == nullptr) { // allow running without RC_Channels if we are doing the examples
|
if (RC_Channels::get_singleton() == nullptr) { // allow running without RC_Channels if we are doing the examples
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -180,7 +180,6 @@ private:
|
||||||
|
|
||||||
uint32_t _last_frame_time_us;
|
uint32_t _last_frame_time_us;
|
||||||
uint32_t _last_tx_frame_time_us;
|
uint32_t _last_tx_frame_time_us;
|
||||||
uint32_t _last_uart_start_time_ms;
|
|
||||||
uint32_t _last_rx_frame_time_us;
|
uint32_t _last_rx_frame_time_us;
|
||||||
uint32_t _start_frame_time_us;
|
uint32_t _start_frame_time_us;
|
||||||
bool telem_available;
|
bool telem_available;
|
||||||
|
|
Loading…
Reference in New Issue