Skip to content

Commit

Permalink
Plane: slew limit tilted motor throttles
Browse files Browse the repository at this point in the history
this reduces the sudden change in throttle on fwd transition
completion and allows for THR_SLEWRATE to work on tilt quadplanes
  • Loading branch information
tridge committed Jan 3, 2025
1 parent 3e2c07e commit ed37cd3
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 3 deletions.
1 change: 1 addition & 0 deletions ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,7 @@ void Plane::throttle_slew_limit()
if (g.takeoff_throttle_slewrate != 0 && quadplane.in_frwd_transition()) {
slewrate = g.takeoff_throttle_slewrate;
}
SRV_Channels::set_slew_rate(SRV_Channel::k_throttle_tilt, quadplane.tiltrotor.fully_fwd()?slewrate:0, 100, G_Dt);
#endif
SRV_Channels::set_slew_rate(SRV_Channel::k_throttle, slewrate, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleLeft, slewrate, 100, G_Dt);
Expand Down
14 changes: 11 additions & 3 deletions ArduPlane/tiltrotor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -150,6 +150,8 @@ void Tiltrotor::setup()
}
quadplane.transition = transition;

SRV_Channels::set_range(SRV_Channel::k_throttle_tilt, 100); // match k_throttle

setup_complete = true;
}

Expand Down Expand Up @@ -229,7 +231,9 @@ void Tiltrotor::continuous_update(void)

max_change = tilt_max_change(false);

float new_throttle = constrain_float(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)*0.01, 0, 1);
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle_tilt, SRV_Channels::get_output_scaled(SRV_Channel::k_throttle));
float new_throttle = constrain_float(SRV_Channels::get_slew_limited_output_scaled(SRV_Channel::k_throttle_tilt)*0.01, 0, 1);

if (current_tilt < get_fully_forward_tilt()) {
current_throttle = constrain_float(new_throttle,
current_throttle-max_change,
Expand All @@ -245,7 +249,7 @@ void Tiltrotor::continuous_update(void)
}
if (!quadplane.motor_test.running) {
// the motors are all the way forward, start using them for fwd thrust
const uint16_t mask = is_zero(current_throttle)?0U:tilt_mask.get();
const uint16_t mask = tilt_mask.get();
motors->output_motor_mask(current_throttle, mask, plane.rudder_dt);
}
return;
Expand Down Expand Up @@ -363,7 +367,8 @@ void Tiltrotor::binary_update(void)
// all the way forward and run them as a forward motor
binary_slew(true);

float new_throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)*0.01f;
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle_tilt, SRV_Channels::get_output_scaled(SRV_Channel::k_throttle));
float new_throttle = constrain_float(SRV_Channels::get_slew_limited_output_scaled(SRV_Channel::k_throttle_tilt)*0.01, 0, 1);
if (current_tilt >= 1) {
const uint16_t mask = is_zero(new_throttle)?0U:tilt_mask.get();
// the motors are all the way forward, start using them for fwd thrust
Expand Down Expand Up @@ -489,6 +494,9 @@ void Tiltrotor::tilt_compensate_angle(float *thrust, uint8_t num_motors, float n
thrust[i] *= scale;
}
}
if (!fully_fwd()) {
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle_tilt, largest_tilted*100);
}
}

/*
Expand Down

0 comments on commit ed37cd3

Please sign in to comment.