mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
Copter: auto climb and descent params removed
These params now reside in the AC_WPNav library
This commit is contained in:
parent
764853bd56
commit
f5955d8915
@ -1895,7 +1895,7 @@ void update_throttle_mode(void)
|
|||||||
case THROTTLE_AUTO:
|
case THROTTLE_AUTO:
|
||||||
// auto pilot altitude controller with target altitude held in wp_nav.get_desired_alt()
|
// auto pilot altitude controller with target altitude held in wp_nav.get_desired_alt()
|
||||||
if(ap.auto_armed) {
|
if(ap.auto_armed) {
|
||||||
get_throttle_althold_with_slew(wp_nav.get_desired_alt(), g.auto_velocity_z_min, g.auto_velocity_z_max);
|
get_throttle_althold_with_slew(wp_nav.get_desired_alt(), -wp_nav.get_descent_velocity(), wp_nav.get_climb_velocity());
|
||||||
set_target_alt_for_reporting(wp_nav.get_desired_alt()); // To-Do: return get_destination_alt if we are flying to a waypoint
|
set_target_alt_for_reporting(wp_nav.get_desired_alt()); // To-Do: return get_destination_alt if we are flying to a waypoint
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -1171,7 +1171,7 @@ get_throttle_land()
|
|||||||
{
|
{
|
||||||
// if we are above 10m and the sonar does not sense anything perform regular alt hold descent
|
// if we are above 10m and the sonar does not sense anything perform regular alt hold descent
|
||||||
if (current_loc.alt >= LAND_START_ALT && !(g.sonar_enabled && sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
if (current_loc.alt >= LAND_START_ALT && !(g.sonar_enabled && sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
||||||
get_throttle_althold_with_slew(LAND_START_ALT, g.auto_velocity_z_min, -abs(g.land_speed));
|
get_throttle_althold_with_slew(LAND_START_ALT, -wp_nav.get_descent_velocity(), -abs(g.land_speed));
|
||||||
}else{
|
}else{
|
||||||
get_throttle_rate_stabilized(-abs(g.land_speed));
|
get_throttle_rate_stabilized(-abs(g.land_speed));
|
||||||
|
|
||||||
|
@ -215,8 +215,8 @@ public:
|
|||||||
k_param_circle_radius,
|
k_param_circle_radius,
|
||||||
k_param_waypoint_speed_max, // remove
|
k_param_waypoint_speed_max, // remove
|
||||||
k_param_land_speed,
|
k_param_land_speed,
|
||||||
k_param_auto_velocity_z_min,
|
k_param_auto_velocity_z_min, // remove
|
||||||
k_param_auto_velocity_z_max, // 219
|
k_param_auto_velocity_z_max, // remove - 219
|
||||||
|
|
||||||
//
|
//
|
||||||
// 220: PI/D Controllers
|
// 220: PI/D Controllers
|
||||||
@ -291,8 +291,6 @@ public:
|
|||||||
AP_Int16 circle_radius;
|
AP_Int16 circle_radius;
|
||||||
AP_Int32 rtl_loiter_time;
|
AP_Int32 rtl_loiter_time;
|
||||||
AP_Int16 land_speed;
|
AP_Int16 land_speed;
|
||||||
AP_Int16 auto_velocity_z_min; // minimum vertical velocity (i.e. maximum descent) the autopilot may request
|
|
||||||
AP_Int16 auto_velocity_z_max; // maximum vertical velocity the autopilot may request
|
|
||||||
AP_Int16 pilot_velocity_z_max; // maximum vertical velocity the pilot may request
|
AP_Int16 pilot_velocity_z_max; // maximum vertical velocity the pilot may request
|
||||||
|
|
||||||
|
|
||||||
|
@ -228,24 +228,6 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(land_speed, "LAND_SPEED", LAND_SPEED),
|
GSCALAR(land_speed, "LAND_SPEED", LAND_SPEED),
|
||||||
|
|
||||||
// @Param: AUTO_VELZ_MIN
|
|
||||||
// @DisplayName: Autopilot's min vertical speed (max descent) in cm/s
|
|
||||||
// @Description: The minimum vertical velocity (i.e. descent speed) the autopilot may request in cm/s
|
|
||||||
// @Units: Centimeters/Second
|
|
||||||
// @Range: -500 -50
|
|
||||||
// @Increment: 10
|
|
||||||
// @User: Standard
|
|
||||||
GSCALAR(auto_velocity_z_min, "AUTO_VELZ_MIN", AUTO_VELZ_MIN),
|
|
||||||
|
|
||||||
// @Param: AUTO_VELZ_MAX
|
|
||||||
// @DisplayName: Auto pilot's max vertical speed in cm/s
|
|
||||||
// @Description: The maximum vertical velocity the autopilot may request in cm/s
|
|
||||||
// @Units: Centimeters/Second
|
|
||||||
// @Range: 50 500
|
|
||||||
// @Increment: 10
|
|
||||||
// @User: Standard
|
|
||||||
GSCALAR(auto_velocity_z_max, "AUTO_VELZ_MAX", AUTO_VELZ_MAX),
|
|
||||||
|
|
||||||
// @Param: PILOT_VELZ_MAX
|
// @Param: PILOT_VELZ_MAX
|
||||||
// @DisplayName: Pilot maximum vertical speed
|
// @DisplayName: Pilot maximum vertical speed
|
||||||
// @Description: The maximum vertical velocity the pilot may request in cm/s
|
// @Description: The maximum vertical velocity the pilot may request in cm/s
|
||||||
|
Loading…
Reference in New Issue
Block a user