APM:Libraries
AP_Camera.h
Go to the documentation of this file.
1 #pragma once
4 
5 #include <AP_Param/AP_Param.h>
6 #include <AP_Common/AP_Common.h>
8 #include <GCS_MAVLink/GCS.h>
9 #include <AP_Relay/AP_Relay.h>
10 #include <AP_GPS/AP_GPS.h>
11 #include <AP_AHRS/AP_AHRS.h>
12 #include <AP_Mission/AP_Mission.h>
13 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
14 #include <drivers/drv_hrt.h>
15 #endif
16 
17 #define AP_CAMERA_TRIGGER_TYPE_SERVO 0
18 #define AP_CAMERA_TRIGGER_TYPE_RELAY 1
19 
20 #define AP_CAMERA_TRIGGER_DEFAULT_TRIGGER_TYPE AP_CAMERA_TRIGGER_TYPE_SERVO // default is to use servo to trigger camera
21 
22 #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)
23 
24 #define AP_CAMERA_SERVO_ON_PWM 1300 // default PWM value to move servo to when shutter is activated
25 #define AP_CAMERA_SERVO_OFF_PWM 1100 // default PWM value to move servo to when shutter is deactivated
26 
27 #define AP_CAMERA_FEEDBACK_DEFAULT_FEEDBACK_PIN -1 // default is to not use camera feedback pin
28 
31 class AP_Camera {
32 
33 public:
34  AP_Camera(AP_Relay *obj_relay, uint32_t _log_camera_bit, const struct Location &_loc, const AP_AHRS &_ahrs)
35  : _trigger_counter(0) // count of number of cycles shutter has been held open
36  , _image_index(0)
37  , log_camera_bit(_log_camera_bit)
38  , current_loc(_loc)
39  , ahrs(_ahrs)
40  {
42  _apm_relay = obj_relay;
43  }
44 
45  /* Do not allow copies */
46  AP_Camera(const AP_Camera &other) = delete;
47  AP_Camera &operator=(const AP_Camera&) = delete;
48 
49 
50  // MAVLink methods
51  void control_msg(const mavlink_message_t* msg);
52  void send_feedback(mavlink_channel_t chan);
53 
54  // Command processing
55  void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time);
56  // handle camera control
57  void control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id);
58 
59  // set camera trigger distance in a mission
60  void set_trigger_distance(uint32_t distance_m) { _trigg_dist.set(distance_m); }
61 
62  void take_picture();
63 
64  // Update - to be called periodically @at least 10Hz
65  void update();
66 
67  // update camera trigger - 50Hz
68  void update_trigger();
69 
70  static const struct AP_Param::GroupInfo var_info[];
71 
72  // set if vehicle is in AUTO mode
73  void set_is_auto_mode(bool enable) { _is_in_auto_mode = enable; }
74 
75 private:
76  AP_Int8 _trigger_type; // 0:Servo,1:Relay
77  AP_Int8 _trigger_duration; // duration in 10ths of a second that the camera shutter is held open
78  AP_Int8 _relay_on; // relay value to trigger camera
79  AP_Int16 _servo_on_pwm; // PWM value to move servo to when shutter is activated
80  AP_Int16 _servo_off_pwm; // PWM value to move servo to when shutter is deactivated
81  uint8_t _trigger_counter; // count of number of cycles shutter has been held open
82  AP_Relay *_apm_relay; // pointer to relay object from the base class Relay.
83  AP_Int8 _auto_mode_only; // if 1: trigger by distance only if in AUTO mode.
84  bool _is_in_auto_mode; // true if in AUTO mode
85 
86  void servo_pic(); // Servo operated camera
87  void relay_pic(); // basic relay activation
88  void feedback_pin_timer();
89  void setup_feedback_callback(void);
90 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
91  static void capture_callback(void *context, uint32_t chan_index,
92  hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow);
93 #endif
94 
95  AP_Float _trigg_dist; // distance between trigger points (meters)
96  AP_Int16 _min_interval; // Minimum time between shots required by camera
97  AP_Int16 _max_roll; // Maximum acceptable roll angle when trigging camera
98  uint32_t _last_photo_time; // last time a photo was taken
100  uint16_t _image_index; // number of pictures taken since boot
101  uint16_t _feedback_events; // number of feedback events since boot
102 
103  // pin number for accurate camera feedback messages
104  AP_Int8 _feedback_pin;
106 
107  // this is set to 1 when camera trigger pin has fired
108  static volatile bool _camera_triggered;
111 
112  void log_picture();
113 
114  uint32_t log_camera_bit;
115  const struct Location &current_loc;
116  const AP_AHRS &ahrs;
117 
118  // entry point to trip local shutter (e.g. by relay or servo)
119  void trigger_pic();
120 
121  // de-activate the trigger after some delay, but without using a delay() function
122  // should be called at 50hz from main program
123  void trigger_pic_cleanup();
124 
125  // check if trigger pin has fired
126  bool check_trigger_pin(void);
127 
128  // return true if we are using a feedback pin
129  bool using_feedback_pin(void) const { return _feedback_pin > 0; }
130 
131 };
AP_Int16 _servo_on_pwm
Definition: AP_Camera.h:79
bool _timer_installed
Definition: AP_Camera.h:109
AP_Int16 _max_roll
Definition: AP_Camera.h:97
void trigger_pic()
Definition: AP_Camera.cpp:138
void control_msg(const mavlink_message_t *msg)
decode deprecated MavLink message that controls camera.
Definition: AP_Camera.cpp:181
uint8_t _last_pin_state
Definition: AP_Camera.h:110
Interface definition for the various Ground Control System.
static volatile bool _camera_triggered
Definition: AP_Camera.h:108
void feedback_pin_timer()
Definition: AP_Camera.cpp:312
AP_Int8 _relay_on
Definition: AP_Camera.h:78
AP_Int8 _auto_mode_only
Definition: AP_Camera.h:83
uint8_t _trigger_counter
Definition: AP_Camera.h:81
AP_Camera & operator=(const AP_Camera &)=delete
bool _is_in_auto_mode
Definition: AP_Camera.h:84
AP_Int8 _feedback_polarity
Definition: AP_Camera.h:105
AP_Int8 _feedback_pin
Definition: AP_Camera.h:104
struct Location _last_location
Definition: AP_Camera.h:99
A system for managing and storing variables that are of general interest to the system.
AP_Int8 _trigger_type
Definition: AP_Camera.h:76
AP_Int8 _trigger_duration
Definition: AP_Camera.h:77
uint16_t _feedback_events
Definition: AP_Camera.h:101
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Camera.h:70
AP_Camera(AP_Relay *obj_relay, uint32_t _log_camera_bit, const struct Location &_loc, const AP_AHRS &_ahrs)
Definition: AP_Camera.h:34
void take_picture()
Definition: AP_Camera.cpp:419
void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time)
Definition: AP_Camera.cpp:189
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
AP_Float _trigg_dist
Definition: AP_Camera.h:95
void update_trigger()
Definition: AP_Camera.cpp:440
static void capture_callback(void *context, uint32_t chan_index, hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow)
Definition: AP_Camera.cpp:349
uint32_t _last_photo_time
Definition: AP_Camera.h:98
bool check_trigger_pin(void)
Definition: AP_Camera.cpp:336
void send_feedback(mavlink_channel_t chan)
Definition: AP_Camera.cpp:243
bool using_feedback_pin(void) const
Definition: AP_Camera.h:129
void servo_pic()
Servo operated camera.
Definition: AP_Camera.cpp:114
AP_Int16 _min_interval
Definition: AP_Camera.h:96
void trigger_pic_cleanup()
Definition: AP_Camera.cpp:159
void relay_pic()
basic relay activation
Definition: AP_Camera.cpp:124
void log_picture()
Definition: AP_Camera.cpp:400
Common definitions and utility routines for the ArduPilot libraries.
Class to manage the ArduPilot relay.
Definition: AP_Relay.h:18
void set_trigger_distance(uint32_t distance_m)
Definition: AP_Camera.h:60
AP_Int16 _servo_off_pwm
Definition: AP_Camera.h:80
void update()
Definition: AP_Camera.cpp:267
AP_Relay * _apm_relay
Definition: AP_Camera.h:82
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
const AP_AHRS & ahrs
Definition: AP_Camera.h:116
uint32_t log_camera_bit
Definition: AP_Camera.h:114
void control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id)
Definition: AP_Camera.cpp:214
const struct Location & current_loc
Definition: AP_Camera.h:115
void set_is_auto_mode(bool enable)
Definition: AP_Camera.h:73
APM relay control class.
void setup_feedback_callback(void)
Definition: AP_Camera.cpp:360
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
uint16_t _image_index
Definition: AP_Camera.h:100