34 for (uint8_t i=0; i<6; i++) {
125 float throttle_thrust;
126 float throttle_avg_max;
127 float thrust_min_rpy;
129 float rp_scale = 1.0f;
130 float actuator_allowed = 0.0f;
132 float actuator_max = 0.0f;
136 roll_thrust =
_roll_in * compensation_gain;
137 pitch_thrust =
_pitch_in * compensation_gain;
138 yaw_thrust =
_yaw_in * compensation_gain;
143 if (throttle_thrust <= 0.0
f) {
144 throttle_thrust = 0.0f;
154 float rp_thrust_max =
MAX(fabsf(roll_thrust), fabsf(pitch_thrust));
161 if (rp_scale < 1.0
f) {
166 actuator_allowed = 1.0f - rp_scale * rp_thrust_max;
167 if (fabsf(yaw_thrust) > actuator_allowed) {
168 yaw_thrust =
constrain_float(yaw_thrust, -actuator_allowed, actuator_allowed);
175 actuator[0] = rp_scale * roll_thrust - yaw_thrust;
177 actuator[1] = rp_scale * pitch_thrust - yaw_thrust;
179 actuator[2] = -rp_scale * roll_thrust - yaw_thrust;
181 actuator[3] = -rp_scale * pitch_thrust - yaw_thrust;
184 thrust_min_rpy =
MAX(
MAX(fabsf(actuator[0]), fabsf(actuator[1])),
MAX(fabsf(actuator[2]), fabsf(actuator[3])));
186 thr_adj = throttle_thrust - throttle_avg_max;
187 if (thr_adj < (thrust_min_rpy - throttle_avg_max)) {
190 thr_adj =
MIN(thrust_min_rpy, throttle_avg_max) - throttle_avg_max;
206 if (actuator_max > fabsf(actuator[i])) {
207 actuator_max = fabsf(actuator[i]);
210 if (actuator_max > thrust_out_actuator && !
is_zero(actuator_max)) {
215 rp_scale = thrust_out_actuator/actuator_max;
static void set_angle(SRV_Channel::Aux_servo_function_t function, uint16_t angle)
int16_t get_pwm_output_min() const
static SRV_Channel::Aux_servo_function_t get_motor_function(uint8_t channel)
virtual void rc_write_angle(uint8_t chan, int16_t angle_cd)
Interface definition for the various Ground Control System.
struct AP_Motors::AP_Motors_flags _flags
struct AP_Motors::AP_Motors_limit limit
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]
bool is_zero(const T fVal1)
float _throttle_thrust_max
virtual void rc_write(uint8_t chan, uint16_t pwm)
float _pitch_radio_passthrough
float constrain_float(const float amt, const float low, const float high)
void add_motor_num(int8_t motor_num)
virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz)
float _roll_radio_passthrough
spool_up_down_mode _spool_mode
int16_t calc_spin_up_to_pwm() const
float get_compensation_gain() const
int16_t calc_thrust_to_pwm(float thrust_in) const
float get_throttle() const
virtual uint32_t rc_map_mask(uint32_t mask) const