mirror of https://github.com/ArduPilot/ardupilot
Copter: use Float16_t
This commit is contained in:
parent
cc39bd08be
commit
5fd2decb2f
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue