Browse Source

mavlink: CAMERA_IMAGE_CAPTURED stream check free tx buf before send

release/1.12
Daniel Agar 4 years ago committed by Lorenz Meier
parent
commit
ae706537b8
  1. 3
      src/modules/mavlink/mavlink_messages.cpp

3
src/modules/mavlink/mavlink_messages.cpp

@ -2254,8 +2254,7 @@ protected: @@ -2254,8 +2254,7 @@ protected:
{
camera_capture_s capture;
if (_capture_sub.update(&capture)) {
if ((_mavlink->get_free_tx_buf() >= get_size()) && _capture_sub.update(&capture)) {
mavlink_camera_image_captured_t msg{};
msg.time_boot_ms = capture.timestamp / 1000;

Loading…
Cancel
Save