mirror of https://github.com/ArduPilot/ardupilot
AP_Vehicle: updated nav_script_time
This commit is contained in:
parent
f57935d406
commit
ce77be9599
|
@ -230,7 +230,7 @@ public:
|
|||
virtual bool set_desired_speed(float speed) { return false; }
|
||||
|
||||
// support for NAV_SCRIPT_TIME mission command
|
||||
virtual bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2) { return false; }
|
||||
virtual bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4) { return false; }
|
||||
virtual void nav_script_time_done(uint16_t id) {}
|
||||
|
||||
// allow for VTOL velocity matching of a target
|
||||
|
|
Loading…
Reference in New Issue