/// @file AP_MotorsSingle.h /// @brief Motor and Servo control class for Singlecopters #pragma once #include #include // ArduPilot Mega Vector/Matrix math Library #include #include "AP_MotorsMulticopter.h" // feedback direction #define AP_MOTORS_SING_POSITIVE 1 #define AP_MOTORS_SING_NEGATIVE -1 #define NUM_ACTUATORS 4 #define AP_MOTORS_SINGLE_SPEED_DIGITAL_SERVOS 250 // update rate for digital servos #define AP_MOTORS_SINGLE_SPEED_ANALOG_SERVOS 125 // update rate for analog servos #define AP_MOTORS_SINGLE_SERVO_INPUT_RANGE 4500 // roll or pitch input of -4500 will cause servos to their minimum (i.e. radio_min), +4500 will move them to their maximum (i.e. radio_max) /// @class AP_MotorsSingle class AP_MotorsSingle : public AP_MotorsMulticopter { public: /// Constructor AP_MotorsSingle(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMulticopter(loop_rate, speed_hz) { }; // init void init(motor_frame_class frame_class, motor_frame_type frame_type); // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus) void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type); // set update rate to motors - a value in hertz void set_update_rate( uint16_t speed_hz ); // output_test - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 virtual void output_test(uint8_t motor_seq, int16_t pwm); // output_to_motors - sends minimum values out to the motors virtual void output_to_motors(); // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict virtual uint16_t get_motor_mask(); protected: // output - sends commands to the motors void output_armed_stabilizing(); int16_t _throttle_radio_output; // total throttle pwm value, summed onto throttle channel minimum, typically ~1100-1900 float _actuator_out[NUM_ACTUATORS]; // combined roll, pitch, yaw and throttle outputs to motors in 0~1 range float _thrust_out; };