mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_RangeFinder: remove rangefinder prearm requirements for SITL
Getting the virtual rangefinder to move in prearm would be better, much much more involved.
This commit is contained in:
parent
281fad53c2
commit
3be9f35264
@ -24,7 +24,11 @@
|
||||
#define RANGEFINDER_MAX_INSTANCES 2
|
||||
#define RANGEFINDER_GROUND_CLEARANCE_CM_DEFAULT 10
|
||||
#define RANGEFINDER_PREARM_ALT_MAX_CM 200
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#define RANGEFINDER_PREARM_REQUIRED_CHANGE_CM 0
|
||||
#else
|
||||
#define RANGEFINDER_PREARM_REQUIRED_CHANGE_CM 50
|
||||
#endif
|
||||
|
||||
class AP_RangeFinder_Backend;
|
||||
|
||||
|
@ -97,7 +97,7 @@ void AP_RangeFinder_Backend::update_pre_arm_check()
|
||||
state.pre_arm_distance_max = MAX(state.distance_cm, state.pre_arm_distance_max);
|
||||
|
||||
// Check that the range finder has been exercised through a realistic range of movement
|
||||
if (((state.pre_arm_distance_max - state.pre_arm_distance_min) > RANGEFINDER_PREARM_REQUIRED_CHANGE_CM) &&
|
||||
if (((state.pre_arm_distance_max - state.pre_arm_distance_min) >= RANGEFINDER_PREARM_REQUIRED_CHANGE_CM) &&
|
||||
(state.pre_arm_distance_max < RANGEFINDER_PREARM_ALT_MAX_CM) &&
|
||||
((int16_t)state.pre_arm_distance_min < (MAX(state.ground_clearance_cm,state.min_distance_cm) + 10)) &&
|
||||
((int16_t)state.pre_arm_distance_min > (MIN(state.ground_clearance_cm,state.min_distance_cm) - 10))) {
|
||||
|
Loading…
Reference in New Issue
Block a user