AP_ESC_Telem: Add support for a max rpm check on the motors running check

This commit is contained in:
Michael du Breuil 2023-04-28 13:02:55 -07:00 committed by Randy Mackay
parent f1be6df93e
commit 3de912f2b8
2 changed files with 5 additions and 3 deletions

View File

@ -123,7 +123,7 @@ uint8_t AP_ESC_Telem::get_num_active_escs() const {
}
// return the whether all the motors in servo_channel_mask are running
bool AP_ESC_Telem::are_motors_running(uint32_t servo_channel_mask, float min_rpm) const
bool AP_ESC_Telem::are_motors_running(uint32_t servo_channel_mask, float min_rpm, float max_rpm) const
{
const uint32_t now = AP_HAL::micros();
@ -137,6 +137,9 @@ bool AP_ESC_Telem::are_motors_running(uint32_t servo_channel_mask, float min_rpm
if (rpmdata.rpm < min_rpm) {
return false;
}
if ((max_rpm > 0) && (rpmdata.rpm > max_rpm)) {
return false;
}
}
}
return true;

View File

@ -39,7 +39,7 @@ public:
float get_average_motor_rpm() const { return get_average_motor_rpm(0xFFFFFFFF); }
// determine whether all the motors in servo_channel_mask are running
bool are_motors_running(uint32_t servo_channel_mask, float min_rpm) const;
bool are_motors_running(uint32_t servo_channel_mask, float min_rpm, float max_rpm) const;
// get an individual ESC's temperature in centi-degrees if available, returns true on success
bool get_temperature(uint8_t esc_index, int16_t& temp) const;
@ -136,4 +136,3 @@ namespace AP {
};
#endif // HAL_WITH_ESC_TELEM