Browse Source

AP_KDECAN: fix compilation when HAL_WITH_ESC_TELEM == 0

c415-sdk
Dr.-Ing. Amilcar do Carmo Lucas 4 years ago committed by Peter Barker
parent
commit
f4409066bc
  1. 2
      libraries/AP_KDECAN/AP_KDECAN.cpp

2
libraries/AP_KDECAN/AP_KDECAN.cpp

@ -437,6 +437,7 @@ void AP_KDECAN::loop() @@ -437,6 +437,7 @@ void AP_KDECAN::loop()
int16_t res = _can_iface->receive(frame, rx_time, flags);
if (res == 1) {
#if HAL_WITH_ESC_TELEM
frame_id_t id { .value = frame.id & AP_HAL::CANFrame::MaskExtID };
// check if frame is valid: directed at autopilot, doesn't come from broadcast and ESC was detected before
@ -470,6 +471,7 @@ void AP_KDECAN::loop() @@ -470,6 +471,7 @@ void AP_KDECAN::loop()
break;
}
}
#endif // HAL_WITH_ESC_TELEM
}
}

Loading…
Cancel
Save