mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 10:38:28 -04:00
parent
33cbc0692a
commit
0e6213a4c6
@ -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) {
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user