Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: Add radius to MAV_CMD_DO_REPOSITION #19860

Merged
merged 1 commit into from
Oct 11, 2022

Conversation

magicrub
Copy link
Contributor

mavlink change: ArduPilot/mavlink#240

Replaced #19297

This adds an adjustable radius for Guided mode vis the . This does not effect any other vehicle since the concept of radius does not apply to any vehicle that has a guided mode.

It's fully backwards compatible to existing command.

param3: was unused, now it's the positive-only radius. Ignore if <= 0
param4: controls radius, as stated in existing mavlink spec. Added option to ignore yaw if not == 0 or == 1.

This also lays the groundwork to easily add a new param GUIDED_LOIT_RAD in the future which is requested by @pompecukor

Behavior:
when entering guided mode, it uses WP_LOITER_RAD like usual. If the DO_REPOS command is received and the radius is > 0, then it overwrites the radius with this new one. Any change away and back to guided will reset you back to WP_LOITER_RAD. This is consistent with how DO_CHANGE_SPEED behaves.

This has been discussed with @peterbarker and @WickedShell

@magicrub magicrub force-pushed the pr/do_reposition_radius branch 2 times, most recently from 412d64e to faa3a0a Compare April 9, 2022 17:22
@magicrub magicrub removed the WIP label Apr 9, 2022
@magicrub
Copy link
Contributor Author

magicrub commented Apr 9, 2022

updated. This PR is not blocked by the mavlink PR because it's just taking advantage of an unused command_int param3.

@magicrub
Copy link
Contributor Author

upstream mavlink PR has merged: mavlink/mavlink#1825

ArduPlane/mode.h Outdated Show resolved Hide resolved
ArduPlane/GCS_Mavlink.cpp Outdated Show resolved Hide resolved
ArduPlane/mode.h Outdated Show resolved Hide resolved
@magicrub
Copy link
Contributor Author

Anything else @WickedShell ?

@magicrub magicrub force-pushed the pr/do_reposition_radius branch 2 times, most recently from 55b5be4 to ff73df6 Compare May 23, 2022 21:39
@magicrub
Copy link
Contributor Author

@WickedShell anything else?

@magicrub
Copy link
Contributor Author

magicrub commented Jun 8, 2022

@WickedShell is requesting someone else to take a peek before he approves.

@magicrub
Copy link
Contributor Author

magicrub commented Jun 9, 2022

I tagged this with DevCallTopic but I don't think it really needs to be discussed. It just needs to be looked at by someone else before we merge per @WickedShell 's request

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.

An autotest would be really nice here. This is the sort of functionality which is easy to test but can be unknowingly broken by people relatively easily.

@@ -944,7 +944,7 @@ class Plane : public AP_Vehicle {
#endif

// commands.cpp
void set_guided_WP(const Location &loc);
void set_guided_WP(const Location &loc, const float radius = 0); // radius values: -1 = default (use param WP_LOITER_RAD), 0 = ignore (no-change), >0 is radius
Copy link
Contributor

Choose a reason for hiding this comment

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

Why have such complicated semantics for the second parameter?

Wouldn't it be easier for the (two) callers to call set_guided_radius directly?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I had it like that at one point but it didn't seem right that anyone could reach down into the guided mode class and set that property anytime. Seems better as an atomic-ish thing with a single entry point

@magicrub
Copy link
Contributor Author

An autotest would be really nice here. This is the sort of functionality which is easy to test but can be unknowingly broken by people relatively easily.

Yup, that's very true. I'll take a look into it

float radius = 0;
// Loiter radius for planes. Positive radius in meters, direction is controlled by Yaw (param4) value.
// radius values:-1 = use default param WP_LOITER_RAD, 0 = ignore (no-change), >0 radius
if (!isnan(packet.param3)) {
Copy link
Contributor

Choose a reason for hiding this comment

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

need to check > 0 as spec says +ve

Copy link
Contributor Author

Choose a reason for hiding this comment

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

fixed

ArduPlane/mode.h Outdated
// to: <= 0 use default param WP_LOITER_RAD, >0 radius_m
// we constrain to uint16_t because that is what update_loiter() is currently limited to
if (!is_zero(radius)) {
active_radius_m = (radius < 0) ? 0 : MIN(radius,UINT16_MAX);
Copy link
Contributor

Choose a reason for hiding this comment

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

set to default radius is <= 0, so it doesn't persist

Copy link
Contributor Author

Choose a reason for hiding this comment

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

fixed

@tridge
Copy link
Contributor

tridge commented Jun 13, 2022

adding a set_radius_and_direction() makes sense

@peterbarker
Copy link
Contributor

ping @magicrub - ball's in your court here - I think the requested changes are relatively small.

@magicrub
Copy link
Contributor Author

fixed

@tridge tridge added the WikiNeeded needs wiki update label Oct 10, 2022
ArduPlane/mode_guided.cpp Outdated Show resolved Hide resolved
@magicrub magicrub merged commit 46bc30a into ArduPilot:master Oct 11, 2022
@magicrub magicrub deleted the pr/do_reposition_radius branch March 2, 2023 18:06
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Plane WikiNeeded needs wiki update
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants