mirror of https://github.com/ArduPilot/ardupilot
Sub: Remove LAND parameters
This commit is contained in:
parent
19afd7a3dd
commit
69d89c5871
|
@ -266,24 +266,6 @@ const AP_Param::Info Sub::var_info[] = {
|
|||
// @User: Standard
|
||||
GSCALAR(rtl_loiter_time, "RTL_LOIT_TIME", RTL_LOITER_TIME),
|
||||
|
||||
// @Param: LAND_SPEED
|
||||
// @DisplayName: Land speed
|
||||
// @Description: The descent speed for the final stage of landing in cm/s
|
||||
// @Units: cm/s
|
||||
// @Range: 30 200
|
||||
// @Increment: 10
|
||||
// @User: Standard
|
||||
GSCALAR(land_speed, "LAND_SPEED", LAND_SPEED),
|
||||
|
||||
// @Param: LAND_SPEED_HIGH
|
||||
// @DisplayName: Land speed high
|
||||
// @Description: The descent speed for the first stage of landing in cm/s. If this is zero then WPNAV_SPEED_DN is used
|
||||
// @Units: cm/s
|
||||
// @Range: 0 500
|
||||
// @Increment: 10
|
||||
// @User: Standard
|
||||
GSCALAR(land_speed_high, "LAND_SPEED_HIGH", 0),
|
||||
|
||||
// @Param: PILOT_VELZ_MAX
|
||||
// @DisplayName: Pilot maximum vertical speed
|
||||
// @Description: The maximum vertical velocity the pilot may request in cm/s
|
||||
|
@ -482,13 +464,6 @@ const AP_Param::Info Sub::var_info[] = {
|
|||
// @Values: 0:Very Soft, 25:Soft, 50:Medium, 75:Crisp, 100:Very Crisp
|
||||
GSCALAR(rc_feel_rp, "RC_FEEL_RP", RC_FEEL_RP_MEDIUM),
|
||||
|
||||
// @Param: LAND_REPOSITION
|
||||
// @DisplayName: Land repositioning
|
||||
// @Description: Enables user input during LAND mode, the landing phase of RTL, and auto mode landings.
|
||||
// @Values: 0:No repositioning, 1:Repositioning
|
||||
// @User: Advanced
|
||||
GSCALAR(land_repositioning, "LAND_REPOSITION", LAND_REPOSITION_DEFAULT),
|
||||
|
||||
// @Param: FS_EKF_ACTION
|
||||
// @DisplayName: EKF Failsafe Action
|
||||
// @Description: Controls the action that will be taken when an EKF failsafe is invoked
|
||||
|
|
|
@ -95,7 +95,6 @@ public:
|
|||
k_param_rc_14,
|
||||
k_param_rally,
|
||||
k_param_pilot_accel_z,
|
||||
k_param_land_repositioning,
|
||||
k_param_rangefinder, // rangefinder object
|
||||
k_param_fs_ekf_thresh,
|
||||
k_param_terrain,
|
||||
|
@ -210,12 +209,6 @@ public:
|
|||
k_param_flight_mode5,
|
||||
k_param_flight_mode6,
|
||||
|
||||
//
|
||||
// 210: Waypoint data
|
||||
//
|
||||
k_param_land_speed,
|
||||
k_param_land_speed_high,
|
||||
|
||||
//
|
||||
// 220: PI/D Controllers
|
||||
//
|
||||
|
@ -328,8 +321,6 @@ public:
|
|||
// Waypoints
|
||||
//
|
||||
AP_Int32 rtl_loiter_time;
|
||||
AP_Int16 land_speed;
|
||||
AP_Int16 land_speed_high;
|
||||
AP_Int16 pilot_velocity_z_max; // maximum vertical velocity the pilot may request
|
||||
AP_Int16 pilot_accel_z; // vertical acceleration the pilot may request
|
||||
|
||||
|
@ -364,7 +355,6 @@ public:
|
|||
AP_Int8 arming_check;
|
||||
AP_Int8 disarm_delay;
|
||||
|
||||
AP_Int8 land_repositioning;
|
||||
AP_Int8 fs_ekf_action;
|
||||
AP_Int8 fs_crash_check;
|
||||
AP_Float fs_ekf_thresh;
|
||||
|
|
|
@ -49,7 +49,7 @@ void Sub::surface_run()
|
|||
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
|
||||
// set target climb rate
|
||||
float cmb_rate = constrain_float(abs(g.land_speed), 1, pos_control.get_speed_up());
|
||||
float cmb_rate = constrain_float(abs(wp_nav.get_speed_up()), 1, pos_control.get_speed_up());
|
||||
|
||||
// record desired climb rate for logging
|
||||
desired_climb_rate = cmb_rate;
|
||||
|
|
Loading…
Reference in New Issue