AP_Periph: fixed current decoding for HWESC

This commit is contained in:
Andrew Tridgell 2020-02-14 18:52:07 +11:00
parent bca1bd2c72
commit 5462c468cd
2 changed files with 4 additions and 4 deletions

View File

@ -105,8 +105,8 @@ bool HWESC_Telem::parse_packet(void)
decoded.throttle = be16toh(pkt.throttle); decoded.throttle = be16toh(pkt.throttle);
decoded.rpm = be16toh(pkt.rpm); decoded.rpm = be16toh(pkt.rpm);
decoded.voltage = be16toh(pkt.voltage) * 0.1; decoded.voltage = be16toh(pkt.voltage) * 0.1;
decoded.load = be16toh(pkt.load); decoded.load = int16_t(be16toh(pkt.load));
decoded.current = be16toh(pkt.current); decoded.current = int16_t(be16toh(pkt.current)) * 0.01;
decoded.temperature = be16toh(pkt.temperature); decoded.temperature = be16toh(pkt.temperature);
decoded.unknown = be16toh(pkt.unknown); decoded.unknown = be16toh(pkt.unknown);

View File

@ -44,8 +44,8 @@ private:
uint16_t throttle; uint16_t throttle;
uint16_t rpm; uint16_t rpm;
uint16_t voltage; uint16_t voltage;
uint16_t load; int16_t current;
uint16_t current; int16_t load;
uint16_t temperature; uint16_t temperature;
uint16_t unknown; uint16_t unknown;
uint16_t crc; uint16_t crc;