mavlink : send camera_image_captured message

This commit is contained in:
Mohammed Kabir
2017-05-04 11:16:53 +02:00
committed by Lorenz Meier
parent b665737aca
commit 192e8b48d1
2 changed files with 3 additions and 1 deletions
+2
View File
@@ -2042,6 +2042,7 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("CAMERA_CAPTURE", 2.0f);
//camera trigger is rate limited at the source, do not limit here
configure_stream("CAMERA_TRIGGER", 500.0f);
configure_stream("CAMERA_IMAGE_CAPTURED", 5.0f);
configure_stream("ACTUATOR_CONTROL_TARGET0", 10.0f);
break;
@@ -2094,6 +2095,7 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("VFR_HUD", 20.0f);
configure_stream("WIND_COV", 10.0f);
configure_stream("CAMERA_TRIGGER", 500.0f);
configure_stream("CAMERA_IMAGE_CAPTURED", 5.0f);
configure_stream("MISSION_ITEM", 50.0f);
configure_stream("ACTUATOR_CONTROL_TARGET0", 30.0f);
configure_stream("MANUAL_CONTROL", 5.0f);
+1 -1
View File
@@ -1544,7 +1544,7 @@ protected:
msg.lat = capture.lat * 1e7;
msg.lon = capture.lon * 1e7;
msg.alt = capture.alt * 1e3f;
msg.relative_alt = capture.relative_alt * 1e3f;
msg.relative_alt = capture.ground_distance * 1e3f;
msg.q[0] = capture.q[0];
msg.q[1] = capture.q[1];
msg.q[2] = capture.q[2];