AP_MotorsMatrix.h 4.9 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697
  1. /// @file AP_MotorsMatrix.h
  2. /// @brief Motor control class for Matrixcopters
  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 <RC_Channel/RC_Channel.h> // RC Channel Library
  7. #include "AP_MotorsMulticopter.h"
  8. #define AP_MOTORS_MATRIX_YAW_FACTOR_CW -1
  9. #define AP_MOTORS_MATRIX_YAW_FACTOR_CCW 1
  10. /// @class AP_MotorsMatrix
  11. class AP_MotorsMatrix : public AP_MotorsMulticopter {
  12. public:
  13. /// Constructor
  14. AP_MotorsMatrix(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
  15. AP_MotorsMulticopter(loop_rate, speed_hz)
  16. {};
  17. // init
  18. void init(motor_frame_class frame_class, motor_frame_type frame_type) override;
  19. // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
  20. void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) override;
  21. // set update rate to motors - a value in hertz
  22. // you must have setup_motors before calling this
  23. void set_update_rate(uint16_t speed_hz) override;
  24. // output_test_seq - spin a motor at the pwm value specified
  25. // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
  26. // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
  27. virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override;
  28. // output_test_num - spin a motor connected to the specified output channel
  29. // (should only be performed during testing)
  30. // If a motor output channel is remapped, the mapped channel is used.
  31. // Returns true if motor output is set, false otherwise
  32. // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
  33. bool output_test_num(uint8_t motor, int16_t pwm);
  34. // output_to_motors - sends minimum values out to the motors
  35. void output_to_motors() override;
  36. // get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used)
  37. // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
  38. uint16_t get_motor_mask() override;
  39. // return number of motor that has failed. Should only be called if get_thrust_boost() returns true
  40. uint8_t get_lost_motor() const override { return _motor_lost_index; }
  41. // return the roll factor of any motor, this is used for tilt rotors and tail sitters
  42. // using copter motors for forward flight
  43. float get_roll_factor(uint8_t i) override { return _roll_factor[i]; }
  44. protected:
  45. // output - sends commands to the motors
  46. void output_armed_stabilizing() override;
  47. // check for failed motor
  48. void check_for_failed_motor(float throttle_thrust_best);
  49. // add_motor using raw roll, pitch, throttle and yaw factors
  50. void add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, uint8_t testing_order);
  51. // add_motor using just position and yaw_factor (or prop direction)
  52. void add_motor(int8_t motor_num, float angle_degrees, float yaw_factor, uint8_t testing_order);
  53. // add_motor using separate roll and pitch factors (for asymmetrical frames) and prop direction
  54. void add_motor(int8_t motor_num, float roll_factor_in_degrees, float pitch_factor_in_degrees, float yaw_factor, uint8_t testing_order);
  55. // remove_motor
  56. void remove_motor(int8_t motor_num);
  57. // configures the motors for the defined frame_class and frame_type
  58. virtual void setup_motors(motor_frame_class frame_class, motor_frame_type frame_type);
  59. // normalizes the roll, pitch and yaw factors so maximum magnitude is 0.5
  60. void normalise_rpy_factors();
  61. // call vehicle supplied thrust compensation if set
  62. void thrust_compensation(void) override;
  63. float _roll_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to roll
  64. float _pitch_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to pitch
  65. float _yaw_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to yaw (normally 1 or -1)
  66. float _thrust_rpyt_out[AP_MOTORS_MAX_NUM_MOTORS]; // combined roll, pitch, yaw and throttle outputs to motors in 0~1 range
  67. uint8_t _test_order[AP_MOTORS_MAX_NUM_MOTORS]; // order of the motors in the test sequence
  68. motor_frame_class _last_frame_class; // most recently requested frame class (i.e. quad, hexa, octa, etc)
  69. motor_frame_type _last_frame_type; // most recently requested frame type (i.e. plus, x, v, etc)
  70. // motor failure handling
  71. float _thrust_rpyt_out_filt[AP_MOTORS_MAX_NUM_MOTORS]; // filtered thrust outputs with 1 second time constant
  72. uint8_t _motor_lost_index; // index number of the lost motor
  73. };