Browse Source

HAL_PX4: fixed build warnings

mission-4.1.18
Andrew Tridgell 7 years ago
parent
commit
95df35f102
  1. 6
      libraries/AP_HAL_PX4/RCInput.cpp
  2. 2
      libraries/AP_HAL_PX4/RCInput.h

6
libraries/AP_HAL_PX4/RCInput.cpp

@ -24,7 +24,7 @@ void PX4RCInput::init()
clear_overrides(); clear_overrides();
pthread_mutex_init(&rcin_mutex, nullptr); pthread_mutex_init(&rcin_mutex, nullptr);
#if HAL_RCINPUT_WITH_AP_RADIO #ifdef HAL_RCINPUT_WITH_AP_RADIO
radio = AP_Radio::instance(); radio = AP_Radio::instance();
if (radio) { if (radio) {
radio->init(); radio->init();
@ -161,7 +161,7 @@ void PX4RCInput::_timer_tick(void)
pthread_mutex_unlock(&rcin_mutex); pthread_mutex_unlock(&rcin_mutex);
} }
#if HAL_RCINPUT_WITH_AP_RADIO #ifdef HAL_RCINPUT_WITH_AP_RADIO
if (radio && radio->last_recv_us() != last_radio_us) { if (radio && radio->last_recv_us() != last_radio_us) {
last_radio_us = radio->last_recv_us(); last_radio_us = radio->last_recv_us();
pthread_mutex_lock(&rcin_mutex); pthread_mutex_lock(&rcin_mutex);
@ -190,7 +190,7 @@ bool PX4RCInput::rc_bind(int dsmMode)
return false; return false;
} }
#if HAL_RCINPUT_WITH_AP_RADIO #ifdef HAL_RCINPUT_WITH_AP_RADIO
if (radio) { if (radio) {
radio->start_recv_bind(); radio->start_recv_bind();
} }

2
libraries/AP_HAL_PX4/RCInput.h

@ -45,7 +45,7 @@ private:
uint8_t last_input_source = input_rc_s::RC_INPUT_SOURCE_UNKNOWN; uint8_t last_input_source = input_rc_s::RC_INPUT_SOURCE_UNKNOWN;
const char *input_source_name(uint8_t id) const; const char *input_source_name(uint8_t id) const;
#if HAL_RCINPUT_WITH_AP_RADIO #ifdef HAL_RCINPUT_WITH_AP_RADIO
AP_Radio *radio; AP_Radio *radio;
uint32_t last_radio_us; uint32_t last_radio_us;
#endif #endif

Loading…
Cancel
Save