mirror of https://github.com/ArduPilot/ardupilot
AP_Periph: fixed HWESC RPM and current readings
This commit is contained in:
parent
49314b2b86
commit
998f93c7c9
|
@ -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);
|
||||
|
|
|
@ -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;
|
||||
}
|
||||
|
|
|
@ -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;
|
||||
|
||||
|
|
Loading…
Reference in New Issue