From eff316dd6bac03df5b107248279128df78fc1b53 Mon Sep 17 00:00:00 2001 From: Siddharth Purohit Date: Fri, 4 Oct 2019 12:32:26 +0530 Subject: [PATCH] AP_KDECAN: update prearm method to support snprintf methods --- libraries/AP_KDECAN/AP_KDECAN.cpp | 12 ++++++------ libraries/AP_KDECAN/AP_KDECAN.h | 2 +- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/libraries/AP_KDECAN/AP_KDECAN.cpp b/libraries/AP_KDECAN/AP_KDECAN.cpp index 2a3ad0bc3a..a4aa59635e 100644 --- a/libraries/AP_KDECAN/AP_KDECAN.cpp +++ b/libraries/AP_KDECAN/AP_KDECAN.cpp @@ -637,16 +637,16 @@ void AP_KDECAN::update() } } -bool AP_KDECAN::pre_arm_check(const char* &reason) +bool AP_KDECAN::pre_arm_check(char* reason, uint8_t reason_len) { if (!_enum_sem.take(1)) { debug_can(2, "KDECAN: failed to get enumeration semaphore on read\n\r"); - reason = "KDECAN enumeration state unknown"; + snprintf(reason, reason_len ,"KDECAN enumeration state unknown"); return false; } if (_enumeration_state != ENUMERATION_STOPPED) { - reason = "KDECAN enumeration running"; + snprintf(reason, reason_len ,"KDECAN enumeration running"); _enum_sem.give(); return false; } @@ -664,17 +664,17 @@ bool AP_KDECAN::pre_arm_check(const char* &reason) uint8_t num_present_escs = __builtin_popcount(_esc_present_bitmask); if (num_present_escs < num_expected_motors) { - reason = "Not enough KDECAN ESCs detected"; + snprintf(reason, reason_len ,"Not enough KDECAN ESCs detected"); return false; } if (num_present_escs > num_expected_motors) { - reason = "Too many KDECAN ESCs detected"; + snprintf(reason, reason_len ,"Too many KDECAN ESCs detected"); return false; } if (_esc_max_node_id != num_expected_motors) { - reason = "Wrong KDECAN node IDs, run enumeration"; + snprintf(reason, reason_len ,"Wrong KDECAN node IDs, run enumeration"); return false; } diff --git a/libraries/AP_KDECAN/AP_KDECAN.h b/libraries/AP_KDECAN/AP_KDECAN.h index 6582bdd9bc..68704720c6 100644 --- a/libraries/AP_KDECAN/AP_KDECAN.h +++ b/libraries/AP_KDECAN/AP_KDECAN.h @@ -49,7 +49,7 @@ public: void update(); // check that arming can happen - bool pre_arm_check(const char* &reason); + bool pre_arm_check(char* reason, uint8_t reason_len); // send MAVLink telemetry packets void send_mavlink(uint8_t chan);