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

Copter, Sub, AP_Mount: Fix inconsistent handling of clearing ROIs #25277

Merged

Conversation

nexton-winjeel
Copy link
Contributor

@nexton-winjeel nexton-winjeel commented Oct 16, 2023

Addresses #25276:

There are two ways to remove a Region of Interest (ROI):

  1. Send a DO_SET_ROI/DO_SET_ROI_LOCATION command with the location set to (0, 0, 0); or
  2. Send a DO_SET_ROI_NONE command.

However, in Copter and Sub, the first case has special handling to set the Auto Yaw behaviour, but the second case doesn't.

FYI: @rmackay9

@nexton-winjeel nexton-winjeel force-pushed the upstream/fix-copter-do-set-roi-none branch from 6b66f97 to 1345eb4 Compare October 16, 2023 09:33
@nexton-winjeel
Copy link
Contributor Author

Added an autotest to demonstrate the previous (and fixed) behaviour.

@nexton-winjeel nexton-winjeel force-pushed the upstream/fix-copter-do-set-roi-none branch from 1345eb4 to 490d2bb Compare October 18, 2023 00:50
@nexton-winjeel
Copy link
Contributor Author

@peterbarker, @IamPete1: can you please look at this in Randy's absence?

@@ -5104,12 +5104,17 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
case MAV_CMD_DO_SET_MODE:
return handle_command_do_set_mode(packet);

case MAV_CMD_DO_SET_ROI_NONE: {
Copy link
Contributor

Choose a reason for hiding this comment

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

I'm not really a fan of moving handling of this command up into the GCS layer. That seems like we're moving in the wrong direction.

I think the inconsistently comes from how Copter's special handling of ROI in that we want to be able to point the copter's nose at the ROI target in case the gimbal does not have yaw control.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Agreed, but moving it here is consistent with how DO_SET_ROI and DO_SET_ROI_LOCATION are currently handled.

I'd rather move this here now, then refactor all three of them together.

Copy link
Contributor

@rmackay9 rmackay9 left a comment

Choose a reason for hiding this comment

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

I think that @nexton-winjeel is probably correct that in the short-term this is probably the best fix. The very specific reason is that AP_Mount::handle_command() doesn't handle DO_SET_ROI or DO_SET_ROI_LOCATION so it makes sense that the DO_SET_ROI_NONE would also not be in AP_Mount::handle_command().

FYI @peterbarker the DO_SET_ROI_SYSID is also in AP_Mount::handle_command() which becomes even more of an outlier with this change. Of course it is such a rarely used command that it probably doesn't matter for now.

@rmackay9
Copy link
Contributor

@IamPete1 @peterbarker feel free to merge this if you have no objections.

@rmackay9 rmackay9 merged commit 98dfaba into ArduPilot:master Oct 29, 2023
86 checks passed
@rmackay9
Copy link
Contributor

Merged, thanks!

@nexton-winjeel nexton-winjeel deleted the upstream/fix-copter-do-set-roi-none branch October 30, 2023 02:19
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.

3 participants