Skip to content

Conversation

timtuxworth
Copy link
Contributor

@timtuxworth timtuxworth commented Nov 7, 2024

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.

I've also included 3 Lua modules that are used by the script but might also be useful to others.

  • speedpid.lua - A PID controller extracted/generalized from plane_aerobatics
  • mavlink_command_int.Lua - allows sending MAVlink command_int messages to another vehicle
  • mavlink_attitude - a receiver for MAVlink ATTITUDE messages sent by another vehicle.

This PR depends on
#28526 - this has now been included into this PR
ArduPilot/mavlink#372 - this has been merged
#28527 - this has been merged

@timtuxworth timtuxworth force-pushed the pr-plane-follow-script branch 5 times, most recently from b2021a5 to c6bec54 Compare November 8, 2024 10:55
@timtuxworth
Copy link
Contributor Author

Could you take a look @peterbarker and @tridge ?

@timtuxworth timtuxworth force-pushed the pr-plane-follow-script branch from c6bec54 to a85ee8f Compare November 9, 2024 10:00
@timtuxworth
Copy link
Contributor Author

I wonder if you'd be able to take a look at my Lua @yuri-rage - any suggestions appreciated.

@yuri-rage
Copy link
Contributor

I wonder if you'd be able to take a look at my Lua @yuri-rage - any suggestions appreciated.

I'd be happy to take a look, Tim, but I have some external commitments upcoming that may prevent me from diving in right away. Please remind me either here, Discuss, or Discord if I don't reply in a week.

@timtuxworth timtuxworth force-pushed the pr-plane-follow-script branch from a85ee8f to b9de7f9 Compare November 15, 2024 04:47
@timtuxworth timtuxworth force-pushed the pr-plane-follow-script branch from b9de7f9 to 3cbe60d Compare November 28, 2024 19:14
@timtuxworth timtuxworth force-pushed the pr-plane-follow-script branch 2 times, most recently from db44c23 to 8910d83 Compare December 21, 2024 20:50
@timtuxworth timtuxworth force-pushed the pr-plane-follow-script branch 2 times, most recently from 52d0f53 to 2183684 Compare January 24, 2025 22:31
@timtuxworth timtuxworth force-pushed the pr-plane-follow-script branch 2 times, most recently from 2821e85 to 3a0b2c3 Compare February 17, 2025 23:39
@timtuxworth timtuxworth force-pushed the pr-plane-follow-script branch 4 times, most recently from 9e6a6a8 to 7b22a30 Compare March 16, 2025 19:00
@timtuxworth timtuxworth force-pushed the pr-plane-follow-script branch 2 times, most recently from b0db2e8 to 8b99bef Compare March 20, 2025 20:49
@timtuxworth timtuxworth force-pushed the pr-plane-follow-script branch 2 times, most recently from 8f59dc2 to 47f44b2 Compare March 31, 2025 21:10
next_WP_loc = loc;

// used to control FBW and limit the rate of climb
// cannot be applied in Guided as this prevents the guided set altitude from working correctly
Copy link
Member

Choose a reason for hiding this comment

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

Why is this?

Copy link
Contributor Author

@timtuxworth timtuxworth Mar 31, 2025

Choose a reason for hiding this comment

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

I guess it's because this code assumes that GUIDED is always running in "location" sub-mode (i.e. flying towards a location), but my follow code needs to switch between "location" sub-mode and "heading" sub mode. This line prevents the target altitude being reset when switching between sub-modes.

Copy link
Contributor

Choose a reason for hiding this comment

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

I think this would prevent a simple mode change to GUIDED from locking the current alt

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Mar 31, 2025
@timtuxworth timtuxworth force-pushed the pr-plane-follow-script branch from 181025f to 07a0e56 Compare April 7, 2025 01:23
Copy link
Contributor Author

@timtuxworth timtuxworth left a comment

Choose a reason for hiding this comment

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

Implemented changes from the Dev call on 31 March 2025

_target_location.lng = packet.lon;

// select altitude source based on FOLL_ALT_TYPE param
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
Copy link
Contributor

Choose a reason for hiding this comment

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

i think this should be available on copter

next_WP_loc = loc;

// used to control FBW and limit the rate of climb
// cannot be applied in Guided as this prevents the guided set altitude from working correctly
Copy link
Contributor

Choose a reason for hiding this comment

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

I think this would prevent a simple mode change to GUIDED from locking the current alt

// check for timeout
if ((_last_heading_update_ms == 0) || (AP_HAL::millis() - _last_heading_update_ms > AP_FOLLOW_TIMEOUT_MS)) {
if ((_last_heading_update_ms == 0) || (AP_HAL::millis() - _last_heading_update_ms > (uint32_t)_timeout_ms)) {
gcs().send_text(MAV_SEVERITY_NOTICE, "gthd timeout %d", (int)(AP_HAL::millis() - _last_location_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.

could flood the link with msgs?

AP_Follow follow;
#endif

AP_Int32 guided_timeout;
Copy link
Member

Choose a reason for hiding this comment

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

AP_Float please.

AP_Enum<Location::AltFrame> _alt_type; // altitude source for follow mode
AC_P _p_pos; // position error P controller
AP_Int16 _options; // options for mount behaviour follow mode
AP_Int32 _timeout_ms; // position estimate timeout after x milliseconds
Copy link
Member

Choose a reason for hiding this comment

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

AP_Float and update comment for seconds.

return false;
}
// ignore message if we already received a more recent one
if(_target_location_last_time_boot_ms != 0 && packet.time_boot_ms <= _target_location_last_time_boot_ms ) {
Copy link
Member

Choose a reason for hiding this comment

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

What happens if the follow target vehicle is rebooted? Its boot time will go backwards so it will be ignored. Maybe if the time is more than 5 or 10 seconds in the past it would reset the boot time.

local xy_dist = follow:get_distance_to_target() -- this value is set by get_target_dist_and_vel_ned() - why do I have to know this?
local target_heading = follow:get_target_heading_deg()
*/
bool AP_Follow::get_target_info(Vector3f &dist_ned, Vector3f &dist_with_offs,
Copy link
Contributor

Choose a reason for hiding this comment

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

I find it odd to be fetching both with and without the offset, why would a consumer want both?

Copy link
Contributor

Choose a reason for hiding this comment

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

I think we need to fix the API so you don't need to call function A in order to get the correct value for function B

@timtuxworth timtuxworth force-pushed the pr-plane-follow-script branch 2 times, most recently from eccc87a to f4065aa Compare April 26, 2025 04:32
@timtuxworth timtuxworth force-pushed the pr-plane-follow-script branch from f4065aa to 27ccc36 Compare April 26, 2025 08:30
@timtuxworth
Copy link
Contributor Author

Replaced by #30654

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.

7 participants