Skip to content

Conversation

timtuxworth
Copy link
Contributor

@timtuxworth timtuxworth commented Jul 14, 2025

This creates a new Lua Script applet that implements "plane follow" - a fixed wing follow/chase functionality that runs in guided mode. The code uses the core AP_Follow library functionality and therefore uses most of the documented FOLL_ parameters that are used in Copter and Rover FOLLOW mode.

The kinematic extrapolation improvements made by @lthall significantly improved the quality and smoothness of the follow.

I've made one small enhancement to make the follow Altitude sensitive as this was required by the partner who I worked with through this process. If FOLL_ALT_TYPE = 3:terrain then the follow altitude will be terrain relative. There is also a scripted FOLLP_OVR_ALT that forces the follow vehicle to use a specific altitude overriding the altitude it receives from the lead plane and the follow library.

I've also included a Lua module that is used by the script but might also be useful to others.

pid.lua - A PID controller extracted/generalized from plane_aerobatics

@timtuxworth timtuxworth changed the title Pr plane follow Plane follow lua applet DRAFT Jul 14, 2025
@timtuxworth timtuxworth force-pushed the pr-plane-follow branch 7 times, most recently from 1db472a to 3becb7e Compare July 21, 2025 00:37
@timtuxworth timtuxworth force-pushed the pr-plane-follow branch 2 times, most recently from 28941e2 to 27589aa Compare July 23, 2025 17:40
@timtuxworth timtuxworth force-pushed the pr-plane-follow branch 6 times, most recently from 8046766 to f0f5cee Compare August 5, 2025 17:37
@timtuxworth timtuxworth changed the title Plane follow lua applet DRAFT Plane follow lua applet Aug 5, 2025
@timtuxworth timtuxworth marked this pull request as ready for review August 5, 2025 21:43
@timtuxworth timtuxworth force-pushed the pr-plane-follow branch 4 times, most recently from 60d9854 to 684840c Compare August 11, 2025 21:54
Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

partial review on-call only

Copy link
Contributor

@lthall lthall left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

With the changes below I highlighted I think this is good.

Copy link
Contributor

@tridge tridge left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

partial review

@timtuxworth timtuxworth force-pushed the pr-plane-follow branch 10 times, most recently from 773bb71 to f8a523d Compare September 30, 2025 18:09
//==========================================================================

uint32_t _last_location_update_ms; // Time of last target position update (ms)
uint64_t _last_location_update_us; // Time of last target position update (ms)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'd make this uint64_t _last_location_update_ms;

}

// apply jitter-corrected timestamp to this update unless the update is older than the most recently received message or FOLL_TIMEOUT seconds
uint64_t location_update_us = _jitter.correct_offboard_timestamp_usec((uint64_t)packet.time_boot_ms * 1000, AP_HAL::micros());
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

uint64_t location_update_ms = uint64_div1000(_jitter.correct_offboard_timestamp_usec((uint64_t)packet.time_boot_ms * 1000, AP_HAL::micros()));


// apply jitter-corrected timestamp to this update unless the update is older than the most recently received message or FOLL_TIMEOUT seconds
uint64_t location_update_us = _jitter.correct_offboard_timestamp_usec((uint64_t)packet.time_boot_ms * 1000, AP_HAL::micros());
if (location_update_us < _last_location_update_us || (location_update_us - _last_location_update_us) > _timeout.cast_to_float() * 1000000 ) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would do something like:
float tdelta = int32_t(location_update_ms - _last_location_update_ms) * 0.001;
if (tdelta < 0 && tdelta > -10) {
xxx;
}

/// Altitude comes in AMSL
_target_location.set_alt_cm(packet.alt * 0.1, Location::AltFrame::ABSOLUTE);
// convert the incoming altitude to terrain altitude
_target_location.change_alt_frame(Location::AltFrame::ABOVE_TERRAIN);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

what happens if this fails?

@tridge tridge merged commit ba0a13f into ArduPilot:master Oct 7, 2025
107 of 108 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

WikiNeeded needs wiki update

Projects

None yet

Development

Successfully merging this pull request may close these issues.

8 participants