APM:Libraries
AP_Camera.cpp
Go to the documentation of this file.
1 #include "AP_Camera.h"
2 #include <AP_Relay/AP_Relay.h>
3 #include <AP_Math/AP_Math.h>
5 #include <AP_HAL/AP_HAL.h>
6 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
7 #include <drivers/drv_input_capture.h>
8 #include <drivers/drv_pwm_output.h>
9 #include <sys/types.h>
10 #include <sys/stat.h>
11 #include <fcntl.h>
12 #include <unistd.h>
13 #endif
14 
15 // ------------------------------
16 #define CAM_DEBUG DISABLED
17 
19  // @Param: TRIGG_TYPE
20  // @DisplayName: Camera shutter (trigger) type
21  // @Description: how to trigger the camera to take a picture
22  // @Values: 0:Servo,1:Relay
23  // @User: Standard
24  AP_GROUPINFO("TRIGG_TYPE", 0, AP_Camera, _trigger_type, AP_CAMERA_TRIGGER_DEFAULT_TRIGGER_TYPE),
25 
26  // @Param: DURATION
27  // @DisplayName: Duration that shutter is held open
28  // @Description: How long the shutter will be held open in 10ths of a second (i.e. enter 10 for 1second, 50 for 5seconds)
29  // @Units: ds
30  // @Range: 0 50
31  // @User: Standard
32  AP_GROUPINFO("DURATION", 1, AP_Camera, _trigger_duration, AP_CAMERA_TRIGGER_DEFAULT_DURATION),
33 
34  // @Param: SERVO_ON
35  // @DisplayName: Servo ON PWM value
36  // @Description: PWM value in microseconds to move servo to when shutter is activated
37  // @Units: PWM
38  // @Range: 1000 2000
39  // @User: Standard
40  AP_GROUPINFO("SERVO_ON", 2, AP_Camera, _servo_on_pwm, AP_CAMERA_SERVO_ON_PWM),
41 
42  // @Param: SERVO_OFF
43  // @DisplayName: Servo OFF PWM value
44  // @Description: PWM value in microseconds to move servo to when shutter is deactivated
45  // @Units: PWM
46  // @Range: 1000 2000
47  // @User: Standard
48  AP_GROUPINFO("SERVO_OFF", 3, AP_Camera, _servo_off_pwm, AP_CAMERA_SERVO_OFF_PWM),
49 
50  // @Param: TRIGG_DIST
51  // @DisplayName: Camera trigger distance
52  // @Description: Distance in meters between camera triggers. If this value is non-zero then the camera will trigger whenever the GPS position changes by this number of meters regardless of what mode the APM is in. Note that this parameter can also be set in an auto mission using the DO_SET_CAM_TRIGG_DIST command, allowing you to enable/disable the triggering of the camera during the flight.
53  // @User: Standard
54  // @Units: m
55  // @Range: 0 1000
56  AP_GROUPINFO("TRIGG_DIST", 4, AP_Camera, _trigg_dist, 0),
57 
58  // @Param: RELAY_ON
59  // @DisplayName: Relay ON value
60  // @Description: This sets whether the relay goes high or low when it triggers. Note that you should also set RELAY_DEFAULT appropriately for your camera
61  // @Values: 0:Low,1:High
62  // @User: Standard
63  AP_GROUPINFO("RELAY_ON", 5, AP_Camera, _relay_on, 1),
64 
65  // @Param: MIN_INTERVAL
66  // @DisplayName: Minimum time between photos
67  // @Description: Postpone shooting if previous picture was taken less than preset time(ms) ago.
68  // @User: Standard
69  // @Units: ms
70  // @Range: 0 10000
71  AP_GROUPINFO("MIN_INTERVAL", 6, AP_Camera, _min_interval, 0),
72 
73  // @Param: MAX_ROLL
74  // @DisplayName: Maximum photo roll angle.
75  // @Description: Postpone shooting if roll is greater than limit. (0=Disable, will shoot regardless of roll).
76  // @User: Standard
77  // @Units: deg
78  // @Range: 0 180
79  AP_GROUPINFO("MAX_ROLL", 7, AP_Camera, _max_roll, 0),
80 
81  // @Param: FEEDBACK_PIN
82  // @DisplayName: Camera feedback pin
83  // @Description: pin number to use for save accurate camera feedback messages. If set to -1 then don't use a pin flag for this, otherwise this is a pin number which if held high after a picture trigger order, will save camera messages when camera really takes a picture. A universal camera hot shoe is needed. The pin should be held high for at least 2 milliseconds for reliable trigger detection. See also the CAM_FEEDBACK_POL option. If using AUX4 pin on a Pixhawk then a fast capture method is used that allows for the trigger time to be as short as one microsecond.
84  // @Values: -1:Disabled,50:PX4 AUX1,51:PX4 AUX2,52:PX4 AUX3,53:PX4 AUX4(fast capture),54:PX4 AUX5,55:PX4 AUX6
85  // @User: Standard
86  AP_GROUPINFO("FEEDBACK_PIN", 8, AP_Camera, _feedback_pin, AP_CAMERA_FEEDBACK_DEFAULT_FEEDBACK_PIN),
87 
88  // @Param: FEEDBACK_POL
89  // @DisplayName: Camera feedback pin polarity
90  // @Description: Polarity for feedback pin. If this is 1 then the feedback pin should go high on trigger. If set to 0 then it should go low
91  // @Values: 0:TriggerLow,1:TriggerHigh
92  // @User: Standard
93  AP_GROUPINFO("FEEDBACK_POL", 9, AP_Camera, _feedback_polarity, 1),
94 
95  // @Param: AUTO_ONLY
96  // @DisplayName: Distance-trigging in AUTO mode only
97  // @Description: When enabled, trigging by distance is done in AUTO mode only.
98  // @Values: 0:Always,1:Only when in AUTO
99  // @User: Standard
100  AP_GROUPINFO("AUTO_ONLY", 10, AP_Camera, _auto_mode_only, 0),
101 
103 };
104 
105 extern const AP_HAL::HAL& hal;
106 
107 /*
108  static trigger var for PX4 callback
109  */
110 volatile bool AP_Camera::_camera_triggered;
111 
113 void
115 {
117 
118  // leave a message that it should be active for this many loops (assumes 50hz loops)
120 }
121 
123 void
125 {
126  if (_relay_on) {
127  _apm_relay->on(0);
128  } else {
129  _apm_relay->off(0);
130  }
131 
132  // leave a message that it should be active for this many loops (assumes 50hz loops)
134 }
135 
139 {
141 
142  _image_index++;
143  switch (_trigger_type)
144  {
146  servo_pic(); // Servo operated camera
147  break;
149  relay_pic(); // basic relay activation
150  break;
151  }
152 
153  log_picture();
154 }
155 
158 void
160 {
161  if (_trigger_counter) {
163  } else {
164  switch (_trigger_type) {
167  break;
169  if (_relay_on) {
170  _apm_relay->off(0);
171  } else {
172  _apm_relay->on(0);
173  }
174  break;
175  }
176  }
177 }
178 
180 void
181 AP_Camera::control_msg(const mavlink_message_t* msg)
182 {
183  __mavlink_digicam_control_t packet;
184  mavlink_msg_digicam_control_decode(msg, &packet);
185 
186  control(packet.session, packet.zoom_pos, packet.zoom_step, packet.focus_lock, packet.shot, packet.command_id);
187 }
188 
189 void AP_Camera::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time)
190 {
191  // we cannot process the configure command so convert to mavlink message
192  // and send to all components in case they and process it
193 
194  mavlink_message_t msg;
195  mavlink_command_long_t mav_cmd_long = {};
196 
197  // convert mission command to mavlink command_long
198  mav_cmd_long.command = MAV_CMD_DO_DIGICAM_CONFIGURE;
199  mav_cmd_long.param1 = shooting_mode;
200  mav_cmd_long.param2 = shutter_speed;
201  mav_cmd_long.param3 = aperture;
202  mav_cmd_long.param4 = ISO;
203  mav_cmd_long.param5 = exposure_type;
204  mav_cmd_long.param6 = cmd_id;
205  mav_cmd_long.param7 = engine_cutoff_time;
206 
207  // Encode Command long into MAVLINK msg
208  mavlink_msg_command_long_encode(0, 0, &msg, &mav_cmd_long);
209 
210  // send to all components
212 }
213 
214 void AP_Camera::control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id)
215 {
216  // take picture
217  if (is_equal(shooting_cmd,1.0f)) {
218  trigger_pic();
219  }
220 
221  mavlink_message_t msg;
222  mavlink_command_long_t mav_cmd_long = {};
223 
224  // convert command to mavlink command long
225  mav_cmd_long.command = MAV_CMD_DO_DIGICAM_CONTROL;
226  mav_cmd_long.param1 = session;
227  mav_cmd_long.param2 = zoom_pos;
228  mav_cmd_long.param3 = zoom_step;
229  mav_cmd_long.param4 = focus_lock;
230  mav_cmd_long.param5 = shooting_cmd;
231  mav_cmd_long.param6 = cmd_id;
232 
233  // Encode Command long into MAVLINK msg
234  mavlink_msg_command_long_encode(0, 0, &msg, &mav_cmd_long);
235 
236  // send to all components
238 }
239 
240 /*
241  Send camera feedback to the GCS
242  */
243 void AP_Camera::send_feedback(mavlink_channel_t chan)
244 {
245  float altitude, altitude_rel;
247  altitude = current_loc.alt+ahrs.get_home().alt;
248  altitude_rel = current_loc.alt;
249  } else {
250  altitude = current_loc.alt;
251  altitude_rel = current_loc.alt - ahrs.get_home().alt;
252  }
253 
254  mavlink_msg_camera_feedback_send(
255  chan,
256  AP::gps().time_epoch_usec(),
257  0, 0, _image_index,
259  altitude*1e-2, altitude_rel*1e-2,
260  ahrs.roll_sensor*1e-2, ahrs.pitch_sensor*1e-2, ahrs.yaw_sensor*1e-2,
261  0.0f, CAMERA_FEEDBACK_PHOTO, _feedback_events);
262 }
263 
264 
265 /* update; triggers by distance moved
266 */
268 {
269  if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {
270  return;
271  }
272 
273  if (is_zero(_trigg_dist)) {
274  return;
275  }
276  if (_last_location.lat == 0 && _last_location.lng == 0) {
278  return;
279  }
281  // we haven't moved - this can happen as update() may
282  // be called without a new GPS fix
283  return;
284  }
285 
287  return;
288  }
289 
290  if (_max_roll > 0 && labs(ahrs.roll_sensor*1e-2) > _max_roll) {
291  return;
292  }
293 
294  if (_is_in_auto_mode != true && _auto_mode_only != 0) {
295  return;
296  }
297 
298  uint32_t tnow = AP_HAL::millis();
299  if (tnow - _last_photo_time < (unsigned) _min_interval) {
300  return;
301  }
302 
303  take_picture();
304 
306  _last_photo_time = tnow;
307 }
308 
309 /*
310  check if feedback pin is high
311  */
313 {
314  int8_t dpin = hal.gpio->analogPinToDigitalPin(_feedback_pin);
315  if (dpin == -1) {
316  return;
317  }
318  // ensure we are in input mode
319  hal.gpio->pinMode(dpin, HAL_GPIO_INPUT);
320 
321  // enable pullup
322  hal.gpio->write(dpin, 1);
323 
324  uint8_t pin_state = hal.gpio->read(dpin);
325  uint8_t trigger_polarity = _feedback_polarity==0?0:1;
326  if (pin_state == trigger_polarity &&
327  _last_pin_state != trigger_polarity) {
328  _camera_triggered = true;
329  }
330  _last_pin_state = pin_state;
331 }
332 
333 /*
334  check if camera has triggered
335  */
337 {
338  if (_camera_triggered) {
339  _camera_triggered = false;
340  return true;
341  }
342  return false;
343 }
344 
345 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
346 /*
347  callback for timer capture on PX4
348  */
349 void AP_Camera::capture_callback(void *context, uint32_t chan_index,
350  hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow)
351 {
352  _camera_triggered = true;
353 }
354 #endif
355 
356 /*
357  setup a callback for a feedback pin. When on PX4 with the right FMU
358  mode we can use the microsecond timer.
359  */
361 {
362  if (_feedback_pin <= 0 || _timer_installed) {
363  // invalid or already installed
364  return;
365  }
366 
367 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
368  /*
369  special case for pin 53 on PX4. We can use the fast timer support
370  */
371  if (_feedback_pin == 53) {
372  int fd = open("/dev/px4fmu", 0);
373  if (fd != -1) {
374  if (ioctl(fd, PWM_SERVO_SET_MODE, PWM_SERVO_MODE_3PWM1CAP) != 0) {
375  gcs().send_text(MAV_SEVERITY_WARNING, "Camera: unable to setup 3PWM1CAP");
376  close(fd);
377  goto failed;
378  }
379  if (up_input_capture_set(3, _feedback_polarity==1?Rising:Falling, 0, capture_callback, this) != 0) {
380  gcs().send_text(MAV_SEVERITY_WARNING, "Camera: unable to setup timer capture");
381  close(fd);
382  goto failed;
383  }
384  close(fd);
385  _timer_installed = true;
386  gcs().send_text(MAV_SEVERITY_WARNING, "Camera: setup fast trigger capture");
387  }
388  }
389 failed:
390 #endif // CONFIG_HAL_BOARD
391 
392  if (!_timer_installed) {
393  // install a 1kHz timer to check feedback pin
395  }
396  _timer_installed = true;
397 }
398 
399 // log_picture - log picture taken and send feedback to GCS
401 {
403  if (df == nullptr) {
404  return;
405  }
406  if (!using_feedback_pin()) {
408  if (df->should_log(log_camera_bit)) {
410  }
411  } else {
412  if (df->should_log(log_camera_bit)) {
414  }
415  }
416 }
417 
418 // take_picture - take a picture
420 {
421  // take a local picture:
422  trigger_pic();
423 
424  // tell all of our components to take a picture:
425  mavlink_command_long_t cmd_msg;
426  memset(&cmd_msg, 0, sizeof(cmd_msg));
427  cmd_msg.command = MAV_CMD_DO_DIGICAM_CONTROL;
428  cmd_msg.param5 = 1;
429  // create message
430  mavlink_message_t msg;
431  mavlink_msg_command_long_encode(0, 0, &msg, &cmd_msg);
432 
433  // forward to all components
435 }
436 
437 /*
438  update camera trigger - 50Hz
439  */
441 {
443  if (check_trigger_pin()) {
447  if (df != nullptr) {
448  if (df->should_log(log_camera_bit)) {
450  }
451  }
452  }
453 }
AP_Int16 _servo_on_pwm
Definition: AP_Camera.h:79
bool _timer_installed
Definition: AP_Camera.h:109
virtual int8_t analogPinToDigitalPin(uint8_t pin)=0
void Log_Write_Trigger(const AP_AHRS &ahrs, const Location &current_loc)
Definition: LogFile.cpp:1354
AP_Int16 _max_roll
Definition: AP_Camera.h:97
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
void trigger_pic()
Definition: AP_Camera.cpp:138
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
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
static volatile bool _camera_triggered
Definition: AP_Camera.h:108
bool should_log(uint32_t mask) const
Definition: DataFlash.cpp:416
const struct Location & get_home(void) const
Definition: AP_AHRS.h:435
void feedback_pin_timer()
Definition: AP_Camera.cpp:312
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
float get_distance(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:36
AP_Int8 _relay_on
Definition: AP_Camera.h:78
void off(uint8_t relay)
Definition: AP_Relay.cpp:127
GCS & gcs()
AP_Int8 _auto_mode_only
Definition: AP_Camera.h:83
uint8_t _trigger_counter
Definition: AP_Camera.h:81
#define AP_CAMERA_TRIGGER_DEFAULT_TRIGGER_TYPE
Definition: AP_Camera.h:20
bool _is_in_auto_mode
Definition: AP_Camera.h:84
virtual void write(uint8_t pin, uint8_t value)=0
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
int32_t roll_sensor
Definition: AP_AHRS.h:229
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
void on(uint8_t relay)
Definition: AP_Relay.cpp:118
void send_message(enum ap_message id)
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
#define AP_CAMERA_SERVO_OFF_PWM
Definition: AP_Camera.h:25
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
int32_t pitch_sensor
Definition: AP_AHRS.h:230
RC_Channel manager, with EEPROM-backed storage of constants.
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Camera.h:70
void Log_Write_Camera(const AP_AHRS &ahrs, const Location &current_loc)
Definition: LogFile.cpp:1348
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
static void set_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t value)
uint32_t millis()
Definition: system.cpp:157
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
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
AP_Float _trigg_dist
Definition: AP_Camera.h:95
void update_trigger()
Definition: AP_Camera.cpp:440
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
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
virtual void pinMode(uint8_t pin, uint8_t output)=0
uint32_t _last_photo_time
Definition: AP_Camera.h:98
bool check_trigger_pin(void)
Definition: AP_Camera.cpp:336
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
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
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
Definition: AP_Common.h:135
AP_Int16 _min_interval
Definition: AP_Camera.h:96
#define HAL_GPIO_INPUT
Definition: GPIO.h:7
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
#define AP_CAMERA_TRIGGER_TYPE_RELAY
Definition: AP_Camera.h:18
virtual void register_timer_process(AP_HAL::MemberProc)=0
virtual uint8_t read(uint8_t pin)=0
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
#define AP_CAMERA_FEEDBACK_DEFAULT_FEEDBACK_PIN
Definition: AP_Camera.h:27
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Definition: AP_Math.cpp:12
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
AP_HAL::GPIO * gpio
Definition: HAL.h:111
#define AP_CAMERA_TRIGGER_DEFAULT_DURATION
Definition: AP_Camera.h:22
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
const AP_AHRS & ahrs
Definition: AP_Camera.h:116
uint32_t log_camera_bit
Definition: AP_Camera.h:114
#define AP_CAMERA_TRIGGER_TYPE_SERVO
Definition: AP_Camera.h:17
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
#define AP_CAMERA_SERVO_ON_PWM
Definition: AP_Camera.h:24
void control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id)
Definition: AP_Camera.cpp:214
int32_t yaw_sensor
Definition: AP_AHRS.h:231
const struct Location & current_loc
Definition: AP_Camera.h:115
Photo or video camera manager, with EEPROM-backed storage of constants.
#define AP_GROUPEND
Definition: AP_Param.h:121
APM relay control class.
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
void setup_feedback_callback(void)
Definition: AP_Camera.cpp:360
uint16_t _image_index
Definition: AP_Camera.h:100