From 998f93c7c92bf90cce41af346c54721838a55053 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 10 Mar 2020 09:36:59 +1100 Subject: [PATCH] AP_Periph: fixed HWESC RPM and current readings --- Tools/AP_Periph/can.cpp | 2 +- Tools/AP_Periph/hwing_esc.cpp | 6 +++--- Tools/AP_Periph/hwing_esc.h | 10 +++++----- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index e83e9d8b83..0d83b248c4 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -1119,7 +1119,7 @@ void AP_Periph_FW::hwesc_telem_update() pkt.current = t.current; pkt.temperature = t.temperature; pkt.rpm = t.rpm; - pkt.power_rating_pct = (t.load & 0x7F); + pkt.power_rating_pct = t.phase_current; fix_float16(pkt.voltage); fix_float16(pkt.current); diff --git a/Tools/AP_Periph/hwing_esc.cpp b/Tools/AP_Periph/hwing_esc.cpp index 4fdaa9c48c..861c4a6f4c 100644 --- a/Tools/AP_Periph/hwing_esc.cpp +++ b/Tools/AP_Periph/hwing_esc.cpp @@ -103,12 +103,12 @@ bool HWESC_Telem::parse_packet(void) decoded.counter = be32toh(pkt.counter); decoded.throttle_req = be16toh(pkt.throttle_req); decoded.throttle = be16toh(pkt.throttle); - decoded.rpm = be16toh(pkt.rpm); + decoded.rpm = be16toh(pkt.rpm) * 5.0 / 7.0; // scale from eRPM to RPM decoded.voltage = be16toh(pkt.voltage) * 0.1; - decoded.load = int16_t(be16toh(pkt.load)); + decoded.phase_current = int16_t(be16toh(pkt.phase_current)) * 0.01; decoded.current = int16_t(be16toh(pkt.current)) * 0.01; decoded.temperature = be16toh(pkt.temperature); - decoded.unknown = be16toh(pkt.unknown); + decoded.status = be16toh(pkt.status); return true; } diff --git a/Tools/AP_Periph/hwing_esc.h b/Tools/AP_Periph/hwing_esc.h index 36928501b9..5db0d8974a 100644 --- a/Tools/AP_Periph/hwing_esc.h +++ b/Tools/AP_Periph/hwing_esc.h @@ -21,12 +21,12 @@ public: uint32_t counter; uint16_t throttle_req; uint16_t throttle; - uint16_t rpm; + float rpm; float voltage; - uint16_t load; + float phase_current; float current; uint16_t temperature; - uint16_t unknown; + uint16_t status; }; const HWESC &get_telem(void) { @@ -45,9 +45,9 @@ private: uint16_t rpm; uint16_t voltage; int16_t current; - int16_t load; + int16_t phase_current; uint16_t temperature; - uint16_t unknown; + uint16_t status; uint16_t crc; } pkt;