AP_Mount_Backend.h 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. Mount driver backend class. Each supported mount type
  15. needs to have an object derived from this class.
  16. */
  17. #pragma once
  18. #include <AP_Common/AP_Common.h>
  19. #include "AP_Mount.h"
  20. #include <RC_Channel/RC_Channel.h>
  21. class AP_Mount_Backend
  22. {
  23. public:
  24. // Constructor
  25. AP_Mount_Backend(AP_Mount &frontend, AP_Mount::mount_state& state, uint8_t instance) :
  26. _frontend(frontend),
  27. _state(state),
  28. _instance(instance)
  29. {}
  30. // Virtual destructor
  31. virtual ~AP_Mount_Backend(void) {}
  32. // init - performs any required initialisation for this instance
  33. virtual void init() = 0;
  34. // update mount position - should be called periodically
  35. virtual void update() = 0;
  36. // used for gimbals that need to read INS data at full rate
  37. virtual void update_fast() {}
  38. // has_pan_control - returns true if this mount can control it's pan (required for multicopters)
  39. virtual bool has_pan_control() const = 0;
  40. // set_mode - sets mount's mode
  41. virtual void set_mode(enum MAV_MOUNT_MODE mode) = 0;
  42. // set_angle_targets - sets angle targets in degrees
  43. virtual void set_angle_targets(float roll, float tilt, float pan);
  44. // set_roi_target - sets target location that mount should attempt to point towards
  45. virtual void set_roi_target(const struct Location &target_loc);
  46. // control - control the mount
  47. virtual void control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, MAV_MOUNT_MODE mount_mode);
  48. // process MOUNT_CONFIGURE messages received from GCS:
  49. void handle_mount_configure(const mavlink_mount_configure_t &msg);
  50. // process MOUNT_CONTROL messages received from GCS:
  51. void handle_mount_control(const mavlink_mount_control_t &packet);
  52. // send_mount_status - called to allow mounts to send their status to GCS via MAVLink
  53. virtual void send_mount_status(mavlink_channel_t chan) = 0;
  54. // handle a GIMBAL_REPORT message
  55. virtual void handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg) {}
  56. // handle a PARAM_VALUE message
  57. virtual void handle_param_value(const mavlink_message_t &msg) {}
  58. // send a GIMBAL_REPORT message to the GCS
  59. virtual void send_gimbal_report(const mavlink_channel_t chan) {}
  60. protected:
  61. // update_targets_from_rc - updates angle targets (i.e. _angle_ef_target_rad) using input from receiver
  62. void update_targets_from_rc();
  63. // angle_input_rad - convert RC input into an earth-frame target angle
  64. float angle_input_rad(const RC_Channel* rc, int16_t angle_min, int16_t angle_max);
  65. // calc_angle_to_location - calculates the earth-frame roll, tilt and pan angles (and radians) to point at the given target
  66. void calc_angle_to_location(const struct Location &target, Vector3f& angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan = true);
  67. // get the mount mode from frontend
  68. MAV_MOUNT_MODE get_mode(void) const { return _frontend.get_mode(_instance); }
  69. AP_Mount &_frontend; // reference to the front end which holds parameters
  70. AP_Mount::mount_state &_state; // references to the parameters and state for this backend
  71. uint8_t _instance; // this instance's number
  72. Vector3f _angle_ef_target_rad; // desired earth-frame roll, tilt and vehicle-relative pan angles in radians
  73. private:
  74. void rate_input_rad(float &out, const RC_Channel *ch, float min, float max) const;
  75. };