Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Accel limit for big copters while precison-land #26885

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
9 changes: 9 additions & 0 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
rahulOCR marked this conversation as resolved.
Show resolved Hide resolved

// @Param: LAND_SPEED
// @DisplayName: Land speed
// @Description: The descent speed for the final stage of landing in cm/s
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -381,13 +381,13 @@ class Parameters {
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;
Expand Down
11 changes: 9 additions & 2 deletions ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
const float adjusted_acceleration = (float)copter.g.land_accel_limit;
const float adjusted_acceleration = copter.g.land_accel_limit.get();


if (adjusted_acceleration > 0.0f){
Copy link
Contributor

@lthall lthall Apr 27, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would suggest using is_positive()

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
if (adjusted_acceleration > 0.0f){
if (is_positive(adjusted_acceleration)) {

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()) {
Expand Down
11 changes: 9 additions & 2 deletions ArduCopter/mode_land.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
const float adjusted_acceleration = (float)copter.g.land_accel_limit;
const float adjusted_acceleration = copter.g.land_accel_limit.get();


if (adjusted_acceleration > 0.0f){
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
if (adjusted_acceleration > 0.0f){
if (is_positive(adjusted_acceleration)) {

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()) {
Expand Down