Browse Source

AP_Camera: Option to trig by distance only when in AUTO mode

master
André Kjellstrup 7 years ago committed by Francisco Ferreira
parent
commit
1a63fd85d8
  1. 11
      libraries/AP_Camera/AP_Camera.cpp
  2. 5
      libraries/AP_Camera/AP_Camera.h

11
libraries/AP_Camera/AP_Camera.cpp

@ -92,6 +92,13 @@ const AP_Param::GroupInfo AP_Camera::var_info[] = { @@ -92,6 +92,13 @@ const AP_Param::GroupInfo AP_Camera::var_info[] = {
// @User: Standard
AP_GROUPINFO("FEEDBACK_POL", 9, AP_Camera, _feedback_polarity, 1),
// @Param: AUTO_ONLY
// @DisplayName: Distance-trigging in AUTO mode only
// @Description: When enabled, trigging by distance is done in AUTO mode only.
// @Values: 0:Always,1:Only when in AUTO
// @User: Standard
AP_GROUPINFO("AUTO_ONLY", 10, AP_Camera, _auto_mode_only, 0),
AP_GROUPEND
};
@ -283,6 +290,10 @@ void AP_Camera::update() @@ -283,6 +290,10 @@ void AP_Camera::update()
return;
}
if (_is_in_auto_mode != true && _auto_mode_only != 0) {
return;
}
uint32_t tnow = AP_HAL::millis();
if (tnow - _last_photo_time < (unsigned) _min_interval) {
return;

5
libraries/AP_Camera/AP_Camera.h

@ -68,6 +68,9 @@ public: @@ -68,6 +68,9 @@ public:
static const struct AP_Param::GroupInfo var_info[];
// set if vehicle is in AUTO mode
void set_is_auto_mode(bool enable) { _is_in_auto_mode = enable; }
private:
AP_Camera(AP_Relay *obj_relay, uint32_t _log_camera_bit, const struct Location &_loc, const AP_GPS &_gps, const AP_AHRS &_ahrs)
: _trigger_counter(0) // count of number of cycles shutter has been held open
@ -88,6 +91,8 @@ private: @@ -88,6 +91,8 @@ 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
AP_Relay *_apm_relay; // pointer to relay object from the base class Relay.
AP_Int8 _auto_mode_only; // if 1: trigger by distance only if in AUTO mode.
bool _is_in_auto_mode; // true if in AUTO mode
void servo_pic(); // Servo operated camera
void relay_pic(); // basic relay activation

Loading…
Cancel
Save