AP_MotorsTailsitter.h 1.5 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546
  1. /// @file AP_MotorsTailsitter.h
  2. /// @brief Motor control class for tailsitters and bicopters
  3. #pragma once
  4. #include <AP_Common/AP_Common.h>
  5. #include <AP_Math/AP_Math.h>
  6. #include <SRV_Channel/SRV_Channel.h>
  7. #include "AP_MotorsMulticopter.h"
  8. /// @class AP_MotorsTailsitter
  9. class AP_MotorsTailsitter : public AP_MotorsMulticopter {
  10. public:
  11. /// Constructor
  12. AP_MotorsTailsitter(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT);
  13. // init
  14. void init(motor_frame_class frame_class, motor_frame_type frame_type) override;
  15. // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
  16. void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) override {}
  17. // set update rate to motors - a value in hertz
  18. void set_update_rate( uint16_t speed_hz ) override;
  19. // spin a motor at the pwm value specified
  20. void output_test_seq(uint8_t motor_seq, int16_t pwm) override;
  21. // output_to_motors - sends output to named servos
  22. void output_to_motors() override;
  23. // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
  24. // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
  25. uint16_t get_motor_mask() override;
  26. protected:
  27. // calculate motor outputs
  28. void output_armed_stabilizing() override;
  29. // calculated outputs
  30. float _throttle; // 0..1
  31. float _tilt_left; // -1..1
  32. float _tilt_right; // -1..1
  33. float _thrust_left; // 0..1
  34. float _thrust_right; // 0..1
  35. };