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_Param: throw error if we lose parameters #27820

Merged
merged 1 commit into from
Aug 19, 2024

Conversation

tridge
Copy link
Contributor

@tridge tridge commented Aug 12, 2024

if we can't save a parameter due to the queue size not being large enough then there is a coding error, likely the code trying to save large numbers of parameters from main thread while armed

if we can't save a parameter due to the queue size not being large
enough then there is a coding error, likely the code trying to save
large numbers of parameters while armed
@@ -1266,6 +1266,7 @@ void AP_Param::save(bool force_save)
if (hal.util->get_soft_armed() && hal.scheduler->in_main_thread()) {
// if we are armed in main thread then don't sleep, instead we lose the
// parameter save
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
Copy link
Collaborator

Choose a reason for hiding this comment

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

Doesn't this mean we get an internal error while flying? Doesn't seem terribly friendly.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

nearly all our internal errors can happen when flying

@tridge tridge merged commit faf769d into ArduPilot:master Aug 19, 2024
93 checks passed
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