mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: remove unused crosstrack variables and parameters
Cross track is still calculated internally to the wpnav controller so we should move this to a library and still report it to the ground station
This commit is contained in:
parent
a1295c042b
commit
61e29173e3
@ -692,8 +692,6 @@ static struct Location guided_WP;
|
||||
// deg * 100, The original angle to the next_WP when the next_WP was set
|
||||
// Also used to check when we pass a WP
|
||||
static int32_t original_wp_bearing;
|
||||
// The amount of angle correction applied to wp_bearing to bring the copter back on its optimum path
|
||||
static int16_t crosstrack_error;
|
||||
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -275,7 +275,7 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
|
||||
wp_distance / 1.0e2f,
|
||||
altitude_error / 1.0e2f,
|
||||
0,
|
||||
crosstrack_error); // was 0
|
||||
0);
|
||||
}
|
||||
|
||||
static void NOINLINE send_ahrs(mavlink_channel_t chan)
|
||||
|
@ -75,7 +75,7 @@ public:
|
||||
// Yaw Rate 1 = fast,
|
||||
// 2 = med, 3 = slow
|
||||
|
||||
k_param_crosstrack_min_distance,
|
||||
k_param_crosstrack_min_distance, // deprecated - remove with next eeprom number change
|
||||
k_param_rssi_pin,
|
||||
k_param_throttle_accel_enabled,
|
||||
k_param_yaw_override_behaviour,
|
||||
@ -145,7 +145,7 @@ public:
|
||||
// 160: Navigation parameters
|
||||
//
|
||||
k_param_rtl_altitude = 160,
|
||||
k_param_crosstrack_gain,
|
||||
k_param_crosstrack_gain, // deprecated - remove with next eeprom number change
|
||||
k_param_rtl_loiter_time,
|
||||
k_param_rtl_alt_final,
|
||||
k_param_tilt_comp, //164
|
||||
@ -291,8 +291,6 @@ public:
|
||||
AP_Int16 waypoint_radius;
|
||||
AP_Int16 circle_radius;
|
||||
AP_Int16 waypoint_speed_max;
|
||||
AP_Float crosstrack_gain;
|
||||
AP_Int16 crosstrack_min_distance;
|
||||
AP_Int32 rtl_loiter_time;
|
||||
AP_Int16 land_speed;
|
||||
AP_Int16 auto_velocity_z_min; // minimum vertical velocity (i.e. maximum descent) the autopilot may request
|
||||
|
@ -235,22 +235,6 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @User: Standard
|
||||
GSCALAR(waypoint_speed_max, "WP_SPEED_MAX", WAYPOINT_SPEED_MAX),
|
||||
|
||||
// @Param: XTRK_GAIN_SC
|
||||
// @DisplayName: Cross-Track Gain
|
||||
// @Description: This controls the rate that the Auto Controller will attempt to return original track
|
||||
// @Units: Dimensionless
|
||||
// @User: Standard
|
||||
GSCALAR(crosstrack_gain, "XTRK_GAIN_SC", CROSSTRACK_GAIN),
|
||||
|
||||
// @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", CROSSTRACK_MIN_DISTANCE),
|
||||
|
||||
// @Param: RTL_LOIT_TIME
|
||||
// @DisplayName: RTL loiter time
|
||||
// @Description: Time (in milliseconds) to loiter above home before begining final descent
|
||||
|
@ -262,9 +262,6 @@ static void verify_altitude()
|
||||
// Keeps old data out of our calculation / logs
|
||||
static void reset_nav_params(void)
|
||||
{
|
||||
// We must be heading to a new WP, so XTrack must be 0
|
||||
crosstrack_error = 0;
|
||||
|
||||
// Will be set by new command
|
||||
wp_bearing = 0;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user