mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_ESC_Telem: add are_motors_running() based on rpm feedback
add spin armed rpm to SITL use floats for rpm in API calls implement is_telemetry_active() simulate ESC telemetry in SITL
This commit is contained in:
parent
ab64480d2b
commit
b9280630f5
@ -24,6 +24,8 @@
|
||||
|
||||
//#define ESC_TELEM_DEBUG
|
||||
|
||||
#define ESC_RPM_CHECK_TIMEOUT_US 100000UL // timeout for motor running validity
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// table of user settable parameters
|
||||
@ -117,6 +119,40 @@ uint8_t AP_ESC_Telem::get_num_active_escs() const {
|
||||
return __builtin_popcount(active);
|
||||
}
|
||||
|
||||
// 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
|
||||
{
|
||||
const uint32_t now = AP_HAL::micros();
|
||||
|
||||
for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {
|
||||
if (BIT_IS_SET(servo_channel_mask, i)) {
|
||||
const volatile AP_ESC_Telem_Backend::RpmData& rpmdata = _rpm_data[i];
|
||||
// we choose a relatively strict measure of health so that failsafe actions can rely on the results
|
||||
if (now < rpmdata.last_update_us || now - rpmdata.last_update_us > ESC_RPM_CHECK_TIMEOUT_US) {
|
||||
return false;
|
||||
}
|
||||
if (rpmdata.rpm < min_rpm) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
// is telemetry active for the provided channel mask
|
||||
bool AP_ESC_Telem::is_telemetry_active(uint32_t servo_channel_mask) const
|
||||
{
|
||||
for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {
|
||||
if (BIT_IS_SET(servo_channel_mask, i)) {
|
||||
// no data received
|
||||
if (get_last_telem_data_ms(i) == 0 && _rpm_data[i].last_update_us == 0) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
// get an individual ESC's slewed rpm if available, returns true on success
|
||||
bool AP_ESC_Telem::get_rpm(uint8_t esc_index, float& rpm) const
|
||||
{
|
||||
|
@ -42,6 +42,9 @@ public:
|
||||
// return the average motor RPM
|
||||
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;
|
||||
|
||||
// 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;
|
||||
|
||||
@ -91,6 +94,9 @@ public:
|
||||
// udpate at 10Hz to log telemetry
|
||||
void update();
|
||||
|
||||
// is rpm telemetry configured for the provided channel mask
|
||||
bool is_telemetry_active(uint32_t servo_channel_mask) const;
|
||||
|
||||
// callback to update the rpm in the frontend, should be called by the driver when new data is available
|
||||
// can also be called from scripting
|
||||
void update_rpm(const uint8_t esc_index, const uint16_t new_rpm, const float error_rate);
|
||||
|
@ -36,13 +36,34 @@ void AP_ESC_Telem_SITL::update()
|
||||
return;
|
||||
}
|
||||
|
||||
#if HAL_WITH_ESC_TELEM
|
||||
for (uint8_t i = 0; i < sitl->state.num_motors; i++) {
|
||||
// some fake values so that is_telemetry_active() returns true
|
||||
TelemetryData t {
|
||||
.temperature_cdeg = 32,
|
||||
.voltage = 16.8f,
|
||||
.current = 0.8f,
|
||||
.consumption_mah = 1.0f,
|
||||
};
|
||||
|
||||
update_telem_data(i, t,
|
||||
AP_ESC_Telem_Backend::TelemetryType::CURRENT
|
||||
| AP_ESC_Telem_Backend::TelemetryType::VOLTAGE
|
||||
| AP_ESC_Telem_Backend::TelemetryType::CONSUMPTION
|
||||
| AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE);
|
||||
}
|
||||
|
||||
if (is_zero(sitl->throttle)) {
|
||||
if (!is_zero(sitl->esc_rpm_armed) && hal.util->get_soft_armed()) {
|
||||
for (uint8_t i = 0; i < sitl->state.num_motors; i++) {
|
||||
update_rpm(i, sitl->esc_rpm_armed);
|
||||
}
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
#if HAL_WITH_ESC_TELEM
|
||||
for (uint8_t i = 0; i < sitl->state.num_motors; i++) {
|
||||
update_rpm(i, sitl->state.rpm[sitl->state.vtol_motor_start+i]);
|
||||
update_rpm(i, MAX(sitl->state.rpm[sitl->state.vtol_motor_start+i], sitl->esc_rpm_armed));
|
||||
}
|
||||
#endif
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user