Camera: Track number of completed events

Closes #3903
This commit is contained in:
Michael du Breuil 2018-03-05 12:02:19 -07:00 committed by Francisco Ferreira
parent 33cbc0692a
commit 0e6213a4c6
2 changed files with 3 additions and 1 deletions

View File

@ -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) {

View File

@ -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;