From 5fd2decb2fe80d3cbf7b5fb40070fc1880a272b5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 14 Oct 2022 07:30:58 +1100 Subject: [PATCH] Copter: use Float16_t --- ArduCopter/mode_auto.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 3ae434f59a..07fbeed3f7 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -1648,8 +1648,8 @@ void ModeAuto::do_nav_script_time(const AP_Mission::Mission_Command& cmd) nav_scripting.start_ms = millis(); nav_scripting.command = cmd.content.nav_script_time.command; nav_scripting.timeout_s = cmd.content.nav_script_time.timeout_s; - nav_scripting.arg1 = cmd.content.nav_script_time.arg1; - nav_scripting.arg2 = cmd.content.nav_script_time.arg2; + nav_scripting.arg1 = cmd.content.nav_script_time.arg1.get(); + nav_scripting.arg2 = cmd.content.nav_script_time.arg2.get(); set_submode(SubMode::NAV_SCRIPT_TIME); } else { // for safety we set nav_scripting to done to protect against the mission getting stuck