mirror of https://github.com/ArduPilot/ardupilot
copter:acceleration limit in land
This commit is contained in:
parent
bc29550c9b
commit
e479e35333
|
@ -188,6 +188,15 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
// @User: Standard
|
||||
GSCALAR(wp_yaw_behavior, "WP_YAW_BEHAVIOR", WP_YAW_BEHAVIOR_DEFAULT),
|
||||
|
||||
// @Param: LAND_ACCEL
|
||||
// @DisplayName: Land acceleration
|
||||
// @Description: Limits maximum acceleration during landing. WPNAV_ACCEL is used if this parameter is zero
|
||||
// @Units: cm/s/s
|
||||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
GSCALAR(land_accel_limit, "LAND_ACCEL", 0),
|
||||
|
||||
// @Param: LAND_SPEED
|
||||
// @DisplayName: Land speed
|
||||
// @Description: The descent speed for the final stage of landing in cm/s
|
||||
|
|
|
@ -381,13 +381,13 @@ public:
|
|||
k_param_vehicle = 257, // vehicle common block of parameters
|
||||
k_param_throw_altitude_min,
|
||||
k_param_throw_altitude_max,
|
||||
|
||||
k_param_land_accel_limit,
|
||||
// the k_param_* space is 9-bits in size
|
||||
// 511: reserved
|
||||
};
|
||||
|
||||
AP_Int16 format_version;
|
||||
|
||||
AP_Float land_accel_limit;
|
||||
// Telemetry control
|
||||
//
|
||||
AP_Int16 sysid_this_mav;
|
||||
|
|
|
@ -409,8 +409,15 @@ bool ModeAuto::wp_start(const Location& dest_loc)
|
|||
void ModeAuto::land_start()
|
||||
{
|
||||
// set horizontal speed and acceleration limits
|
||||
pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
|
||||
pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
|
||||
const float adjusted_acceleration = (float)copter.g.land_accel_limit;
|
||||
|
||||
if (adjusted_acceleration > 0.0f){
|
||||
pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(),adjusted_acceleration );
|
||||
pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), adjusted_acceleration);
|
||||
} else {
|
||||
pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
|
||||
pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
|
||||
}
|
||||
|
||||
// initialise the vertical position controller
|
||||
if (!pos_control->is_active_xy()) {
|
||||
|
|
|
@ -7,8 +7,15 @@ bool ModeLand::init(bool ignore_checks)
|
|||
control_position = copter.position_ok();
|
||||
|
||||
// set horizontal speed and acceleration limits
|
||||
pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
|
||||
pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
|
||||
const float adjusted_acceleration = (float)copter.g.land_accel_limit;
|
||||
|
||||
if (adjusted_acceleration > 0.0f){
|
||||
pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(),adjusted_acceleration );
|
||||
pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), adjusted_acceleration);
|
||||
} else {
|
||||
pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
|
||||
pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
|
||||
}
|
||||
|
||||
// initialise the horizontal position controller
|
||||
if (control_position && !pos_control->is_active_xy()) {
|
||||
|
|
Loading…
Reference in New Issue