mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 01:23:56 -03:00
AP_ESC_Telem: correct spelling mili -> milli
This commit is contained in:
parent
49e88b7aea
commit
fb8582e98e
@ -388,7 +388,7 @@ void AP_ESC_Telem::update()
|
|||||||
// voltage is in Volt
|
// voltage is in Volt
|
||||||
// current is in Ampere
|
// current is in Ampere
|
||||||
// esc_temp is in centi-degrees Celsius
|
// esc_temp is in centi-degrees Celsius
|
||||||
// current_tot is in mili-Ampere hours
|
// current_tot is in milli-Ampere hours
|
||||||
// motor_temp is in centi-degrees Celsius
|
// motor_temp is in centi-degrees Celsius
|
||||||
// error_rate is in percentage
|
// error_rate is in percentage
|
||||||
const struct log_Esc pkt{
|
const struct log_Esc pkt{
|
||||||
|
@ -20,7 +20,7 @@ public:
|
|||||||
float consumption_mah; // milli-Ampere.hours
|
float consumption_mah; // milli-Ampere.hours
|
||||||
uint32_t usage_s; // usage seconds
|
uint32_t usage_s; // usage seconds
|
||||||
int16_t motor_temp_cdeg; // centi-degrees C, negative values allowed
|
int16_t motor_temp_cdeg; // centi-degrees C, negative values allowed
|
||||||
uint32_t last_update_ms; // last update time in miliseconds, determines whether active
|
uint32_t last_update_ms; // last update time in milliseconds, determines whether active
|
||||||
uint16_t types; // telemetry types present
|
uint16_t types; // telemetry types present
|
||||||
uint16_t count; // number of times updated
|
uint16_t count; // number of times updated
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user