mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Vehicle: Bindings for crosstrack in Lua
This commit is contained in:
parent
8a93c6a264
commit
c2a5554e9f
@ -223,7 +223,11 @@ public:
|
|||||||
|
|
||||||
// allow for landing descent rate to be overridden by a script, may be -ve to climb
|
// allow for landing descent rate to be overridden by a script, may be -ve to climb
|
||||||
virtual bool set_land_descent_rate(float descent_rate) { return false; }
|
virtual bool set_land_descent_rate(float descent_rate) { return false; }
|
||||||
|
|
||||||
|
// Allow for scripting to have control over the crosstracking when exiting and resuming missions or guided flight
|
||||||
|
// It's up to the Lua script to ensure the provided location makes sense
|
||||||
|
virtual bool set_crosstrack_start(const Location &new_start_location) { return false; }
|
||||||
|
|
||||||
// control outputs enumeration
|
// control outputs enumeration
|
||||||
enum class ControlOutput {
|
enum class ControlOutput {
|
||||||
Roll = 1,
|
Roll = 1,
|
||||||
|
Loading…
Reference in New Issue
Block a user