142 float throttle_thrust;
143 float throttle_avg_max;
144 float throttle_thrust_best_rpy;
145 float rpy_scale = 1.0f;
146 float rpy_low = 0.0f;
147 float rpy_high = 0.0f;
148 float yaw_allowed = 1.0f;
154 roll_thrust =
_roll_in * compensation_gain;
155 pitch_thrust =
_pitch_in * compensation_gain;
156 yaw_thrust =
_yaw_in * compensation_gain;
161 if (throttle_thrust <= 0.0
f) {
162 throttle_thrust = 0.0f;
185 throttle_thrust_best_rpy =
MIN(0.5
f, throttle_avg_max);
195 if (yaw_allowed > unused_range) {
196 yaw_allowed = unused_range;
200 if (yaw_allowed > unused_range) {
201 yaw_allowed = unused_range;
211 if (fabsf(yaw_thrust) > yaw_allowed) {
235 throttle_thrust_best_rpy =
MIN(0.5
f - (rpy_low+rpy_high)/2.0, throttle_avg_max);
240 }
else if (
is_zero(rpy_high)) {
243 rpy_scale =
constrain_float(
MIN(-throttle_thrust_best_rpy/rpy_low, (1.0
f-throttle_thrust_best_rpy)/rpy_high), 0.0
f, 1.0
f);
247 thr_adj = throttle_thrust - throttle_thrust_best_rpy;
248 if (rpy_scale < 1.0
f){
252 if (thr_adj > 0.0
f) {
257 if (thr_adj < -(throttle_thrust_best_rpy+rpy_low)){
259 thr_adj = -(throttle_thrust_best_rpy+rpy_low);
260 }
else if (thr_adj > 1.0
f - (throttle_thrust_best_rpy+rpy_high)){
262 thr_adj = 1.0f - (throttle_thrust_best_rpy+rpy_high);
329 add_motor(motor_num, angle_degrees, angle_degrees, yaw_factor, testing_order);
333 void AP_MotorsMatrix::add_motor(int8_t motor_num,
float roll_factor_in_degrees,
float pitch_factor_in_degrees,
float yaw_factor, uint8_t testing_order)
337 cosf(
radians(roll_factor_in_degrees + 90)),
338 cosf(
radians(pitch_factor_in_degrees)),
363 bool success =
false;
365 switch (frame_class) {
368 switch (frame_type) {
447 switch (frame_type) {
473 switch (frame_type) {
525 switch (frame_type) {
578 switch (frame_type) {
616 switch (frame_type) {
663 float roll_fac = 0.0f;
664 float pitch_fac = 0.0f;
665 float yaw_fac = 0.0f;
float _pitch_factor[AP_MOTORS_MAX_NUM_MOTORS]
void remove_motor(int8_t motor_num)
motor_frame_type _last_frame_type
motor_frame_class _last_frame_class
int16_t get_pwm_output_min() const
float _yaw_factor[AP_MOTORS_MAX_NUM_MOTORS]
virtual void setup_motors(motor_frame_class frame_class, motor_frame_type frame_type)
void normalise_rpy_factors()
void add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, uint8_t testing_order)
struct AP_Motors::AP_Motors_flags _flags
void thrust_compensation(void) override
#define AP_MOTORS_MATRIX_YAW_FACTOR_CCW
struct AP_Motors::AP_Motors_limit limit
uint8_t _test_order[AP_MOTORS_MAX_NUM_MOTORS]
void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
uint16_t _disarm_safety_timer
AP_Int8 _disarm_disable_pwm
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
void output_armed_stabilizing()
void output_test(uint8_t motor_seq, int16_t pwm)
Motor control class for Matrixcopters.
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]
bool is_zero(const T fVal1)
void init(motor_frame_class frame_class, motor_frame_type frame_type)
uint16_t get_motor_mask()
float _throttle_thrust_max
void add_motor(int8_t motor_num, float angle_degrees, float yaw_factor, uint8_t testing_order)
virtual void rc_write(uint8_t chan, uint16_t pwm)
float _roll_factor[AP_MOTORS_MAX_NUM_MOTORS]
float _thrust_rpyt_out[AP_MOTORS_MAX_NUM_MOTORS]
float constrain_float(const float amt, const float low, const float high)
void set_update_rate(uint16_t speed_hz)
static constexpr float radians(float deg)
void add_motor_num(int8_t motor_num)
virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz)
spool_up_down_mode _spool_mode
int16_t calc_spin_up_to_pwm() const
thrust_compensation_fn_t _thrust_compensation_callback
float get_compensation_gain() const
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
int16_t calc_thrust_to_pwm(float thrust_in) const
float get_throttle() const
#define AP_MOTORS_MAX_NUM_MOTORS
virtual uint32_t rc_map_mask(uint32_t mask) const
#define AP_MOTORS_MATRIX_YAW_FACTOR_CW