28 #define SERVO_OUTPUT_RANGE 4500 29 #define THROTTLE_RANGE 100 53 float throttle_left = 0;
54 float throttle_right = 0;
98 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
Motor control class for tailsitters.
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Interface definition for the various Ground Control System.
struct AP_Motors::AP_Motors_flags _flags
#define SERVO_OUTPUT_RANGE
struct AP_Motors::AP_Motors_limit limit
void output_armed_stabilizing()
AP_MotorsTailsitter(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_SPEED_DEFAULT)
Constructor.
static void output_ch_all(void)
static void set_output_scaled(SRV_Channel::Aux_servo_function_t function, int16_t value)
float _throttle_thrust_max
float constrain_float(const float amt, const float low, const float high)
static void set_rc_frequency(SRV_Channel::Aux_servo_function_t function, uint16_t frequency)
spool_up_down_mode _spool_mode
float get_throttle() const
static void calc_pwm(void)
void init(motor_frame_class frame_class, motor_frame_type frame_type)