AP_Camera.h 5.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140
  1. /// @file AP_Camera.h
  2. /// @brief Photo or video camera manager, with EEPROM-backed storage of constants.
  3. #pragma once
  4. #include <AP_Param/AP_Param.h>
  5. #include <GCS_MAVLink/GCS.h>
  6. #define AP_CAMERA_TRIGGER_TYPE_SERVO 0
  7. #define AP_CAMERA_TRIGGER_TYPE_RELAY 1
  8. #define AP_CAMERA_TRIGGER_DEFAULT_TRIGGER_TYPE AP_CAMERA_TRIGGER_TYPE_SERVO // default is to use servo to trigger camera
  9. #define AP_CAMERA_TRIGGER_DEFAULT_DURATION 10 // default duration servo or relay is held open in 10ths of a second (i.e. 10 = 1 second)
  10. #define AP_CAMERA_SERVO_ON_PWM 1300 // default PWM value to move servo to when shutter is activated
  11. #define AP_CAMERA_SERVO_OFF_PWM 1100 // default PWM value to move servo to when shutter is deactivated
  12. #define AP_CAMERA_FEEDBACK_DEFAULT_FEEDBACK_PIN -1 // default is to not use camera feedback pin
  13. /// @class Camera
  14. /// @brief Object managing a Photo or video camera
  15. class AP_Camera {
  16. public:
  17. AP_Camera(uint32_t _log_camera_bit, const struct Location &_loc)
  18. : log_camera_bit(_log_camera_bit)
  19. , current_loc(_loc)
  20. {
  21. AP_Param::setup_object_defaults(this, var_info);
  22. _singleton = this;
  23. }
  24. /* Do not allow copies */
  25. AP_Camera(const AP_Camera &other) = delete;
  26. AP_Camera &operator=(const AP_Camera&) = delete;
  27. // get singleton instance
  28. static AP_Camera *get_singleton()
  29. {
  30. return _singleton;
  31. }
  32. // MAVLink methods
  33. void control_msg(const mavlink_message_t &msg);
  34. void send_feedback(mavlink_channel_t chan);
  35. // Command processing
  36. void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time);
  37. // handle camera control
  38. void control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id);
  39. // set camera trigger distance in a mission
  40. void set_trigger_distance(uint32_t distance_m)
  41. {
  42. _trigg_dist.set(distance_m);
  43. }
  44. void take_picture();
  45. // Update - to be called periodically @at least 10Hz
  46. void update();
  47. // update camera trigger - 50Hz
  48. void update_trigger();
  49. static const struct AP_Param::GroupInfo var_info[];
  50. // set if vehicle is in AUTO mode
  51. void set_is_auto_mode(bool enable)
  52. {
  53. _is_in_auto_mode = enable;
  54. }
  55. enum camera_types {
  56. CAMERA_TYPE_STD,
  57. CAMERA_TYPE_BMMCC
  58. };
  59. private:
  60. static AP_Camera *_singleton;
  61. AP_Int8 _trigger_type; // 0:Servo,1:Relay
  62. AP_Int8 _trigger_duration; // duration in 10ths of a second that the camera shutter is held open
  63. AP_Int8 _relay_on; // relay value to trigger camera
  64. AP_Int16 _servo_on_pwm; // PWM value to move servo to when shutter is activated
  65. AP_Int16 _servo_off_pwm; // PWM value to move servo to when shutter is deactivated
  66. uint8_t _trigger_counter; // count of number of cycles shutter has been held open
  67. uint8_t _trigger_counter_cam_function; // count of number of cycles alternative camera function has been held open
  68. AP_Int8 _auto_mode_only; // if 1: trigger by distance only if in AUTO mode.
  69. AP_Int8 _type; // Set the type of camera in use, will open additional parameters if set
  70. bool _is_in_auto_mode; // true if in AUTO mode
  71. void servo_pic(); // Servo operated camera
  72. void relay_pic(); // basic relay activation
  73. void feedback_pin_timer();
  74. void feedback_pin_isr(uint8_t, bool, uint32_t);
  75. void setup_feedback_callback(void);
  76. AP_Float _trigg_dist; // distance between trigger points (meters)
  77. AP_Int16 _min_interval; // Minimum time between shots required by camera
  78. AP_Int16 _max_roll; // Maximum acceptable roll angle when trigging camera
  79. uint32_t _last_photo_time; // last time a photo was taken
  80. struct Location _last_location;
  81. uint16_t _image_index; // number of pictures taken since boot
  82. // pin number for accurate camera feedback messages
  83. AP_Int8 _feedback_pin;
  84. AP_Int8 _feedback_polarity;
  85. uint32_t _camera_trigger_count;
  86. uint32_t _camera_trigger_logged;
  87. uint32_t _feedback_timestamp_us;
  88. bool _timer_installed;
  89. bool _isr_installed;
  90. uint8_t _last_pin_state;
  91. void log_picture();
  92. uint32_t log_camera_bit;
  93. const struct Location &current_loc;
  94. // entry point to trip local shutter (e.g. by relay or servo)
  95. void trigger_pic();
  96. // de-activate the trigger after some delay, but without using a delay() function
  97. // should be called at 50hz from main program
  98. void trigger_pic_cleanup();
  99. // return true if we are using a feedback pin
  100. bool using_feedback_pin(void) const
  101. {
  102. return _feedback_pin > 0;
  103. }
  104. };
  105. namespace AP {
  106. AP_Camera *camera();
  107. };