AP_Mount.h 7.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188
  1. /************************************************************
  2. * AP_mount -- library to control a 2 or 3 axis mount. *
  3. * *
  4. * Author: Joe Holdsworth; *
  5. * Ritchie Wilson; *
  6. * Amilcar Lucas; *
  7. * Gregory Fletcher; *
  8. * heavily modified by Randy Mackay *
  9. * *
  10. * Purpose: Move a 2 or 3 axis mount attached to vehicle, *
  11. * Used for mount to track targets or stabilise *
  12. * camera plus other modes. *
  13. * *
  14. * Usage: Use in main code to control mounts attached to *
  15. * vehicle. *
  16. * *
  17. * Comments: All angles in degrees * 100, distances in meters*
  18. * unless otherwise stated. *
  19. ************************************************************/
  20. #pragma once
  21. #include <AP_Math/AP_Math.h>
  22. #include <AP_Common/AP_Common.h>
  23. #include <AP_Common/Location.h>
  24. #include <GCS_MAVLink/GCS_MAVLink.h>
  25. // maximum number of mounts
  26. #define AP_MOUNT_MAX_INSTANCES 1
  27. // declare backend classes
  28. class AP_Mount_Backend;
  29. class AP_Mount_Servo;
  30. class AP_Mount_SoloGimbal;
  31. class AP_Mount_Alexmos;
  32. class AP_Mount_SToRM32;
  33. class AP_Mount_SToRM32_serial;
  34. /*
  35. This is a workaround to allow the MAVLink backend access to the
  36. SmallEKF. It would be nice to find a neater solution to this
  37. */
  38. class AP_Mount
  39. {
  40. // declare backends as friends
  41. friend class AP_Mount_Backend;
  42. friend class AP_Mount_Servo;
  43. friend class AP_Mount_SoloGimbal;
  44. friend class AP_Mount_Alexmos;
  45. friend class AP_Mount_SToRM32;
  46. friend class AP_Mount_SToRM32_serial;
  47. public:
  48. AP_Mount(const struct Location &current_loc);
  49. /* Do not allow copies */
  50. AP_Mount(const AP_Mount &other) = delete;
  51. AP_Mount &operator=(const AP_Mount&) = delete;
  52. // get singleton instance
  53. static AP_Mount *get_singleton() {
  54. return _singleton;
  55. }
  56. // Enums
  57. enum MountType {
  58. Mount_Type_None = 0, /// no mount
  59. Mount_Type_Servo = 1, /// servo controlled mount
  60. Mount_Type_SoloGimbal = 2, /// Solo's gimbal
  61. Mount_Type_Alexmos = 3, /// Alexmos mount
  62. Mount_Type_SToRM32 = 4, /// SToRM32 mount using MAVLink protocol
  63. Mount_Type_SToRM32_serial = 5 /// SToRM32 mount using custom serial protocol
  64. };
  65. // init - detect and initialise all mounts
  66. void init();
  67. // update - give mount opportunity to update servos. should be called at 10hz or higher
  68. void update();
  69. // used for gimbals that need to read INS data at full rate
  70. void update_fast();
  71. // get_mount_type - returns the type of mount
  72. AP_Mount::MountType get_mount_type() const { return get_mount_type(_primary); }
  73. AP_Mount::MountType get_mount_type(uint8_t instance) const;
  74. // has_pan_control - returns true if the mount has yaw control (required for copters)
  75. bool has_pan_control() const { return has_pan_control(_primary); }
  76. bool has_pan_control(uint8_t instance) const;
  77. // get_mode - returns current mode of mount (i.e. Retracted, Neutral, RC_Targeting, GPS Point)
  78. enum MAV_MOUNT_MODE get_mode() const { return get_mode(_primary); }
  79. enum MAV_MOUNT_MODE get_mode(uint8_t instance) const;
  80. // set_mode - sets mount's mode
  81. // returns true if mode is successfully set
  82. void set_mode(enum MAV_MOUNT_MODE mode) { return set_mode(_primary, mode); }
  83. void set_mode(uint8_t instance, enum MAV_MOUNT_MODE mode);
  84. // set_mode_to_default - restores the mode to it's default mode held in the MNT_DEFLT_MODE parameter
  85. // this operation requires 60us on a Pixhawk/PX4
  86. void set_mode_to_default() { set_mode_to_default(_primary); }
  87. void set_mode_to_default(uint8_t instance);
  88. // set_angle_targets - sets angle targets in degrees
  89. void set_angle_targets(float roll, float tilt, float pan) { set_angle_targets(_primary, roll, tilt, pan); }
  90. void set_angle_targets(uint8_t instance, float roll, float tilt, float pan);
  91. // set_roi_target - sets target location that mount should attempt to point towards
  92. void set_roi_target(const struct Location &target_loc) { set_roi_target(_primary,target_loc); }
  93. void set_roi_target(uint8_t instance, const struct Location &target_loc);
  94. // mavlink message handling:
  95. MAV_RESULT handle_command_long(const mavlink_command_long_t &packet);
  96. void handle_param_value(const mavlink_message_t &msg);
  97. void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg);
  98. // send a GIMBAL_REPORT message to GCS
  99. void send_gimbal_report(mavlink_channel_t chan);
  100. // send a MOUNT_STATUS message to GCS:
  101. void send_mount_status(mavlink_channel_t chan);
  102. // parameter var table
  103. static const struct AP_Param::GroupInfo var_info[];
  104. protected:
  105. static AP_Mount *_singleton;
  106. // private members
  107. const struct Location &_current_loc; // reference to the vehicle's current location
  108. // frontend parameters
  109. AP_Int8 _joystick_speed; // joystick gain
  110. // front end members
  111. uint8_t _num_instances; // number of mounts instantiated
  112. uint8_t _primary; // primary mount
  113. AP_Mount_Backend *_backends[AP_MOUNT_MAX_INSTANCES]; // pointers to instantiated mounts
  114. // backend state including parameters
  115. struct mount_state {
  116. // Parameters
  117. AP_Int8 _type; // mount type (None, Servo or MAVLink, see MountType enum)
  118. AP_Int8 _default_mode; // default mode on startup and when control is returned from autopilot
  119. AP_Int8 _stab_roll; // 1 = mount should stabilize earth-frame roll axis, 0 = no stabilization
  120. AP_Int8 _stab_tilt; // 1 = mount should stabilize earth-frame pitch axis
  121. AP_Int8 _stab_pan; // 1 = mount should stabilize earth-frame yaw axis
  122. // RC input channels from receiver used for direct angular input from pilot
  123. AP_Int8 _roll_rc_in; // pilot provides roll input on this channel
  124. AP_Int8 _tilt_rc_in; // pilot provides tilt input on this channel
  125. AP_Int8 _pan_rc_in; // pilot provides pan input on this channel
  126. // Mount's physical limits
  127. AP_Int16 _roll_angle_min; // min roll in 0.01 degree units
  128. AP_Int16 _roll_angle_max; // max roll in 0.01 degree units
  129. AP_Int16 _tilt_angle_min; // min tilt in 0.01 degree units
  130. AP_Int16 _tilt_angle_max; // max tilt in 0.01 degree units
  131. AP_Int16 _pan_angle_min; // min pan in 0.01 degree units
  132. AP_Int16 _pan_angle_max; // max pan in 0.01 degree units
  133. AP_Vector3f _retract_angles; // retracted position for mount, vector.x = roll vector.y = tilt, vector.z=pan
  134. AP_Vector3f _neutral_angles; // neutral position for mount, vector.x = roll vector.y = tilt, vector.z=pan
  135. AP_Float _roll_stb_lead; // roll lead control gain
  136. AP_Float _pitch_stb_lead; // pitch lead control gain
  137. MAV_MOUNT_MODE _mode; // current mode (see MAV_MOUNT_MODE enum)
  138. struct Location _roi_target; // roi target location
  139. } state[AP_MOUNT_MAX_INSTANCES];
  140. private:
  141. void handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg);
  142. void handle_mount_configure(const mavlink_message_t &msg);
  143. void handle_mount_control(const mavlink_message_t &msg);
  144. MAV_RESULT handle_command_do_mount_configure(const mavlink_command_long_t &packet);
  145. MAV_RESULT handle_command_do_mount_control(const mavlink_command_long_t &packet);
  146. };
  147. namespace AP {
  148. AP_Mount *mount();
  149. };