From 0e6213a4c6f4756f21bf2e3d18aee2283acfa386 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Mon, 5 Mar 2018 12:02:19 -0700 Subject: [PATCH] Camera: Track number of completed events Closes #3903 --- libraries/AP_Camera/AP_Camera.cpp | 3 ++- libraries/AP_Camera/AP_Camera.h | 1 + 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index 957340369f..eda7c2515e 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -258,7 +258,7 @@ void AP_Camera::send_feedback(mavlink_channel_t chan) current_loc.lat, current_loc.lng, altitude*1e-2, altitude_rel*1e-2, ahrs.roll_sensor*1e-2, ahrs.pitch_sensor*1e-2, ahrs.yaw_sensor*1e-2, - 0.0f,CAMERA_FEEDBACK_PHOTO); + 0.0f, CAMERA_FEEDBACK_PHOTO, _feedback_events); } @@ -441,6 +441,7 @@ void AP_Camera::update_trigger() { trigger_pic_cleanup(); if (check_trigger_pin()) { + _feedback_events++; gcs().send_message(MSG_CAMERA_FEEDBACK); DataFlash_Class *df = DataFlash_Class::instance(); if (df != nullptr) { diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 59c7f45ace..b2d302db7b 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -98,6 +98,7 @@ private: uint32_t _last_photo_time; // last time a photo was taken struct Location _last_location; uint16_t _image_index; // number of pictures taken since boot + uint16_t _feedback_events; // number of feedback events since boot // pin number for accurate camera feedback messages AP_Int8 _feedback_pin;