AP_MotorsCoax.h 2.5 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859
  1. /// @file AP_MotorsCoax.h
  2. /// @brief Motor and Servo control class for Co-axial helicopters with two motors and two flaps
  3. #pragma once
  4. #include <AP_Common/AP_Common.h>
  5. #include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
  6. #include <SRV_Channel/SRV_Channel.h>
  7. #include "AP_MotorsMulticopter.h"
  8. // feedback direction
  9. #define AP_MOTORS_COAX_POSITIVE 1
  10. #define AP_MOTORS_COAX_NEGATIVE -1
  11. #define NUM_ACTUATORS 4
  12. #define AP_MOTORS_SINGLE_SPEED_DIGITAL_SERVOS 250 // update rate for digital servos
  13. #define AP_MOTORS_SINGLE_SPEED_ANALOG_SERVOS 125 // update rate for analog servos
  14. #define AP_MOTORS_COAX_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)
  15. /// @class AP_MotorsSingle
  16. class AP_MotorsCoax : public AP_MotorsMulticopter {
  17. public:
  18. /// Constructor
  19. AP_MotorsCoax(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
  20. AP_MotorsMulticopter(loop_rate, speed_hz)
  21. {
  22. };
  23. // init
  24. void init(motor_frame_class frame_class, motor_frame_type frame_type) override;
  25. // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
  26. void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) override;
  27. // set update rate to motors - a value in hertz
  28. void set_update_rate( uint16_t speed_hz ) override;
  29. // output_test_seq - spin a motor at the pwm value specified
  30. // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
  31. // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
  32. virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override;
  33. // output_to_motors - sends minimum values out to the motors
  34. virtual void output_to_motors() override;
  35. // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
  36. // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
  37. uint16_t get_motor_mask() override;
  38. protected:
  39. // output - sends commands to the motors
  40. void output_armed_stabilizing() override;
  41. float _actuator_out[NUM_ACTUATORS]; // combined roll, pitch, yaw and throttle outputs to motors in 0~1 range
  42. float _thrust_yt_ccw;
  43. float _thrust_yt_cw;
  44. };