123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140 |
- #pragma once
- #include <AP_Param/AP_Param.h>
- #include <GCS_MAVLink/GCS.h>
- #define AP_CAMERA_TRIGGER_TYPE_SERVO 0
- #define AP_CAMERA_TRIGGER_TYPE_RELAY 1
- #define AP_CAMERA_TRIGGER_DEFAULT_TRIGGER_TYPE AP_CAMERA_TRIGGER_TYPE_SERVO
- #define AP_CAMERA_TRIGGER_DEFAULT_DURATION 10
- #define AP_CAMERA_SERVO_ON_PWM 1300
- #define AP_CAMERA_SERVO_OFF_PWM 1100
- #define AP_CAMERA_FEEDBACK_DEFAULT_FEEDBACK_PIN -1
- class AP_Camera {
- public:
- AP_Camera(uint32_t _log_camera_bit, const struct Location &_loc)
- : log_camera_bit(_log_camera_bit)
- , current_loc(_loc)
- {
- AP_Param::setup_object_defaults(this, var_info);
- _singleton = this;
- }
-
- AP_Camera(const AP_Camera &other) = delete;
- AP_Camera &operator=(const AP_Camera&) = delete;
-
- static AP_Camera *get_singleton()
- {
- return _singleton;
- }
-
- void control_msg(const mavlink_message_t &msg);
- void send_feedback(mavlink_channel_t chan);
-
- void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time);
-
- void control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id);
-
- void set_trigger_distance(uint32_t distance_m)
- {
- _trigg_dist.set(distance_m);
- }
- void take_picture();
-
- void update();
-
- void update_trigger();
- static const struct AP_Param::GroupInfo var_info[];
-
- void set_is_auto_mode(bool enable)
- {
- _is_in_auto_mode = enable;
- }
- enum camera_types {
- CAMERA_TYPE_STD,
- CAMERA_TYPE_BMMCC
- };
- private:
- static AP_Camera *_singleton;
- AP_Int8 _trigger_type;
- AP_Int8 _trigger_duration;
- AP_Int8 _relay_on;
- AP_Int16 _servo_on_pwm;
- AP_Int16 _servo_off_pwm;
- uint8_t _trigger_counter;
- uint8_t _trigger_counter_cam_function;
- AP_Int8 _auto_mode_only;
- AP_Int8 _type;
- bool _is_in_auto_mode;
- void servo_pic();
- void relay_pic();
- void feedback_pin_timer();
- void feedback_pin_isr(uint8_t, bool, uint32_t);
- void setup_feedback_callback(void);
- AP_Float _trigg_dist;
- AP_Int16 _min_interval;
- AP_Int16 _max_roll;
- uint32_t _last_photo_time;
- struct Location _last_location;
- uint16_t _image_index;
-
- AP_Int8 _feedback_pin;
- AP_Int8 _feedback_polarity;
- uint32_t _camera_trigger_count;
- uint32_t _camera_trigger_logged;
- uint32_t _feedback_timestamp_us;
- bool _timer_installed;
- bool _isr_installed;
- uint8_t _last_pin_state;
- void log_picture();
- uint32_t log_camera_bit;
- const struct Location ¤t_loc;
-
- void trigger_pic();
-
-
- void trigger_pic_cleanup();
-
- bool using_feedback_pin(void) const
- {
- return _feedback_pin > 0;
- }
- };
- namespace AP {
- AP_Camera *camera();
- };
|