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

ArduPlane: initialize the accz integrator at takeoff #25718

Conversation

magate
Copy link
Contributor

@magate magate commented Dec 6, 2023

Currently the integrator gets set to the lowest value at takeoff since throttle demand is near zero and hover throttle could be saved in the Q_M_THST_HOVER parameter. This allows the user to specify a desired initialization percentage/100.

For small vehicles this is unlikely to be needed. For larger (heavier) quadplanes this should prevent prolonged time on the ground at a low power setting where the vehicle could be light on the landing gear and skip across the ground.

Testing

Baseline

baseline.BIN.txt
image
Figure:

  1. Integrator initializes at large negative value.
  2. Vehicle lifts off ~1.5 seconds later

Feature Disabled

disabled.BIN.txt
image
Figure: Similar results to baseline.

  1. Integrator initializes at large negative value.
  2. Vehicle lifts off ~1.5 seconds later

Feature Enabled at zero

enabled.BIN.txt
image
Figure:

  1. Integrator initializes at zero.
  2. Vehicle lifts off ~1 second later

Currently the integrator gets set to the lowest value at takeoff since
throttle demand is near zero and hover throttle could be saved in the
Q_M_THST_HOVER parameter. This allows the user to specify a desired
initialization percentage/100.

For small vehicles this is unlikely to be needed. For larger (heavier)
quadplanes this should prevent prolonged time on the ground at a low
power setting where the vehicle could be light on the landing gear and
skip across the ground.
@magate magate force-pushed the feature/quadplane-vtol-takeoff-faster-ground-liftoff branch 2 times, most recently from 6469173 to e27571d Compare December 6, 2023 21:10
@IamPete1
Copy link
Member

IamPete1 commented Dec 7, 2023

My preference would be to copy copter rather than re-inventing the wheel. It has better takeoff handling that we do on plane.

I think this is the key bit we need:

// aircraft stays in landed state until vertical movement is detected or 90% throttle is reached
if (copter.ap.land_complete) {
// send throttle to attitude controller with angle boost
float throttle = constrain_float(copter.attitude_control->get_throttle_in() + copter.G_Dt / copter.g2.takeoff_throttle_slew_time, 0.0, 1.0);
copter.attitude_control->set_throttle_out(throttle, true, 0.0);
// tell position controller to reset alt target and reset I terms
copter.pos_control->init_z_controller();
pos_control->relax_velocity_controller_xy();
pos_control->update_xy_controller();
attitude_control->reset_rate_controller_I_terms();
attitude_control->input_thrust_vector_rate_heading(pos_control->get_thrust_vector(), 0.0);
if (throttle >= MIN(copter.g2.takeoff_throttle_max, 0.9) ||
(copter.pos_control->get_z_accel_cmss() >= 0.5 * copter.pos_control->get_max_accel_z_cmss()) ||
(copter.pos_control->get_vel_desired_cms().z >= 0.1 * copter.pos_control->get_max_speed_up_cms()) ||
( no_nav_active && (inertial_nav.get_position_z_up_cm() >= no_nav_alt_cm))) {
// throttle > 90%
// acceleration > 50% maximum acceleration
// velocity > 10% maximum velocity
// altitude change greater than half auto_takeoff_no_nav_alt_cm
copter.set_land_complete(false);
}
return;
}

@magate
Copy link
Contributor Author

magate commented Dec 7, 2023

My preference would be to copy copter rather than re-inventing the wheel. It has better takeoff handling that we do on plane.

I think this is the key bit we need:

// aircraft stays in landed state until vertical movement is detected or 90% throttle is reached
if (copter.ap.land_complete) {
// send throttle to attitude controller with angle boost
float throttle = constrain_float(copter.attitude_control->get_throttle_in() + copter.G_Dt / copter.g2.takeoff_throttle_slew_time, 0.0, 1.0);
copter.attitude_control->set_throttle_out(throttle, true, 0.0);
// tell position controller to reset alt target and reset I terms
copter.pos_control->init_z_controller();
pos_control->relax_velocity_controller_xy();
pos_control->update_xy_controller();
attitude_control->reset_rate_controller_I_terms();
attitude_control->input_thrust_vector_rate_heading(pos_control->get_thrust_vector(), 0.0);
if (throttle >= MIN(copter.g2.takeoff_throttle_max, 0.9) ||
(copter.pos_control->get_z_accel_cmss() >= 0.5 * copter.pos_control->get_max_accel_z_cmss()) ||
(copter.pos_control->get_vel_desired_cms().z >= 0.1 * copter.pos_control->get_max_speed_up_cms()) ||
( no_nav_active && (inertial_nav.get_position_z_up_cm() >= no_nav_alt_cm))) {
// throttle > 90%
// acceleration > 50% maximum acceleration
// velocity > 10% maximum velocity
// altitude change greater than half auto_takeoff_no_nav_alt_cm
copter.set_land_complete(false);
}
return;
}

Perfect, thanks. Will close this and open a new PR.

@magate magate closed this Dec 7, 2023
@magate magate deleted the feature/quadplane-vtol-takeoff-faster-ground-liftoff branch December 7, 2023 20:08
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants