1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859 |
- #pragma once
- #include <AP_Common/AP_Common.h>
- #include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
- #include <SRV_Channel/SRV_Channel.h>
- #include "AP_MotorsMulticopter.h"
- #define AP_MOTORS_SING_POSITIVE 1
- #define AP_MOTORS_SING_NEGATIVE -1
- #define NUM_ACTUATORS 4
- #define AP_MOTORS_SINGLE_SPEED_DIGITAL_SERVOS 250
- #define AP_MOTORS_SINGLE_SPEED_ANALOG_SERVOS 125
- #define AP_MOTORS_SINGLE_SERVO_INPUT_RANGE 4500
- class AP_MotorsSingle : public AP_MotorsMulticopter {
- public:
-
- AP_MotorsSingle(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
- AP_MotorsMulticopter(loop_rate, speed_hz)
- {
- };
-
- void init(motor_frame_class frame_class, motor_frame_type frame_type) override;
-
- void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) override;
-
- void set_update_rate( uint16_t speed_hz ) override;
-
-
-
- virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override;
-
- virtual void output_to_motors() override;
-
-
- uint16_t get_motor_mask() override;
- protected:
-
- void output_armed_stabilizing() override;
- int16_t _throttle_radio_output;
- float _actuator_out[NUM_ACTUATORS];
- float _thrust_out;
- };
|