mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_Camera: don't use stale image number in CAMERA_FEEDBACK
This commit is contained in:
parent
8f1c255693
commit
1835a63bfb
@ -344,7 +344,8 @@ void AP_Camera::send_feedback(mavlink_channel_t chan) const
|
|||||||
feedback.roll_sensor*1e-2f,
|
feedback.roll_sensor*1e-2f,
|
||||||
feedback.pitch_sensor*1e-2f,
|
feedback.pitch_sensor*1e-2f,
|
||||||
feedback.yaw_sensor*1e-2f,
|
feedback.yaw_sensor*1e-2f,
|
||||||
0.0f, CAMERA_FEEDBACK_PHOTO, _camera_trigger_logged);
|
0.0f, CAMERA_FEEDBACK_PHOTO,
|
||||||
|
feedback.camera_trigger_logged);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -508,6 +509,7 @@ void AP_Camera::prep_mavlink_msg_camera_feedback(uint64_t timestamp_us)
|
|||||||
feedback.roll_sensor = ahrs.roll_sensor;
|
feedback.roll_sensor = ahrs.roll_sensor;
|
||||||
feedback.pitch_sensor = ahrs.pitch_sensor;
|
feedback.pitch_sensor = ahrs.pitch_sensor;
|
||||||
feedback.yaw_sensor = ahrs.yaw_sensor;
|
feedback.yaw_sensor = ahrs.yaw_sensor;
|
||||||
|
feedback.camera_trigger_logged = _camera_trigger_logged;
|
||||||
|
|
||||||
gcs().send_message(MSG_CAMERA_FEEDBACK);
|
gcs().send_message(MSG_CAMERA_FEEDBACK);
|
||||||
}
|
}
|
||||||
|
@ -123,6 +123,7 @@ private:
|
|||||||
int32_t roll_sensor;
|
int32_t roll_sensor;
|
||||||
int32_t pitch_sensor;
|
int32_t pitch_sensor;
|
||||||
int32_t yaw_sensor;
|
int32_t yaw_sensor;
|
||||||
|
uint32_t camera_trigger_logged; // ID sequence number
|
||||||
} feedback;
|
} feedback;
|
||||||
void prep_mavlink_msg_camera_feedback(uint64_t timestamp_us);
|
void prep_mavlink_msg_camera_feedback(uint64_t timestamp_us);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user