mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
sensors delete disabled ATT_VIBE_THRESH (#8372)
This commit is contained in:
parent
1d1da12859
commit
ed7f333fe8
@ -155,8 +155,6 @@ int initialize_parameter_handles(ParameterHandles ¶meter_handles)
|
||||
/* Barometer QNH */
|
||||
parameter_handles.baro_qnh = param_find("SENS_BARO_QNH");
|
||||
|
||||
parameter_handles.vibe_thresh = param_find("ATT_VIBE_THRESH");
|
||||
|
||||
parameter_handles.air_cmodel = param_find("CAL_AIR_CMODEL");
|
||||
parameter_handles.air_tube_length = param_find("CAL_AIR_TUBELEN");
|
||||
parameter_handles.air_tube_diameter_mm = param_find("CAL_AIR_TUBED_MM");
|
||||
@ -490,8 +488,6 @@ int update_parameters(const ParameterHandles ¶meter_handles, Parameters &par
|
||||
|
||||
param_get(parameter_handles.baro_qnh, &(parameters.baro_qnh));
|
||||
|
||||
param_get(parameter_handles.vibe_thresh, ¶meters.vibration_warning_threshold);
|
||||
|
||||
param_get(parameter_handles.air_cmodel, ¶meters.air_cmodel);
|
||||
param_get(parameter_handles.air_tube_length, ¶meters.air_tube_length);
|
||||
param_get(parameter_handles.air_tube_diameter_mm, ¶meters.air_tube_diameter_mm);
|
||||
|
||||
@ -144,8 +144,6 @@ struct Parameters {
|
||||
|
||||
float baro_qnh;
|
||||
|
||||
float vibration_warning_threshold;
|
||||
|
||||
int32_t air_cmodel;
|
||||
float air_tube_length;
|
||||
float air_tube_diameter_mm;
|
||||
@ -228,8 +226,6 @@ struct ParameterHandles {
|
||||
|
||||
param_t baro_qnh;
|
||||
|
||||
param_t vibe_thresh; /**< vibration threshold */
|
||||
|
||||
param_t air_cmodel;
|
||||
param_t air_tube_length;
|
||||
param_t air_tube_diameter_mm;
|
||||
|
||||
@ -208,16 +208,6 @@ PARAM_DEFINE_FLOAT(SENS_BOARD_X_OFF, 0.0f);
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_BOARD_Z_OFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Threshold (of RMS) to warn about high vibration levels
|
||||
*
|
||||
* @group Sensors
|
||||
* @min 0.01
|
||||
* @max 10
|
||||
* @decimal 2
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(ATT_VIBE_THRESH, 0.2f);
|
||||
|
||||
/**
|
||||
* Lidar-Lite (LL40LS)
|
||||
*
|
||||
|
||||
@ -690,8 +690,6 @@ Sensors::run()
|
||||
orb_publish(ORB_ID(sensor_preflight), _sensor_preflight, &preflt);
|
||||
|
||||
}
|
||||
|
||||
//_voted_sensors_update.check_vibration(); //disabled for now, as it does not seem to be reliable
|
||||
}
|
||||
|
||||
/* keep adding sensors as long as we are not armed,
|
||||
|
||||
@ -962,34 +962,6 @@ bool VotedSensorsUpdate::check_failover(SensorData &sensor, const char *sensor_n
|
||||
return false;
|
||||
}
|
||||
|
||||
bool VotedSensorsUpdate::check_vibration()
|
||||
{
|
||||
bool ret = false;
|
||||
hrt_abstime cur_time = hrt_absolute_time();
|
||||
|
||||
if (!_vibration_warning && (_gyro.voter.get_vibration_factor(cur_time) > _parameters.vibration_warning_threshold ||
|
||||
_accel.voter.get_vibration_factor(cur_time) > _parameters.vibration_warning_threshold ||
|
||||
_mag.voter.get_vibration_factor(cur_time) > _parameters.vibration_warning_threshold)) {
|
||||
|
||||
if (_vibration_warning_timestamp == 0) {
|
||||
_vibration_warning_timestamp = cur_time;
|
||||
|
||||
} else if (hrt_elapsed_time(&_vibration_warning_timestamp) > 10000 * 1000) {
|
||||
_vibration_warning = true;
|
||||
mavlink_log_critical(&_mavlink_log_pub, "HIGH VIBRATION! g: %d a: %d m: %d",
|
||||
(int)(100 * _gyro.voter.get_vibration_factor(cur_time)),
|
||||
(int)(100 * _accel.voter.get_vibration_factor(cur_time)),
|
||||
(int)(100 * _mag.voter.get_vibration_factor(cur_time)));
|
||||
ret = true;
|
||||
}
|
||||
|
||||
} else {
|
||||
_vibration_warning_timestamp = 0;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
void VotedSensorsUpdate::init_sensor_class(const struct orb_metadata *meta, SensorData &sensor_data,
|
||||
uint8_t sensor_count_max)
|
||||
{
|
||||
|
||||
@ -122,13 +122,6 @@ public:
|
||||
*/
|
||||
void check_failover();
|
||||
|
||||
/**
|
||||
* check vibration levels and output a warning if they're high
|
||||
* @return true on high vibration
|
||||
*/
|
||||
bool check_vibration();
|
||||
|
||||
|
||||
int num_gyros() const { return _gyro.subscription_count; }
|
||||
int gyro_fd(int idx) const { return _gyro.subscription[idx]; }
|
||||
|
||||
@ -260,9 +253,6 @@ private:
|
||||
uint64_t _last_mag_timestamp[MAG_COUNT_MAX]; /**< latest full timestamp */
|
||||
uint64_t _last_baro_timestamp[BARO_COUNT_MAX]; /**< latest full timestamp */
|
||||
|
||||
hrt_abstime _vibration_warning_timestamp = 0;
|
||||
bool _vibration_warning = false;
|
||||
|
||||
math::Matrix<3, 3> _board_rotation = {}; /**< rotation matrix for the orientation that the board is mounted */
|
||||
math::Matrix<3, 3> _mag_rotation[MAG_COUNT_MAX] = {}; /**< rotation matrix for the orientation that the external mag0 is mounted */
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user