Skip to content

Commit

Permalink
Plane:force min transition timer to 2 sec
Browse files Browse the repository at this point in the history
  • Loading branch information
Hwurzburg committed Oct 16, 2023
1 parent c980e04 commit 76fea66
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @DisplayName: Transition time
// @Description: Transition time in milliseconds after minimum airspeed is reached
// @Units: ms
// @Range: 1 30000
// @Range: 2000 30000
// @User: Advanced
AP_GROUPINFO("TRANSITION_MS", 11, QuadPlane, transition_time_ms, 5000),

Expand Down Expand Up @@ -1151,7 +1151,7 @@ float QuadPlane::get_pilot_land_throttle(void) const
// get scaled throttle input
float throttle_in = plane.channel_throttle->get_control_in();

// normalize to [0,1]
// normalize to [0,1]transition_time
throttle_in /= plane.channel_throttle->get_range();

return constrain_float(throttle_in, 0, 1);
Expand Down Expand Up @@ -1699,14 +1699,14 @@ void SLT_Transition::update()
// after airspeed is reached we degrade throttle over the
// transition time, but continue to stabilize
const uint32_t transition_timer_ms = now - transition_low_airspeed_ms;
if (transition_timer_ms > (unsigned)quadplane.transition_time_ms) {
if (transition_timer_ms > trans_time_ms) {
transition_state = TRANSITION_DONE;
in_forced_transition = false;
transition_start_ms = 0;
transition_low_airspeed_ms = 0;
gcs().send_text(MAV_SEVERITY_INFO, "Transition done");
}
float trans_time_ms = MAX((float)quadplane.transition_time_ms.get(),1);

float transition_scale = (trans_time_ms - transition_timer_ms) / trans_time_ms;
float throttle_scaled = last_throttle * transition_scale;

Expand Down

0 comments on commit 76fea66

Please sign in to comment.