From a3005fe49c0b7465339f9cd93dde9fe9ab0abb7f Mon Sep 17 00:00:00 2001 From: bin Date: Mon, 1 Mar 2021 10:28:25 +0800 Subject: [PATCH] =?UTF-8?q?=E4=BF=AE=E5=A4=8Dcamera=E7=A9=BA=E6=8C=87?= =?UTF-8?q?=E9=92=88=E5=88=A4=E6=96=AD?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ArduCopter/mode_auto.cpp | 7 +++++-- modules/mavlink | 2 +- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 2f65d681d8..ea43f24445 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -1172,8 +1172,11 @@ Location ModeAuto::loc_from_cmd(const AP_Mission::Mission_Command& cmd) const void ModeAuto::do_nav_wp(const AP_Mission::Mission_Command& cmd) { Location target_loc = loc_from_cmd(cmd); - AP::camera()->cameras_take_enable = AP::camera()->cameras_take_enable_new; - AP::camera()->cameras_take_enable_new = cmd.content.location.cams_enable_bit; + AP_Camera *camera = AP::camera(); + if (camera != nullptr) { + camera->cameras_take_enable = AP::camera()->cameras_take_enable_new; + camera->cameras_take_enable_new = cmd.content.location.cams_enable_bit; + } //gcs().send_text(MAV_SEVERITY_INFO,"NOTICE:WP:%d,p3:%d",cmd.index,AP::camera()->cameras_take_enable_new); //TODO DEBUG!!! // this will be used to remember the time in millis after we reach or pass the WP. loiter_time = 0; diff --git a/modules/mavlink b/modules/mavlink index 18cab69509..0013b46db8 160000 --- a/modules/mavlink +++ b/modules/mavlink @@ -1 +1 @@ -Subproject commit 18cab6950986cd7b9b7a507ec35f3501d4a7e019 +Subproject commit 0013b46db8cb437b6ad77d736263597d90a2262d