mirror of https://github.com/ArduPilot/ardupilot
Plane: use Float16_t
This commit is contained in:
parent
5fd2decb2f
commit
2b69124229
|
@ -1205,8 +1205,8 @@ bool Plane::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2
|
||||||
const auto &c = mission.get_current_nav_cmd().content.nav_script_time;
|
const auto &c = mission.get_current_nav_cmd().content.nav_script_time;
|
||||||
id = nav_scripting.id;
|
id = nav_scripting.id;
|
||||||
cmd = c.command;
|
cmd = c.command;
|
||||||
arg1 = c.arg1;
|
arg1 = c.arg1.get();
|
||||||
arg2 = c.arg2;
|
arg2 = c.arg2.get();
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue