ArduPlane: Bindings for crosstrack in Lua

This commit is contained in:
timtuxworth 2024-08-01 09:50:59 -06:00 committed by Andrew Tridgell
parent b811791863
commit f63568b34b
2 changed files with 15 additions and 0 deletions

View File

@ -908,6 +908,16 @@ bool Plane::set_land_descent_rate(float descent_rate)
#endif
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
bool Plane::set_crosstrack_start(const Location &new_start_location)
{
prev_WP_loc = new_start_location;
auto_state.crosstrack = true;
return true;
}
#endif // AP_SCRIPTING_ENABLED
// returns true if vehicle is landing.

View File

@ -1286,6 +1286,11 @@ public:
// allow for landing descent rate to be overridden by a script, may be -ve to climb
bool set_land_descent_rate(float descent_rate) override;
// allow scripts to override mission/guided crosstrack behaviour
// It's up to the Lua script to ensure the provided location makes sense
bool set_crosstrack_start(const Location &new_start_location) override;
#endif // AP_SCRIPTING_ENABLED
};