46 gcs().
send_text(MAV_SEVERITY_ERROR,
"MotorsTri: unable to setup yaw channel");
125 float throttle_thrust;
126 float throttle_avg_max;
127 float throttle_thrust_best_rpy;
128 float rpy_scale = 1.0f;
129 float rpy_low = 0.0f;
130 float rpy_high = 0.0f;
138 roll_thrust =
_roll_in * compensation_gain;
139 pitch_thrust =
_pitch_in * compensation_gain;
152 float thrust_max = 1.0f;
155 if (throttle_thrust <= 0.0
f) {
156 throttle_thrust = 0.0f;
172 _thrust_left = roll_thrust * 0.5f + pitch_thrust * 0.5f;
186 thrust_max = pivot_thrust_max;
201 throttle_thrust_best_rpy =
MIN(0.5
f*thrust_max - (rpy_low+rpy_high)/2.0, throttle_avg_max);
209 thr_adj = throttle_thrust - throttle_thrust_best_rpy;
210 if(rpy_scale < 1.0
f){
218 if(thr_adj < -(throttle_thrust_best_rpy+rpy_low)){
220 thr_adj = -(throttle_thrust_best_rpy+rpy_low);
221 }
else if(thr_adj > thrust_max - (throttle_thrust_best_rpy+rpy_high)){
223 thr_adj = thrust_max - (throttle_thrust_best_rpy+rpy_high);
284 yaw_input = -yaw_input;
313 _thrust_rear = thrust[3];
int16_t get_pwm_output_min() const
virtual void output_test(uint8_t motor_seq, int16_t pwm)
Interface definition for the various Ground Control System.
struct AP_Motors::AP_Motors_flags _flags
void output_armed_stabilizing()
uint16_t get_output_max(void) const
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
struct AP_Motors::AP_Motors_limit limit
static SRV_Channel * get_channel_for(SRV_Channel::Aux_servo_function_t function, int8_t default_chan=-1)
void thrust_compensation(void) override
#define AP_MOTORS_TRI_SERVO_RANGE_DEG_MIN
#define AP_MOTORS_TRI_SERVO_RANGE_DEG_MAX
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
int16_t calc_yaw_radio_output(float yaw_input, float yaw_input_max)
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]
bool is_zero(const T fVal1)
#define AP_MOTORS_CH_TRI_YAW
Motor control class for Tricopters.
void init(motor_frame_class frame_class, motor_frame_type frame_type)
uint16_t get_output_min(void) const
void send_text(MAV_SEVERITY severity, const char *fmt,...)
float _throttle_thrust_max
float safe_asin(const T v)
virtual void rc_write(uint8_t chan, uint16_t pwm)
uint16_t get_trim(void) const
float constrain_float(const float amt, const float low, const float high)
virtual uint16_t get_motor_mask()
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
bool get_reversed(void) const
int16_t calc_spin_up_to_pwm() const
thrust_compensation_fn_t _thrust_compensation_callback
float get_compensation_gain() const
int16_t calc_thrust_to_pwm(float thrust_in) const
void output_motor_mask(float thrust, uint8_t mask) override
float get_throttle() const
AP_Float _yaw_servo_angle_max_deg
virtual void output_to_motors()
virtual uint32_t rc_map_mask(uint32_t mask) const
void set_update_rate(uint16_t speed_hz)
void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
virtual void output_motor_mask(float thrust, uint8_t mask)