mirror of https://github.com/ArduPilot/ardupilot
AP_ESC_Telem: add method to get the temperature of the motor with highest temperature
This commit is contained in:
parent
f9b149e793
commit
26c6224b2e
|
@ -145,6 +145,22 @@ bool AP_ESC_Telem::get_motor_temperature(uint8_t esc_index, int16_t& temp) const
|
|||
return true;
|
||||
}
|
||||
|
||||
// get the highest ESC temperature in centi-degrees if available, returns true if there is valid data for at least one ESC
|
||||
bool AP_ESC_Telem::get_highest_motor_temperature(int16_t& temp) const
|
||||
{
|
||||
uint8_t valid_escs = 0;
|
||||
|
||||
for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {
|
||||
int16_t temp_temp;
|
||||
if (get_motor_temperature(i, temp_temp)) {
|
||||
temp = MAX(temp, temp_temp);
|
||||
valid_escs++;
|
||||
}
|
||||
}
|
||||
|
||||
return valid_escs > 0;
|
||||
}
|
||||
|
||||
// get an individual ESC's current in Ampere if available, returns true on success
|
||||
bool AP_ESC_Telem::get_current(uint8_t esc_index, float& amps) const
|
||||
{
|
||||
|
|
|
@ -39,6 +39,9 @@ public:
|
|||
// get an individual motor's temperature in centi-degrees if available, returns true on success
|
||||
bool get_motor_temperature(uint8_t esc_index, int16_t& temp) const;
|
||||
|
||||
// get the highest ESC temperature in centi-degrees if available, returns true if there is valid data for at least one ESC
|
||||
bool get_highest_motor_temperature(int16_t& temp) const;
|
||||
|
||||
// get an individual ESC's current in Ampere if available, returns true on success
|
||||
bool get_current(uint8_t esc_index, float& amps) const;
|
||||
|
||||
|
|
Loading…
Reference in New Issue