mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_PiccoloCAN: Fix ESC voltage and current telem scaling
This commit is contained in:
parent
0458d424af
commit
865da3a0f0
@ -743,8 +743,8 @@ bool AP_PiccoloCAN::handle_esc_message(AP_HAL::CANFrame &frame)
|
|||||||
|
|
||||||
AP_ESC_Telem_Backend::TelemetryData telem {};
|
AP_ESC_Telem_Backend::TelemetryData telem {};
|
||||||
|
|
||||||
telem.voltage = float(esc.voltage) * 0.01f;
|
telem.voltage = float(esc.voltage) * 0.1f;
|
||||||
telem.current = float(esc.current) * 0.01f;
|
telem.current = float(esc.current) * 0.1f;
|
||||||
telem.motor_temp_cdeg = int16_t(esc.motorTemperature * 100);
|
telem.motor_temp_cdeg = int16_t(esc.motorTemperature * 100);
|
||||||
|
|
||||||
update_telem_data(addr, telem,
|
update_telem_data(addr, telem,
|
||||||
|
Loading…
Reference in New Issue
Block a user