Skip to content

Commit

Permalink
AP_CANManager: remove KDECAN from CANTester
Browse files Browse the repository at this point in the history
  • Loading branch information
magicrub authored and tridge committed Apr 17, 2023
1 parent eed3cf3 commit 5ca3aa6
Show file tree
Hide file tree
Showing 5 changed files with 3 additions and 383 deletions.
56 changes: 1 addition & 55 deletions libraries/AP_CANManager/AP_CANTester.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,15 +30,14 @@
#include <uavcan/equipment/esc/Status.hpp>
#include <uavcan/equipment/esc/RawCommand.hpp>
#include <AP_HAL/utility/sparse-endian.h>
#include "AP_CANTester_KDECAN.h"
extern const AP_HAL::HAL& hal;

const AP_Param::GroupInfo CANTester::var_info[] = {
// @Param: ID
// @DisplayName: CAN Test Index
// @Description: Selects the Index of Test that needs to be run recursively, this value gets reset to 0 at boot.
// @Range: 0 4
// @Values: 0:TEST_NONE, 1:TEST_LOOPBACK,2:TEST_BUSOFF_RECOVERY,3:TEST_UAVCAN_DNA,5:TEST_KDE_CAN, 6:TEST_UAVCAN_ESC, 7:TEST_UAVCAN_FD_ESC
// @Values: 0:TEST_NONE, 1:TEST_LOOPBACK,2:TEST_BUSOFF_RECOVERY,3:TEST_UAVCAN_DNA,6:TEST_UAVCAN_ESC,7:TEST_UAVCAN_FD_ESC
// @User: Advanced
AP_GROUPINFO("ID", 1, CANTester, _test_id, 0),

Expand Down Expand Up @@ -192,18 +191,6 @@ void CANTester::main_thread()
gcs().send_text(MAV_SEVERITY_ALERT, "Only one iface needs to be set for DroneCAN_DNA_TEST");
}
break;
case CANTester::TEST_KDE_CAN:
if (_can_ifaces[1] == nullptr) {
gcs().send_text(MAV_SEVERITY_ALERT, "********Running KDE CAN Test********");
if (test_kdecan()) {
gcs().send_text(MAV_SEVERITY_ALERT, "********KDE CAN Test Pass********");
} else {
gcs().send_text(MAV_SEVERITY_ALERT, "********KDE CAN Test Fail********");
}
} else {
gcs().send_text(MAV_SEVERITY_ALERT, "Only one iface needs to be set for TEST_KDE_CAN");
}
break;
case CANTester::TEST_UAVCAN_ESC:
if (_can_ifaces[1] == nullptr) {
gcs().send_text(MAV_SEVERITY_ALERT, "********Running DroneCAN ESC Test********");
Expand Down Expand Up @@ -500,47 +487,6 @@ bool CANTester::test_uavcan_dna()
return true;
}

/*****************************************
* KDE CAN Test *
*****************************************/
bool CANTester::test_kdecan()
{
AP_CANTester_KDECAN* kdecan_test = new AP_CANTester_KDECAN;
if (kdecan_test == nullptr) {
gcs().send_text(MAV_SEVERITY_ERROR, "Failed to allocate KDECAN Tester");
return false;
}
kdecan_test->init(_can_ifaces[0]);

while (true) {
kdecan_test->loop();
static uint32_t last_print_ms;
static uint32_t last_enumsend_ms;
static uint8_t enum_count = 0;
uint32_t now = AP_HAL::millis();
if (now - last_print_ms >= 1000) {
last_print_ms = now;
kdecan_test->print_stats();
}
if (!_kdecan_enumeration) {
enum_count = 0;
}
if (now - last_enumsend_ms >= 2000 && enum_count < 4 && _kdecan_enumeration) {
last_enumsend_ms = now;
if (kdecan_test->send_enumeration(enum_count)) {
enum_count++;
}
}
}
return true;
}

bool CANTester::run_kdecan_enumeration(bool start_stop)
{
_kdecan_enumeration = start_stop;
return true;
}

/***********************************************
* DroneCAN ESC *
* *********************************************/
Expand Down
8 changes: 2 additions & 6 deletions libraries/AP_CANManager/AP_CANTester.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@ class CANTester : public AP_CANDriver

void init(uint8_t driver_index, bool enable_filters) override;
bool add_interface(AP_HAL::CANIface* can_iface) override;
bool run_kdecan_enumeration(bool start_stop);

static CANTester *get_cantester(uint8_t driver_index);

Expand All @@ -51,8 +50,8 @@ class CANTester : public AP_CANDriver
TEST_LOOPBACK,
TEST_BUSOFF_RECOVERY,
TEST_UAVCAN_DNA,
TEST_KDE_CAN,
TEST_UAVCAN_ESC,

TEST_UAVCAN_ESC = 6,
TEST_UAVCAN_FD_ESC,
TEST_END,
};
Expand All @@ -78,8 +77,6 @@ class CANTester : public AP_CANDriver

bool test_uavcan_dna();

bool test_kdecan();

bool test_uavcan_esc(bool enable_canfd);

// write frame on CAN bus, returns true on success
Expand All @@ -104,7 +101,6 @@ class CANTester : public AP_CANDriver
AP_Int32 _test_id;
AP_Int32 _loop_rate;
uint8_t _num_ifaces;
bool _kdecan_enumeration;
};
#endif //#if HAL_MAX_CAN_PROTOCOL_DRIVERS > 1 && !HAL_MINIMIZE_FEATURES && HAL_MAX_CAN_PROTOCOL_DRIVERS

236 changes: 0 additions & 236 deletions libraries/AP_CANManager/AP_CANTester_KDECAN.cpp

This file was deleted.

Loading

0 comments on commit 5ca3aa6

Please sign in to comment.