Plane: two more arguments to NAV_SCRIPT_TIME

This commit is contained in:
Andrew Tridgell 2022-10-14 11:37:52 +11:00
parent 8c4732210c
commit 90459ed6f4
2 changed files with 4 additions and 2 deletions

View File

@ -1128,7 +1128,7 @@ private:
#if AP_SCRIPTING_ENABLED
// support for NAV_SCRIPT_TIME mission command
bool nav_scripting_active(void) const;
bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2) override;
bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4) override;
void nav_script_time_done(uint16_t id) override;
// command throttle percentage and roll, pitch, yaw target

View File

@ -1196,7 +1196,7 @@ bool Plane::nav_scripting_active(void) const
}
// support for NAV_SCRIPTING mission command
bool Plane::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2)
bool Plane::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4)
{
if (!nav_scripting_active()) {
// not in NAV_SCRIPT_TIME
@ -1207,6 +1207,8 @@ bool Plane::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2
cmd = c.command;
arg1 = c.arg1.get();
arg2 = c.arg2.get();
arg3 = c.arg3;
arg4 = c.arg4;
return true;
}