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

Navigator: add optional delay after gimbal mission items #23960

Merged
merged 4 commits into from
Nov 28, 2024

Conversation

StefanoColli
Copy link
Contributor

@StefanoColli StefanoColli commented Nov 18, 2024

Solved Problem

In a mission with a move gimbal item followed by a take picture item, the picture is taken while the gimbal is still moving

Solution

After a CMD_DO_GIMBAL_MANAGER_PITCHYAW wait for a timeout before resuming the mission to be sure that the gimbal reached the desired orientation.
Since we already have CMD_DO_WINCH and NAV_CMD_DO_GRIPPER following a similar pattern, we defined a common timeout parameter (MIS_COMMAND_TOUT) for these 3 mission items. Furthermore, we unified the logic handling such mission items simplifying the navigator code.

Changelog Entry

For release notes:

Removed parameter: MIS_PD_TO (substituted by MIS_COMMAND_TOUT)
New parameter: MIS_COMMAND_TOUT

Test coverage

  • SITL testing

@MaEtUgR MaEtUgR self-requested a review November 18, 2024 12:05
Copy link
Contributor

@sfuhrer sfuhrer left a comment

Choose a reason for hiding this comment

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

Makes sense to me, assuming we do not get feedback from the gimbal and thus cannot know when its position is reached, so we need to assume "worst case".

Please think about how to recommend users to tune it and open a PR against docs.px4 with these instructions.
E.g. in the gimbal docs.

* @decimal 1
* @group Mission
*/
PARAM_DEFINE_FLOAT(MIS_GIM_WAIT_T, 0.0f);
Copy link
Contributor

Choose a reason for hiding this comment

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

Could we come up with a reasonable default that applies for most gimbals, or are the times they need to move actually so far apart that a default doesn't make any sense?
On the gimbal you tested with: to what value would you set it?

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 believe that the best default value is to keep it as 0 since such delay prevents any other mission item to be executed in that time slot. I don't know if it is a desirable default behavior.
I tested it on a simulated gimbal with 3 seconds, but I don't know if gimbals have a 'standard' rate speed we can use to find a default value for the delay. Furthermore the delay depends also on the max angle the gimbal have to move and thus on the specific mission.

Copy link
Member

Choose a reason for hiding this comment

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

Ideally we'd actually chaeck if the gimal reached the attitude it was commanded. Since I assume that's not the scope of this implementation I'd suggest a reasonable default according to our tests and following up with a gimbal state based solution.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Now that we have a common timeout value for winch, gripper and gimbal, it is even more difficult to find a reasonable default value. At this point I would use 5.0 which was the default for MIS_PD_TO

src/modules/navigator/mission_block.cpp Outdated Show resolved Hide resolved
@MaEtUgR
Copy link
Member

MaEtUgR commented Nov 18, 2024

@StefanoColli FYI I'm currently reviewing this pr and have quite some suggestions for simplifications. I can push them after I'm finished, just want to make sure we're not changing the same things at the same time.

MaEtUgR
MaEtUgR previously approved these changes Nov 18, 2024
Copy link
Member

@MaEtUgR MaEtUgR left a comment

Choose a reason for hiding this comment

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

I suggested quite some changes 🙈
@StefanoColli Could you check if my suggestions make sense and if ti still works as expected in your testing? 😇

@StefanoColli
Copy link
Contributor Author

Nice work, the code is much tidier now! In simulation it still behaves as expected. 👍🏻

@@ -445,7 +418,7 @@ MissionBlock::is_mission_item_reached_or_completed()

/* check if the MAV was long enough inside the waypoint orbit */
if ((get_time_inside(_mission_item) < FLT_EPSILON) ||
(now - _time_wp_reached >= (hrt_abstime)(get_time_inside(_mission_item) * 1e6f))) {
(now >= (hrt_abstime)(get_time_inside(_mission_item) * 1_s) + _time_wp_reached)) {
Copy link
Member

Choose a reason for hiding this comment

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

@sfuhrer Isn't this way of timeout condition better because of unsigned wrapping? 🤔

@MaEtUgR
Copy link
Member

MaEtUgR commented Nov 21, 2024

Sorry for the delay we're still testing the solution. We could merge without the default timeout and then set accordingly after the testing.

StefanoColli and others added 4 commits November 28, 2024 17:58
…command

Used for winch, gripper, gimbal to reach the desired state before continuing the mission.
Ideally we'd have feedback from all these components and not just a feed-forward delay.
Copy link
Member

@MaEtUgR MaEtUgR left a comment

Choose a reason for hiding this comment

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

I disabled the timeout by default again since we couldn't confirm how long it should be. We can add a sensible default value later if we see what works for most setups.

From my side this is a good iteration and with all the simplifications it doesn't add any ballast.

@MaEtUgR MaEtUgR merged commit ce3fcd5 into PX4:main Nov 28, 2024
54 of 59 checks passed
@hamishwillee
Copy link
Contributor

hamishwillee commented Dec 11, 2024

@StefanoColli Removal of MIS_PD_TO has created docs errors in these docs:

Can you please fix them up? Also note comment from @sfuhrer here: #23960 (review) - which boils down to "where else should the information be added"?
If you can create a PR with the changes I will review.

It may sound trite, but there is no point adding any feature if you don't document it, because it will not get used.

FWIW I am not certain about this change. The time taken for a winch to spool might be very significantly different to the time for a gimbal to align. If you have a setup with both then you're slowing your mission by however long the longer delay is.
Perhaps not that big a deal.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants