AP_MotorsTri.h 3.1 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374
  1. /// @file AP_MotorsTri.h
  2. /// @brief Motor control class for Tricopters
  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. // tail servo uses channel 7
  9. #define AP_MOTORS_CH_TRI_YAW CH_7
  10. #define AP_MOTORS_TRI_SERVO_RANGE_DEG_MIN 5 // minimum angle movement of tail servo in degrees
  11. #define AP_MOTORS_TRI_SERVO_RANGE_DEG_MAX 80 // maximum angle movement of tail servo in degrees
  12. /// @class AP_MotorsTri
  13. class AP_MotorsTri : public AP_MotorsMulticopter {
  14. public:
  15. /// Constructor
  16. AP_MotorsTri(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
  17. AP_MotorsMulticopter(loop_rate, speed_hz)
  18. {
  19. };
  20. // init
  21. void init(motor_frame_class frame_class, motor_frame_type frame_type) override;
  22. // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
  23. void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) override;
  24. // set update rate to motors - a value in hertz
  25. void set_update_rate( uint16_t speed_hz ) override;
  26. // output_test_seq - spin a motor at the pwm value specified
  27. // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
  28. // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
  29. virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override;
  30. // output_to_motors - sends minimum values out to the motors
  31. virtual void output_to_motors() override;
  32. // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
  33. // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
  34. uint16_t get_motor_mask() override;
  35. // output a thrust to all motors that match a given motor
  36. // mask. This is used to control tiltrotor motors in forward
  37. // flight. Thrust is in the range 0 to 1
  38. // rudder_dt applys diffential thrust for yaw in the range 0 to 1
  39. void output_motor_mask(float thrust, uint8_t mask, float rudder_dt) override;
  40. // return the roll factor of any motor, this is used for tilt rotors and tail sitters
  41. // using copter motors for forward flight
  42. float get_roll_factor(uint8_t i) override;
  43. protected:
  44. // output - sends commands to the motors
  45. void output_armed_stabilizing() override;
  46. // call vehicle supplied thrust compensation if set
  47. void thrust_compensation(void) override;
  48. // calc_yaw_radio_output - calculate final radio output for yaw channel
  49. int16_t calc_yaw_radio_output(float yaw_input, float yaw_input_max); // calculate radio output for yaw servo, typically in range of 1100-1900
  50. // parameters
  51. SRV_Channel *_yaw_servo; // yaw output channel
  52. float _pivot_angle; // Angle of yaw pivot
  53. float _thrust_right;
  54. float _thrust_rear;
  55. float _thrust_left;
  56. };