AP_Mount_Servo.h 2.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172
  1. /*
  2. Servo controlled mount backend class
  3. */
  4. #pragma once
  5. #include <AP_Math/AP_Math.h>
  6. #include <AP_Common/AP_Common.h>
  7. #include <AP_AHRS/AP_AHRS.h>
  8. #include <GCS_MAVLink/GCS_MAVLink.h>
  9. #include <SRV_Channel/SRV_Channel.h>
  10. #include "AP_Mount_Backend.h"
  11. class AP_Mount_Servo : public AP_Mount_Backend
  12. {
  13. public:
  14. // Constructor
  15. AP_Mount_Servo(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance):
  16. AP_Mount_Backend(frontend, state, instance),
  17. _roll_idx(SRV_Channel::k_none),
  18. _tilt_idx(SRV_Channel::k_none),
  19. _pan_idx(SRV_Channel::k_none),
  20. _open_idx(SRV_Channel::k_none)
  21. {
  22. }
  23. // init - performs any required initialisation for this instance
  24. void init() override;
  25. // update mount position - should be called periodically
  26. void update() override;
  27. // has_pan_control - returns true if this mount can control it's pan (required for multicopters)
  28. bool has_pan_control() const override { return _flags.pan_control; }
  29. // set_mode - sets mount's mode
  30. void set_mode(enum MAV_MOUNT_MODE mode) override;
  31. // send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
  32. void send_mount_status(mavlink_channel_t chan) override;
  33. private:
  34. // flags structure
  35. struct {
  36. bool roll_control :1; // true if mount has roll control
  37. bool tilt_control :1; // true if mount has tilt control
  38. bool pan_control :1; // true if mount has pan control
  39. } _flags;
  40. // check_servo_map - detects which axis we control (i.e. _flags) using the functions assigned to the servos in the SRV_Channel
  41. // should be called periodically (i.e. 1hz or less)
  42. void check_servo_map();
  43. // stabilize - stabilizes the mount relative to the Earth's frame
  44. void stabilize();
  45. // closest_limit - returns closest angle to 'angle' taking into account limits. all angles are in degrees * 10
  46. int16_t closest_limit(int16_t angle, int16_t angle_min, int16_t angle_max);
  47. /// move_servo - moves servo with the given id to the specified angle. all angles are in degrees * 10
  48. void move_servo(uint8_t rc, int16_t angle, int16_t angle_min, int16_t angle_max);
  49. // SRV_Channel - different id numbers are used depending upon the instance number
  50. SRV_Channel::Aux_servo_function_t _roll_idx; // SRV_Channel mount roll function index
  51. SRV_Channel::Aux_servo_function_t _tilt_idx; // SRV_Channel mount tilt function index
  52. SRV_Channel::Aux_servo_function_t _pan_idx; // SRV_Channel mount pan function index
  53. SRV_Channel::Aux_servo_function_t _open_idx; // SRV_Channel mount open function index
  54. Vector3f _angle_bf_output_deg; // final body frame output angle in degrees
  55. uint32_t _last_check_servo_map_ms; // system time of latest call to check_servo_map function
  56. };