AP_Motors6DOF.h 3.8 KB

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