AP_Mission: add Jump_TAG hook for scripting

This commit is contained in:
Tom Pittenger 2023-02-21 17:47:01 -08:00 committed by Andrew Tridgell
parent a0fe53414c
commit 7f5222eac2
2 changed files with 19 additions and 0 deletions

View File

@ -2091,6 +2091,18 @@ uint16_t AP_Mission::get_index_of_jump_tag(const uint16_t tag) const
return 0;
}
#if AP_SCRIPTING_ENABLED
bool AP_Mission::get_last_jump_tag(uint16_t &tag, uint16_t &age) const
{
if (_jump_tag.age == 0) {
return false;
}
tag = _jump_tag.tag;
age = _jump_tag.age;
return true;
}
#endif
// init_jump_tracking - initialise jump_tracking variables
void AP_Mission::init_jump_tracking()
{

View File

@ -659,6 +659,13 @@ public:
bool get_item(uint16_t index, mavlink_mission_item_int_t& result) const ;
bool set_item(uint16_t index, mavlink_mission_item_int_t& source) ;
// Jump Tags. When a JUMP_TAG is run in the mission, either via DO_JUMP_TAG or
// by just being the next item, the tag is remembered and the age is set to 1.
// Only the most recent tag is remembered. It's age is how many NAV items have
// progressed since the tag was seen. While executing the tag, the
// age will be 1. The next NAV command after it will tick the age to 2, and so on.
bool get_last_jump_tag(uint16_t &tag, uint16_t &age) const;
// Set the mission index to the first JUMP_TAG with this tag.
// Returns true on success, else false if no appropriate JUMP_TAG match can be found or if setting the index failed
bool jump_to_tag(const uint16_t tag);