Skip to content

Commit 5c7ee40

Browse files
rubenp02magicrub
authored andcommitted
Plane: add rngfnd. engagement distance parameter
Introduces the RNGFND_LND_DIST parameter, which defines the horizontal distance to the landing point at which the rangefinder engages when RNGFND_LANDING is enabled. This is useful for landing on platforms or small plateaus, and to avoid interference from uneven terrain or obstacles during the approach. When set to the default value of 0, the rangefinder engages as soon as it is within range, matching existing behavior. Key changes: - Adds RNGFND_LND_DIST parameter to control rangefinder engagement horizontal distance during landing. - Updates rangefinder logic to engage only when within the specified distance. - Requires rangefinder_state.in_use for rangefinder correction to be applied. - Requires both in_use and in_range for rangefinder_active to be true.
1 parent c5f6cfd commit 5c7ee40

File tree

3 files changed

+30
-4
lines changed

3 files changed

+30
-4
lines changed

ArduPlane/Parameters.cpp

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1279,6 +1279,17 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
12791279
// @User: Advanced
12801280
AP_GROUPINFO("GUIDED_TIMEOUT", 40, ParametersG2, guided_timeout, 3.0f),
12811281

1282+
#if AP_RANGEFINDER_ENABLED
1283+
// @Param: RNGFND_LND_DIST
1284+
// @DisplayName: Rangefinder landing engagement distance
1285+
// @Description: The horizontal distance to the landing point at which the rangefinder engages when RNGFND_LANDING is enabled. This is useful for landing on platforms or small plateaus, and to avoid interference from uneven terrain or obstacles on approach. A value of 0 engages the rangefinder as soon as it reports valid readings within its range limits. Very small values are not recommended unless required by the landing scenario, as they can force large slope corrections near the ground, increase auto-abort frequency if LAND_ABORT_DEG is set, and provide no slope-correction benefit if the rangefinder is engaged after flare.
1286+
// @Range: 0 500
1287+
// @Units: m
1288+
// @Increment: 1
1289+
// @User: Standard
1290+
AP_GROUPINFO("RNGFND_LND_DIST", 41, ParametersG2, rangefinder_land_engage_dist_m, 0),
1291+
#endif
1292+
12821293
AP_GROUPEND
12831294
};
12841295

ArduPlane/Parameters.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -590,6 +590,9 @@ class ParametersG2 {
590590
#if AP_RANGEFINDER_ENABLED
591591
// orientation of rangefinder to use for landing
592592
AP_Int8 rangefinder_land_orient;
593+
594+
// distance to the landing point to engage the rangefinder for landing
595+
AP_Int16 rangefinder_land_engage_dist_m;
593596
#endif
594597

595598
#if AP_PLANE_SYSTEMID_ENABLED

ArduPlane/altitude.cpp

Lines changed: 16 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -686,8 +686,10 @@ float Plane::rangefinder_correction(void)
686686
return 0;
687687
}
688688

689-
// for now we only support the rangefinder for landing
690-
bool using_rangefinder = (rangefinder_use(RangeFinderUse::TAKEOFF_LANDING) && flight_stage == AP_FixedWing::FlightStage::LAND);
689+
// for now we only support the rangefinder for landing
690+
bool using_rangefinder = (rangefinder_use(RangeFinderUse::TAKEOFF_LANDING) &&
691+
flight_stage == AP_FixedWing::FlightStage::LAND &&
692+
rangefinder_state.in_use);
691693
if (!using_rangefinder) {
692694
return 0;
693695
}
@@ -783,9 +785,18 @@ void Plane::rangefinder_height_update(void)
783785
flightstage_good_for_rangefinder_landing = true;
784786
}
785787
#endif
788+
789+
// Check if the aircraft is within RNGFND_LND_DIST meters from the
790+
// landing point to engage it
791+
const int16_t land_engage_dist_m = g2.rangefinder_land_engage_dist_m;
792+
const bool is_within_engagement_distance =
793+
(land_engage_dist_m <= 0) ||
794+
(auto_state.wp_distance <= land_engage_dist_m);
795+
786796
if (!rangefinder_state.in_use &&
787797
flightstage_good_for_rangefinder_landing &&
788-
rangefinder_use(RangeFinderUse::TAKEOFF_LANDING)) {
798+
rangefinder_use(RangeFinderUse::TAKEOFF_LANDING) &&
799+
is_within_engagement_distance) {
789800
rangefinder_state.in_use = true;
790801
gcs().send_text(MAV_SEVERITY_INFO, "Rangefinder engaged at %.2fm", (double)rangefinder_state.height_estimate);
791802
}
@@ -951,7 +962,8 @@ float Plane::get_landing_height(bool &rangefinder_active)
951962
#if AP_RANGEFINDER_ENABLED
952963
// possibly correct with rangefinder
953964
height -= rangefinder_correction();
954-
rangefinder_active = rangefinder_use(RangeFinderUse::TAKEOFF_LANDING) && rangefinder_state.in_range;
965+
rangefinder_active = rangefinder_use(RangeFinderUse::TAKEOFF_LANDING) &&
966+
rangefinder_state.in_use && rangefinder_state.in_range;
955967
#endif
956968

957969
return height;

0 commit comments

Comments
 (0)