AP_Motors6DOF.h 3.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107
  1. /// @file AP_Motors6DOF.h
  2. /// @brief Motor control class for ROVs with direct control over 6DOF (or fewer) in movement
  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_MotorsMatrix.h"
  8. /// @class AP_MotorsMatrix
  9. class AP_Motors6DOF : public AP_MotorsMatrix {
  10. public:
  11. AP_Motors6DOF(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
  12. AP_MotorsMatrix(loop_rate, speed_hz) {
  13. AP_Param::setup_object_defaults(this, var_info);
  14. _singleton = this;
  15. for (uint8_t i= 0; i < 6; i++)
  16. {
  17. motor_to_can[i]=0;
  18. }
  19. pwm_track[0] = 1500;
  20. pwm_track[1] = 1500;
  21. };
  22. // Supported frame types
  23. typedef enum {
  24. SUB_FRAME_BLUEROV1,
  25. SUB_FRAME_VECTORED,
  26. SUB_FRAME_VECTORED_6DOF,
  27. SUB_FRAME_VECTORED_6DOF_90DEG,
  28. SUB_FRAME_SIMPLEROV_3,
  29. SUB_FRAME_SIMPLEROV_4,
  30. SUB_FRAME_SIMPLEROV_5,
  31. SUB_FRAME_CUSTOM
  32. } sub_frame_t;
  33. //----------selfdefine start------------------------
  34. //---------------外部可以调用句柄--------------
  35. static AP_Motors6DOF *_singleton;
  36. static AP_Motors6DOF *get_singleton() {
  37. return _singleton;
  38. }
  39. int32_t motor_to_can[6];//发送给CAN的数据
  40. int16_t pwm_track[2];
  41. float last_thrust_in[AP_MOTORS_MAX_NUM_MOTORS];
  42. int32_t last_thrust_Dhot[AP_MOTORS_MAX_NUM_MOTORS];
  43. //----------selfdefine end------------------------
  44. // Override parent
  45. void setup_motors(motor_frame_class frame_class, motor_frame_type frame_type) override;
  46. // Override parent
  47. void output_min() override;
  48. // Map thrust input -1~1 to pwm output 1100~1900
  49. int16_t calc_thrust_to_pwm(float thrust_in) const;
  50. int32_t calc_thrust_to_motor(float thrust_in,int8_t i);
  51. void output_motor8_and_motor9(void);
  52. // output_to_motors - sends minimum values out to the motors
  53. void output_to_motors() override;
  54. void output_to_Dshot() override;//dshot赋值
  55. // This allows us to read back the output of the altidude controllers
  56. // The controllers are in charge of the throttle input, so this gives vehicle access/visibility to the output of those controllers
  57. float get_throttle_in_bidirectional() const { return constrain_float(2*(_throttle_in - 0.5f), -1.0f, 1.0f); }
  58. // returns a vector with roll, pitch, and yaw contributions
  59. Vector3f get_motor_angular_factors(int motor_number);
  60. // returns true if motor is enabled
  61. bool motor_is_enabled(int motor_number);
  62. bool set_reversed(int motor_number, bool reversed);
  63. // var_info for holding Parameter information
  64. static const struct AP_Param::GroupInfo var_info[];
  65. protected:
  66. // return current_limit as a number from 0 ~ 1 in the range throttle_min to throttle_max
  67. float get_current_limit_max_throttle() override;
  68. //Override MotorsMatrix method
  69. void add_motor_raw_6dof(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, float climb_fac, float forward_fac, float lat_fac, uint8_t testing_order);
  70. void output_armed_stabilizing() override;
  71. void output_armed_stabilizing_vectored();
  72. void output_armed_stabilizing_vectored_6dof();
  73. // Parameters
  74. AP_Int8 _motor_reverse[AP_MOTORS_MAX_NUM_MOTORS];
  75. AP_Float _forwardVerticalCouplingFactor;
  76. float _throttle_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to throttle (climb/descent)
  77. float _forward_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to forward/backward
  78. float _lateral_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to lateral (left/right)
  79. // current limiting
  80. float _output_limited = 1.0f;
  81. float _batt_current_last = 0.0f;
  82. };
  83. namespace AP {
  84. AP_Motors6DOF &motors6dof();
  85. };