|
|
|
@ -2,7 +2,6 @@
@@ -2,7 +2,6 @@
|
|
|
|
|
|
|
|
|
|
/// @file AP_Camera.h
|
|
|
|
|
/// @brief Photo or video camera manager, with EEPROM-backed storage of constants.
|
|
|
|
|
/// @author Amilcar Lucas
|
|
|
|
|
|
|
|
|
|
#ifndef AP_CAMERA_H |
|
|
|
|
#define AP_CAMERA_H |
|
|
|
@ -10,6 +9,7 @@
@@ -10,6 +9,7 @@
|
|
|
|
|
#include <AP_Param.h> |
|
|
|
|
#include <AP_Common.h> |
|
|
|
|
#include <GCS_MAVLink.h> |
|
|
|
|
#include <AP_Relay.h> |
|
|
|
|
|
|
|
|
|
#define AP_CAMERA_TRIGGER_TYPE_SERVO 0 |
|
|
|
|
#define AP_CAMERA_TRIGGER_TYPE_RELAY 1 |
|
|
|
@ -35,11 +35,12 @@ class AP_Camera {
@@ -35,11 +35,12 @@ class AP_Camera {
|
|
|
|
|
public: |
|
|
|
|
/// Constructor
|
|
|
|
|
///
|
|
|
|
|
AP_Camera() : |
|
|
|
|
AP_Camera(AP_Relay *obj_relay) : |
|
|
|
|
_trigger_counter(0), // count of number of cycles shutter has been held open
|
|
|
|
|
_thr_pic_counter(0) // timer variable for throttle_pic
|
|
|
|
|
{ |
|
|
|
|
AP_Param::setup_object_defaults(this, var_info); |
|
|
|
|
_apm_relay = obj_relay; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// single entry point to take pictures
|
|
|
|
@ -62,6 +63,7 @@ private:
@@ -62,6 +63,7 @@ private:
|
|
|
|
|
AP_Int16 _servo_off_pwm; // PWM value to move servo to when shutter is deactivated
|
|
|
|
|
uint8_t _trigger_counter; // count of number of cycles shutter has been held open
|
|
|
|
|
uint8_t _thr_pic_counter; // timer variable for throttle_pic
|
|
|
|
|
AP_Relay *_apm_relay; // pointer to relay object from the base class Relay. The subclasses could be AP_Relay_APM1 or AP_Relay_APM2
|
|
|
|
|
|
|
|
|
|
void servo_pic(); // Servo operated camera
|
|
|
|
|
void relay_pic(); // basic relay activation
|
|
|
|
|