mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
escCheck: rename MOTFAIL_TOUT -> MOTFAIL_TIME and further cleanup
This commit is contained in:
parent
035ccc8395
commit
2ff83e7e7c
@ -31,9 +31,6 @@
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <parameters/param.h>
|
||||
|
||||
/**
|
||||
* Motor Failure Thrust Threshold
|
||||
*
|
||||
@ -65,19 +62,6 @@ PARAM_DEFINE_FLOAT(MOTFAIL_THR, 0.2f);
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MOTFAIL_C2T, 35.f);
|
||||
|
||||
/**
|
||||
* Motor Failure Hysteresis Time
|
||||
*
|
||||
* Motor failure only triggers after current thresholds are exceeded for this time.
|
||||
*
|
||||
* @group Motor Failure
|
||||
* @unit ms
|
||||
* @min 10
|
||||
* @max 10000
|
||||
* @increment 100
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MOTFAIL_TOUT, 1000);
|
||||
|
||||
/**
|
||||
* Undercurrent motor failure limit offset
|
||||
*
|
||||
@ -105,3 +89,16 @@ PARAM_DEFINE_FLOAT(MOTFAIL_LOW_OFF, 10.f);
|
||||
* @increment 1
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MOTFAIL_HIGH_OFF, 10.f);
|
||||
|
||||
/**
|
||||
* Motor Failure Hysteresis Time
|
||||
*
|
||||
* Motor failure only triggers after current thresholds are exceeded for this time.
|
||||
*
|
||||
* @group Motor Failure
|
||||
* @unit ms
|
||||
* @min 10
|
||||
* @max 10000
|
||||
* @increment 100
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MOTFAIL_TIME, 1000);
|
||||
|
||||
@ -273,8 +273,8 @@ uint16_t EscChecks::checkMotorStatus(const Context &context, Report &reporter, c
|
||||
bool current_too_low = current < (thrust * _param_motfail_c2t.get()) - _param_motfail_low_off.get();
|
||||
bool current_too_high = current > (thrust * _param_motfail_c2t.get()) + _param_motfail_high_off.get();
|
||||
|
||||
_esc_undercurrent_hysteresis[i].set_hysteresis_time_from(false, _param_motfail_tout.get() * 1_ms);
|
||||
_esc_overcurrent_hysteresis[i].set_hysteresis_time_from(false, _param_motfail_tout.get() * 1_ms);
|
||||
_esc_undercurrent_hysteresis[i].set_hysteresis_time_from(false, _param_motfail_time.get() * 1_ms);
|
||||
_esc_overcurrent_hysteresis[i].set_hysteresis_time_from(false, _param_motfail_time.get() * 1_ms);
|
||||
|
||||
if (!_esc_undercurrent_hysteresis[i].get_state()) {
|
||||
// Do not clear mid operation because a reaction could be to stop the motor and that would be conidered healthy again
|
||||
|
||||
@ -50,10 +50,7 @@ public:
|
||||
|
||||
void checkAndReport(const Context &context, Report &reporter) override;
|
||||
|
||||
uint16_t getMotorFailureMask() const
|
||||
{
|
||||
return _motor_failure_mask;
|
||||
}
|
||||
uint16_t getMotorFailureMask() const { return _motor_failure_mask; }
|
||||
bool getEscArmStatus() const { return _esc_arm_hysteresis.get_state(); }
|
||||
|
||||
private:
|
||||
@ -63,7 +60,6 @@ private:
|
||||
void updateEscsStatus(const Context &context, Report &reporter, const esc_status_s &esc_status);
|
||||
|
||||
uORB::Subscription _esc_status_sub{ORB_ID(esc_status)};
|
||||
uORB::Subscription _failure_detector_status_sub{ORB_ID(failure_detector_status)};
|
||||
uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)};
|
||||
|
||||
const hrt_abstime _start_time{hrt_absolute_time()};
|
||||
@ -80,7 +76,7 @@ private:
|
||||
(ParamBool<px4::params::FD_ACT_EN>) _param_fd_act_en,
|
||||
(ParamFloat<px4::params::MOTFAIL_THR>) _param_motfail_thr,
|
||||
(ParamFloat<px4::params::MOTFAIL_C2T>) _param_motfail_c2t,
|
||||
(ParamInt<px4::params::MOTFAIL_TOUT>) _param_motfail_tout,
|
||||
(ParamInt<px4::params::MOTFAIL_TIME>) _param_motfail_time,
|
||||
(ParamFloat<px4::params::MOTFAIL_LOW_OFF>) _param_motfail_low_off,
|
||||
(ParamFloat<px4::params::MOTFAIL_HIGH_OFF>) _param_motfail_high_off);
|
||||
};
|
||||
|
||||
@ -39,9 +39,6 @@
|
||||
* @author Mathieu Bresciani <brescianimathieu@gmail.com>
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <parameters/param.h>
|
||||
|
||||
/**
|
||||
* FailureDetector Max Roll
|
||||
*
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user