mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-03-24 02:24:09 +08:00
ESC check cleanup
This commit is contained in:
@@ -71,8 +71,6 @@ static constexpr const char *esc_fault_reason_str(esc_fault_reason_t esc_fault_r
|
||||
void EscChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
{
|
||||
const hrt_abstime now = hrt_absolute_time();
|
||||
const hrt_abstime esc_init_time = 700_ms; // Some DShot ESCs are unresponsive for ~550ms during their initialization
|
||||
|
||||
esc_status_s esc_status;
|
||||
|
||||
// Run motor status checks even when no new ESC data arrives (to detect timeouts)
|
||||
@@ -95,9 +93,9 @@ void EscChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
|
||||
_motor_failure_mask = mask;
|
||||
reporter.setIsPresent(health_component_t::motors_escs);
|
||||
reporter.failsafeFlags().fd_motor_failure = mask != 0;
|
||||
reporter.failsafeFlags().fd_motor_failure = (mask != 0);
|
||||
|
||||
} else if ((_param_com_arm_chk_escs.get() > 0) && now - _start_time > esc_init_time) { // Allow ESCs to init
|
||||
} else if ((_param_com_arm_chk_escs.get() > 0) && now > _start_time + 3_s) { // Allow ESCs to init
|
||||
/* EVENT
|
||||
* @description
|
||||
* <profile name="dev">
|
||||
@@ -117,8 +115,7 @@ uint16_t EscChecks::checkEscOnline(const Context &context, Report &reporter, con
|
||||
{
|
||||
// Check if one or more the ESCs are offline
|
||||
uint16_t mask = 0;
|
||||
char esc_fail_msg[esc_status_s::CONNECTED_ESC_MAX * 6 + 1] {};
|
||||
esc_fail_msg[0] = '\0';
|
||||
char esc_fail_msg[esc_status_s::CONNECTED_ESC_MAX * 6 + 1] = "";
|
||||
|
||||
for (int esc_index = 0; esc_index < esc_status_s::CONNECTED_ESC_MAX; esc_index++) {
|
||||
if (!math::isInRange(esc_status.esc[esc_index].actuator_function,
|
||||
|
||||
@@ -85,7 +85,7 @@ void FailureDetector::publishStatus(bool esc_arm_status, uint16_t motor_failure_
|
||||
failure_detector_status.fd_arm_escs = esc_arm_status || (motor_failure_mask != 0);
|
||||
failure_detector_status.fd_battery = _failure_detector_status.flags.battery;
|
||||
failure_detector_status.fd_imbalanced_prop = _failure_detector_status.flags.imbalanced_prop;
|
||||
failure_detector_status.fd_motor = (motor_failure_mask != 0) || (_failure_injector.getMotorStopMask() != 0);
|
||||
failure_detector_status.fd_motor = (motor_failure_mask != 0);
|
||||
failure_detector_status.imbalanced_prop_metric = _imbalanced_prop_lpf.getState();
|
||||
failure_detector_status.motor_failure_mask = motor_failure_mask;
|
||||
failure_detector_status.motor_stop_mask = _failure_injector.getMotorStopMask();
|
||||
|
||||
@@ -68,10 +68,8 @@ union failure_detector_status_u {
|
||||
uint16_t pitch : 1;
|
||||
uint16_t alt : 1;
|
||||
uint16_t ext : 1;
|
||||
uint16_t arm_escs : 1;
|
||||
uint16_t battery : 1;
|
||||
uint16_t imbalanced_prop : 1;
|
||||
uint16_t motor : 1;
|
||||
} flags;
|
||||
uint16_t value {0};
|
||||
};
|
||||
|
||||
Reference in New Issue
Block a user