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

Rangefinder arming checks #11078

Merged
merged 12 commits into from
Jul 30, 2019

Conversation

WickedShell
Copy link
Contributor

@WickedShell WickedShell commented Apr 11, 2019

This starts on a global set of arming checks on rangefinders. For now it simply introduces the requirement that if a rangefinder was specified, then we must have created a driver for it.

This was actually pretty easy by itself, unfortunately it turns out we have consumed all the bits for ARMING_CHECKS so I had to add param conversion for it, to get it to have 32 bits (we can still only use 24 of them sadly).

This also makes it easier to dump the keys for conversion, just to make it a single define change in the future.

This is a draft as the conversion in Sub is not working correctly. For reference this is what the key dump prints on Sub:
Key 75: Index 0: GroupElement 2 : ARMING_CHECK: 17

hal.util->snprintf(failure_msg, failure_msg_len, "Rangefinder %d was not detected", i + 1);
return false;
}
}
Copy link
Contributor

Choose a reason for hiding this comment

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

you could add a second check that the status is ok ! see : https://github.com/ArduPilot/ardupilot/pull/9886/files#diff-03adf2804cc10b90bbfe953b5c07b33eR91
it would catch correct instanciation but late deconnexion !

Copy link
Contributor Author

@WickedShell WickedShell Apr 11, 2019

Choose a reason for hiding this comment

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

NoData is a valid state though if you are out of range, but don't know which direction you are out of range. (Which is common when on the ground for example and the rangefinder is mounted low on the vehicle).

libraries/AP_Arming/AP_Arming.h Outdated Show resolved Hide resolved
@rmackay9
Copy link
Contributor

Outcome of the dev call was for @tridge to help @WickedShell with the parameter conversion magic.

@tridge tridge force-pushed the wickedshell/rangefinder-arming branch from a613a4d to 5eb88f0 Compare April 28, 2019 05:07
@tridge
Copy link
Contributor

tridge commented Apr 28, 2019

issue with Sub is now resolved

@@ -1096,7 +1096,9 @@ void AP_Param::save(bool force_save)
// when we are disarmed then loop waiting for a slot to become
// available. This guarantees completion for large parameter
// set loads
hal.scheduler->expect_delay_ms(500);
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Unit mixup.

I suspect this kind of thing is going to be so common, that unless we wrap this internally into the delay() call in the HAL with a check if we are on the main thread, this is going to be a constant problem everywhere. Given the relative rarity of calling delay() I think it's worth the overhead.

@WickedShell WickedShell force-pushed the wickedshell/rangefinder-arming branch from 5eb88f0 to 1758cd2 Compare July 23, 2019 02:56
@WickedShell WickedShell marked this pull request as ready for review July 23, 2019 02:57
@tridge tridge merged commit 2572885 into ArduPilot:master Jul 30, 2019
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

5 participants