Skip to content

Commit

Permalink
Plane: pass throttle slew rate into output motor mask for tiltrotors …
Browse files Browse the repository at this point in the history
…and tailsitters
  • Loading branch information
IamPete1 committed Jan 5, 2025
1 parent 50c45cf commit 76008fb
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 11 deletions.
1 change: 1 addition & 0 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -1180,6 +1180,7 @@ class Plane : public AP_Vehicle {
void servos_twin_engine_mix();
void force_flare();
void throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle);
float get_throttle_slewrate() const;
void throttle_slew_limit();
bool suppress_throttle(void);
void update_throttle_hover();
Expand Down
20 changes: 12 additions & 8 deletions ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,10 @@
#include "Plane.h"
#include <utility>

/*****************************************
* Throttle slew limit
*****************************************/
void Plane::throttle_slew_limit()
// Get slew rate for throttle as a percentage per second.
// 100% would allow the throttle to move from 0 to 100 in 1 second.
// 0 is disabled
float Plane::get_throttle_slewrate() const
{
#if HAL_QUADPLANE_ENABLED
const bool do_throttle_slew = (control_mode->does_auto_throttle() || quadplane.in_assisted_flight() || quadplane.in_vtol_mode());
Expand All @@ -32,10 +32,7 @@ void Plane::throttle_slew_limit()

if (!do_throttle_slew) {
// only do throttle slew limiting in modes where throttle control is automatic
SRV_Channels::set_slew_rate(SRV_Channel::k_throttle, 0.0, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleLeft, 0.0, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleRight, 0.0, 100, G_Dt);
return;
return 0.0;
}

uint8_t slewrate = aparm.throttle_slewrate;
Expand All @@ -57,6 +54,13 @@ void Plane::throttle_slew_limit()
slewrate = g.takeoff_throttle_slewrate;
}
#endif
return slewrate;
}

// Apply throttle slew limit
void Plane::throttle_slew_limit()
{
const float slewrate = get_throttle_slewrate();
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);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleRight, slewrate, 100, G_Dt);
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/tailsitter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -336,7 +336,7 @@ void Tailsitter::output(void)

if (!quadplane.assisted_flight) {
// set AP_MotorsMatrix throttles for forward flight
motors->output_motor_mask(throttle, motor_mask, plane.rudder_dt);
motors->output_motor_mask(throttle, motor_mask, plane.rudder_dt, plane.get_throttle_slewrate());

// No tilt output unless forward gain is set
float tilt_left = 0.0;
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/tiltrotor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -246,7 +246,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();
motors->output_motor_mask(current_throttle, mask, plane.rudder_dt);
motors->output_motor_mask(current_throttle, mask, plane.rudder_dt, plane.get_throttle_slewrate());
}
return;
}
Expand Down Expand Up @@ -367,7 +367,7 @@ void Tiltrotor::binary_update(void)
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
motors->output_motor_mask(new_throttle, mask, plane.rudder_dt);
motors->output_motor_mask(new_throttle, mask, plane.rudder_dt, plane.get_throttle_slewrate());
}
} else {
binary_slew(false);
Expand Down

0 comments on commit 76008fb

Please sign in to comment.