Copter: two more arguments to NAV_SCRIPT_TIME

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

View File

@ -411,13 +411,13 @@ bool Copter::nav_scripting_enable(uint8_t mode)
} }
// lua scripts use this to retrieve the contents of the active command // lua scripts use this to retrieve the contents of the active command
bool Copter::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2) bool Copter::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4)
{ {
if (flightmode != &mode_auto) { if (flightmode != &mode_auto) {
return false; return false;
} }
return mode_auto.nav_script_time(id, cmd, arg1, arg2); return mode_auto.nav_script_time(id, cmd, arg1, arg2, arg3, arg4);
} }
// lua scripts use this to indicate when they have complete the command // lua scripts use this to indicate when they have complete the command

View File

@ -663,7 +663,7 @@ private:
bool set_circle_rate(float rate_dps) override; bool set_circle_rate(float rate_dps) override;
bool set_desired_speed(float speed) override; bool set_desired_speed(float speed) override;
bool nav_scripting_enable(uint8_t mode) override; bool nav_scripting_enable(uint8_t mode) override;
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; void nav_script_time_done(uint16_t id) override;
// lua scripts use this to retrieve EKF failsafe state // lua scripts use this to retrieve EKF failsafe state
// returns true if the EKF failsafe has triggered // returns true if the EKF failsafe has triggered

View File

@ -468,7 +468,7 @@ public:
bool jump_to_landing_sequence_auto_RTL(ModeReason reason); bool jump_to_landing_sequence_auto_RTL(ModeReason reason);
// lua accessors for nav script time support // lua accessors for nav script time support
bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2); bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4);
void nav_script_time_done(uint16_t id); void nav_script_time_done(uint16_t id);
AP_Mission mission{ AP_Mission mission{
@ -634,6 +634,8 @@ private:
uint8_t timeout_s; // timeout (in seconds) provided by mission command uint8_t timeout_s; // timeout (in seconds) provided by mission command
float arg1; // 1st argument provided by mission command float arg1; // 1st argument provided by mission command
float arg2; // 2nd argument provided by mission command float arg2; // 2nd argument provided by mission command
int16_t arg3; // 3rd argument provided by mission command
int16_t arg4; // 4th argument provided by mission command
} nav_scripting; } nav_scripting;
#endif #endif

View File

@ -233,7 +233,7 @@ bool ModeAuto::jump_to_landing_sequence_auto_RTL(ModeReason reason)
} }
// lua scripts use this to retrieve the contents of the active command // lua scripts use this to retrieve the contents of the active command
bool ModeAuto::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2) bool ModeAuto::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4)
{ {
#if AP_SCRIPTING_ENABLED #if AP_SCRIPTING_ENABLED
if (_mode == SubMode::NAV_SCRIPT_TIME) { if (_mode == SubMode::NAV_SCRIPT_TIME) {
@ -241,6 +241,8 @@ bool ModeAuto::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &a
cmd = nav_scripting.command; cmd = nav_scripting.command;
arg1 = nav_scripting.arg1; arg1 = nav_scripting.arg1;
arg2 = nav_scripting.arg2; arg2 = nav_scripting.arg2;
arg3 = nav_scripting.arg3;
arg4 = nav_scripting.arg4;
return true; return true;
} }
#endif #endif
@ -1650,6 +1652,8 @@ void ModeAuto::do_nav_script_time(const AP_Mission::Mission_Command& cmd)
nav_scripting.timeout_s = cmd.content.nav_script_time.timeout_s; nav_scripting.timeout_s = cmd.content.nav_script_time.timeout_s;
nav_scripting.arg1 = cmd.content.nav_script_time.arg1.get(); nav_scripting.arg1 = cmd.content.nav_script_time.arg1.get();
nav_scripting.arg2 = cmd.content.nav_script_time.arg2.get(); nav_scripting.arg2 = cmd.content.nav_script_time.arg2.get();
nav_scripting.arg3 = cmd.content.nav_script_time.arg3;
nav_scripting.arg4 = cmd.content.nav_script_time.arg4;
set_submode(SubMode::NAV_SCRIPT_TIME); set_submode(SubMode::NAV_SCRIPT_TIME);
} else { } else {
// for safety we set nav_scripting to done to protect against the mission getting stuck // for safety we set nav_scripting to done to protect against the mission getting stuck