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

Prearm check to validate backend read rates against scheduler loop rate #28672

Open
wants to merge 3 commits into
base: master
Choose a base branch
from

Conversation

bugobliterator
Copy link
Member

This PR adds a prearm check that ensures that we are reading gyro data atleast as fast as we are running our main loop, where all controllers run at. We do this for all the INS sensors that are enabled.

This avoids a situation where user might have set SCHED LOOP RATE faster than gyro poll rate or primary gyro with appropriate backend rate but forgot to do so for the rest.

@bugobliterator bugobliterator force-pushed the pr-sched-rate-prearm-check branch 3 times, most recently from fafeac5 to 6628454 Compare November 19, 2024 01:55
@amilcarlucas
Copy link
Contributor

Binary Name      Text [B]        Data [B]     BSS (B)        Total Flash Change [B] (%)      Flash Free After PR (B)
---------------  --------------  -----------  -------------  ----------------------------  -------------------------
arducopter-heli  316 (+0.0174%)  0 (0.0000%)  -4 (-0.0015%)  316 (+0.0174%)                                   144800
antennatracker   316 (+0.0234%)  0 (0.0000%)  -4 (-0.0015%)  316 (+0.0234%)                                   614640
arducopter       316 (+0.0174%)  0 (0.0000%)  -4 (-0.0015%)  316 (+0.0173%)                                   144344
ardurover        316 (+0.0190%)  0 (0.0000%)  4 (+0.0015%)   316 (+0.0190%)                                   298392
arduplane        316 (+0.0174%)  0 (0.0000%)  -4 (-0.0015%)  316 (+0.0174%)                                   146824
blimp            316 (+0.0231%)  0 (0.0000%)  4 (+0.0015%)   316 (+0.0230%)                                   592716
ardusub          316 (+0.0196%)  0 (0.0000%)  -4 (-0.0015%)  316 (+0.0196%)                                   354132

Copy link
Collaborator

@andyp1per andyp1per left a comment

Choose a reason for hiding this comment

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

Getting there

libraries/AP_InertialSensor/AP_InertialSensor_Backend.h Outdated Show resolved Hide resolved
}
// if gyro backend rate hz is 0, that means we are polling sensor at the sample rate or higher
if (_backends[i]->get_gyro_backend_rate_hz() == 0) {
if (_gyro_raw_sample_rates[i] < _loop_rate) {
Copy link
Collaborator

Choose a reason for hiding this comment

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

Don't you have to cater for oversampling here? See get_gyro_rate_hz()

Copy link
Collaborator

Choose a reason for hiding this comment

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

Didn't we agree that the rate needs to be at least 2x the loop rate?

Copy link
Member Author

@bugobliterator bugobliterator Nov 20, 2024

Choose a reason for hiding this comment

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

Don't you have to cater for oversampling here? See get_gyro_rate_hz()

No, oversampling is only set by drivers that use FIFO, and hence will be setting backend_rate_hz and we will be using that for comparision

Didn't we agree that the rate needs to be at least 2x the loop rate?

Done.

@@ -75,6 +75,11 @@ class AP_InertialSensor_Invensensev3 : public AP_InertialSensor_Backend
bool accumulate_samples(const struct FIFOData *data, uint8_t n_samples);
bool accumulate_highres_samples(const struct FIFODataHighRes *data, uint8_t n_samples);

// get the gyro backend rate in Hz at which the FIFO is being read
uint16_t get_gyro_backend_rate_hz() const override {
Copy link
Collaborator

Choose a reason for hiding this comment

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

I think we should take the opportunity to come up with a better name than "backend". Perhaps "get_gyro_read_rate_hz()" at least conveys what is going on and why it might be important.

Copy link
Member Author

Choose a reason for hiding this comment

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

That needs to be much larger and a separate change, I don't want to widen the scope of this PR.

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 just remove the word "backend" from the method name maybe?

continue;
}
if (_backends[i]->get_gyro_backend_rate_hz() < (2*_loop_rate)) {
hal.util->snprintf(fail_msg, fail_msg_len, "Gyro %d backend rate %dHz < sched loop rate %dHz",
Copy link
Contributor

Choose a reason for hiding this comment

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

we could shorten the message by removing "Hz" or "rate"

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.

It looks good to me but I'll leave it to Andy and Sid to sort out naming

Copy link
Contributor

@tridge tridge left a comment

Choose a reason for hiding this comment

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

looks good to me, thanks @bugobliterator !

@tridge
Copy link
Contributor

tridge commented Nov 20, 2024

@andyp1per I'd like to get your comments on this if possible

@peterbarker
Copy link
Contributor

@andyp1per looking for your approval on this one. Seems like a sensible sanity check.

Copy link
Collaborator

@andyp1per andyp1per left a comment

Choose a reason for hiding this comment

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

Looks good now - thanks @bugobliterator !

@peterbarker peterbarker force-pushed the pr-sched-rate-prearm-check branch from ff88246 to 94c4ebc Compare November 25, 2024 22:44
@peterbarker
Copy link
Contributor

I've rebased this on top of CI fixes and marking it for MergeOnCIPass.

@peterbarker
Copy link
Contributor

.... has to pass CI:

2024-11-26T03:16:37.4288781Z AT-0007.5: Received TIMESYNC response after 0.000000s
2024-11-26T03:16:37.4289428Z AT-0008.8: AP: PreArm: Gyro 1 backend rate 760Hz < sched loop rat
2024-11-26T03:16:37.4289977Z AT-0008.8: AP: e 400Hz
2024-11-26T03:16:37.4290385Z AT-0010.3: AP: PreArm: Gyro 1 backend rate 760Hz < sched loop rat
2024-11-26T03:16:37.4290930Z AT-0010.3: AP: e 400Hz
2024-11-26T03:16:37.4291424Z AT-0011.8: AP: PreArm: Gyro 1 backend rate 760Hz < sched loop rat
2024-11-26T03:16:37.4291859Z AT-0011.8: AP: e 400Hz
2024-11-26T03:16:37.4292372Z AT-0013.3: AP: PreArm: Gyro 1 backend rate 760Hz < sched loop rat
2024-11-26T03:16:37.4292827Z AT-0013.3: AP: e 400Hz
2024-11-26T03:16:37.4293426Z AT-0013.4: Prearm bit never went true.  Attempting arm to elicit reason from autopilot
2024-11-26T03:16:37.4294321Z AT-0013.4: Arm motors with MAVLink cmd
2024-11-26T03:16:37.4296075Z AT-0013.4: Sending COMMAND_LONG to (1,1) (MAV_CMD_COMPONENT_ARM_DISARM=400) (p1=1.000000 p2=0.000000 p3=0.000000 p4=0.000000 p5=0.000000 p6=0.000000  p7=0.000000)
2024-11-26T03:16:37.4297415Z AT-0013.4: ACK received: COMMAND_ACK {command : 400, result : 4, progress : 0, result_param2 : 0, target_system : 250, target_component : 250} (0.000000s)

@tridge tridge force-pushed the pr-sched-rate-prearm-check branch from 94c4ebc to d30d6f7 Compare December 11, 2024 03:40
@bugobliterator bugobliterator force-pushed the pr-sched-rate-prearm-check branch from d30d6f7 to 70db719 Compare December 11, 2024 08:47
@bugobliterator
Copy link
Member Author

Seems like SITL was failing the prearm because the second IMU gyro rate is 760 < 2*400.

Pixhawk1 and other boards using LSM9DS0 will have the same issue. @tridge

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

Successfully merging this pull request may close these issues.

6 participants