From dae9cbfad88e4015720e1fa30dd1ff6f469edc04 Mon Sep 17 00:00:00 2001 From: Siddharth Purohit Date: Sat, 19 Jan 2019 13:32:21 +0800 Subject: [PATCH] AP_KDECAN: add argument for CAN filter, unsupported --- libraries/AP_KDECAN/AP_KDECAN.cpp | 2 +- libraries/AP_KDECAN/AP_KDECAN.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_KDECAN/AP_KDECAN.cpp b/libraries/AP_KDECAN/AP_KDECAN.cpp index ef18f2d85b..092201485f 100644 --- a/libraries/AP_KDECAN/AP_KDECAN.cpp +++ b/libraries/AP_KDECAN/AP_KDECAN.cpp @@ -70,7 +70,7 @@ AP_KDECAN *AP_KDECAN::get_kdecan(uint8_t driver_index) return static_cast(AP::can().get_driver(driver_index)); } -void AP_KDECAN::init(uint8_t driver_index) +void AP_KDECAN::init(uint8_t driver_index, bool enable_filters) { _driver_index = driver_index; diff --git a/libraries/AP_KDECAN/AP_KDECAN.h b/libraries/AP_KDECAN/AP_KDECAN.h index bc598df599..6582bdd9bc 100644 --- a/libraries/AP_KDECAN/AP_KDECAN.h +++ b/libraries/AP_KDECAN/AP_KDECAN.h @@ -43,7 +43,7 @@ public: // Return KDECAN from @driver_index or nullptr if it's not ready or doesn't exist static AP_KDECAN *get_kdecan(uint8_t driver_index); - void init(uint8_t driver_index) override; + void init(uint8_t driver_index, bool enable_filters) override; // called from SRV_Channels void update();