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

ardupilotmega: use params 6 and 7 of MAV_CMD_DO_START_MAG_CAL to pass lon/lat #238

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

Conversation

Williangalvani
Copy link

This will improve the calibration of compasses on vehicles not equipped with a GPS, As fix_radius() in step two of calibration requires a GPS lock.

@@ -158,8 +158,8 @@
<param index="3" label="Autosave" minValue="0" maxValue="1" increment="1">Save without user input (0=require input, 1=autosave).</param>
<param index="4" label="Delay" units="s">Delay.</param>
<param index="5" label="Autoreboot" minValue="0" maxValue="1" increment="1">Autoreboot (0=user reboot, 1=autoreboot).</param>
<param index="6">Empty.</param>
<param index="7">Empty.</param>
<param index="6" label="Latitude" units="deg">Latitude where calibration is happening, for vehicles with no GPS.</param>
Copy link
Collaborator

Choose a reason for hiding this comment

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

needs the comment to say that zero means to ignore

… lon/lat

This will improve the calibration of compasses on vehicles not equipped with a GPS.
As `fix_radius()` in step two of calibration requires a GPS lock.
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