mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
APM: added XTRK_MIN_DIST option
this allows you to disable crosstrack correction on short legs
This commit is contained in:
parent
a446a7a9ed
commit
96ea350143
@ -73,6 +73,7 @@ public:
|
|||||||
k_param_reset_mission_chan,
|
k_param_reset_mission_chan,
|
||||||
k_param_land_flare_alt,
|
k_param_land_flare_alt,
|
||||||
k_param_land_flare_sec,
|
k_param_land_flare_sec,
|
||||||
|
k_param_crosstrack_min_distance,
|
||||||
|
|
||||||
// 110: Telemetry control
|
// 110: Telemetry control
|
||||||
//
|
//
|
||||||
@ -237,6 +238,7 @@ public:
|
|||||||
AP_Float crosstrack_gain;
|
AP_Float crosstrack_gain;
|
||||||
AP_Int16 crosstrack_entry_angle;
|
AP_Int16 crosstrack_entry_angle;
|
||||||
AP_Int8 crosstrack_use_wind;
|
AP_Int8 crosstrack_use_wind;
|
||||||
|
AP_Int16 crosstrack_min_distance;
|
||||||
|
|
||||||
// Estimation
|
// Estimation
|
||||||
//
|
//
|
||||||
|
@ -126,7 +126,16 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Description: If enabled, use wind estimation for navigation crosstrack when using a compass for yaw
|
// @Description: If enabled, use wind estimation for navigation crosstrack when using a compass for yaw
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(crosstrack_use_wind, "XTRK_USE_WIND", 1),
|
GSCALAR(crosstrack_use_wind, "XTRK_USE_WIND", 1),
|
||||||
|
|
||||||
|
// @Param: XTRK_MIN_DIST
|
||||||
|
// @DisplayName: Crosstrack mininum distance
|
||||||
|
// @Description: Minimum distance in meters between waypoints to do crosstrack correction.
|
||||||
|
// @Units: Meters
|
||||||
|
// @Range: 0 32767
|
||||||
|
// @Increment: 1
|
||||||
|
// @User: Standard
|
||||||
|
GSCALAR(crosstrack_min_distance, "XTRK_MIN_DIST", 50),
|
||||||
|
|
||||||
// @Param: ALT_MIX
|
// @Param: ALT_MIX
|
||||||
// @DisplayName: Gps to Baro Mix
|
// @DisplayName: Gps to Baro Mix
|
||||||
|
@ -189,7 +189,8 @@ static void update_crosstrack(void)
|
|||||||
// Crosstrack Error
|
// Crosstrack Error
|
||||||
// ----------------
|
// ----------------
|
||||||
// If we are too far off or too close we don't do track following
|
// If we are too far off or too close we don't do track following
|
||||||
if (abs(wrap_180_cd(target_bearing_cd - crosstrack_bearing_cd)) < 4500) {
|
if (wp_totalDistance >= g.crosstrack_min_distance &&
|
||||||
|
abs(wrap_180_cd(target_bearing_cd - crosstrack_bearing_cd)) < 4500) {
|
||||||
// Meters we are off track line
|
// Meters we are off track line
|
||||||
crosstrack_error = sin(radians((target_bearing_cd - crosstrack_bearing_cd) * 0.01)) * wp_distance;
|
crosstrack_error = sin(radians((target_bearing_cd - crosstrack_bearing_cd) * 0.01)) * wp_distance;
|
||||||
nav_bearing_cd += constrain(crosstrack_error * g.crosstrack_gain, -g.crosstrack_entry_angle.get(), g.crosstrack_entry_angle.get());
|
nav_bearing_cd += constrain(crosstrack_error * g.crosstrack_gain, -g.crosstrack_entry_angle.get(), g.crosstrack_entry_angle.get());
|
||||||
|
Loading…
Reference in New Issue
Block a user