|
|
|
@ -258,7 +258,7 @@ void AP_Camera::send_feedback(mavlink_channel_t chan)
@@ -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()
@@ -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) { |
|
|
|
|