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

AP_Mount: fix object tracking command for ViewPro #29228

Open
wants to merge 1 commit into
base: master
Choose a base branch
from

Conversation

eppravitra
Copy link
Contributor

The command should also take negative values

@eppravitra
Copy link
Contributor Author

The change was tested with CubeOrangePlus connected to ViewPro A10T

@rmackay9
Copy link
Contributor

rmackay9 commented Feb 5, 2025

Hi @eppravitra,

Thanks for your work on fixing the ViewPro driver. Are you sure this works correctly? It seems there could be two problems:

  1. send_tracking_command2 uses the htobe16() method which I think takes a uint16_t meaning that param1 and param2 are just going to be cast to be unsigned anyway
  2. The existing code that converts p1 and p2 to values between -960~+960 and -540 ~ +540 seems incorrect. Of course I wrote this code originally and you haven't touched it as part of this PR but I was unable to test this properly.

Shouldn't this line:
send_tracking_command2(TrackingCommand2::SET_POINT, (p1.x - 0.5) * 960, (p1.y - 0.5) * 540));

.. actually be ..

send_tracking_command2(TrackingCommand2::SET_POINT, (p1.x - 0.5) * 2.0 * 960, (p1.y - 0.5) * 2.0 * 540));

@eppravitra
Copy link
Contributor Author

Hi @rmackay9,

The code works. I tested it with actual hardware. I very much agree with your concerns though. I am willing to help make changes, to make things clearer.

  1. I could not find an equivalent function of htobe16() for int16 though. Do you have any suggestions? That is the reason why I have not changed that line.

  2. I very much want to make this change.

send_tracking_command2(TrackingCommand2::SET_POINT, (p1.x - 0.5) * 2.0 * 960, (p1.y - 0.5) * 2.0 * 540));

With your permission, could I make the change? Of course, it will break someone's code that might be using this function, but the change will make it comply with mavlink documentation.

@rmackay9
Copy link
Contributor

rmackay9 commented Feb 5, 2025

@eppravitra,

Thanks, as long as we think it is correct then I think the 2nd change should be fine. I suspect nobody has used the tracking function yet so it's likely safe. It looks like I have added a command to test this to our MAVLink Interfaces Camera wiki page but I only tested the very center so this is likely why I didn't notice the problem. Once we get this fixed, I'll add some more tests to that page.

Ideally when doing testing we should confirm that it's incorrect before and correct aftwards. So two tests if possible.

The command should also take negative values

Redo scaling to comply with mavlink documentation.
@eppravitra
Copy link
Contributor Author

The scaling change has been made @rmackay9 .
I already test it with CubeOrangePlus and ViewPro A10T. It works.

I think this one is ready for a merge.

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.

tested and it works well, thanks!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
Status: No status
Development

Successfully merging this pull request may close these issues.

2 participants