52 void add_motor_raw_6dof(int8_t motor_num,
float roll_fac,
float pitch_fac,
float yaw_fac,
float climb_fac,
float forward_fac,
float lat_fac, uint8_t testing_order);
AP_Motors6DOF(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_SPEED_DEFAULT)
float _forward_factor[AP_MOTORS_MAX_NUM_MOTORS]
AP_Float _forwardVerticalCouplingFactor
void add_motor_raw_6dof(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, float climb_fac, float forward_fac, float lat_fac, uint8_t testing_order)
#define AP_MOTORS_SPEED_DEFAULT
float get_current_limit_max_throttle() override
static const struct AP_Param::GroupInfo var_info[]
void output_armed_stabilizing() override
int16_t calc_thrust_to_pwm(float thrust_in) const
Motor control class for Matrixcopters.
RC_Channel manager, with EEPROM-backed storage of constants.
void setup_motors(motor_frame_class frame_class, motor_frame_type frame_type) override
void output_to_motors() override
float _lateral_factor[AP_MOTORS_MAX_NUM_MOTORS]
Common definitions and utility routines for the ArduPilot libraries.
AP_Int8 _motor_reverse[AP_MOTORS_MAX_NUM_MOTORS]
void output_min() override
void output_armed_stabilizing_vectored()
#define AP_MOTORS_MAX_NUM_MOTORS
void output_armed_stabilizing_vectored_6dof()
float _throttle_factor[AP_MOTORS_MAX_NUM_MOTORS]
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)