-
Notifications
You must be signed in to change notification settings - Fork 174
Set sequences & handle spurious wakeups in RVC4 IMU #1727
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
base: develop
Are you sure you want to change the base?
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change | ||||||||
|---|---|---|---|---|---|---|---|---|---|---|
| @@ -1,5 +1,6 @@ | ||||||||||
| #include <catch2/catch_all.hpp> | ||||||||||
| #include <catch2/catch_test_macros.hpp> | ||||||||||
| #include <chrono> | ||||||||||
| #include <initializer_list> | ||||||||||
|
|
||||||||||
| #include "depthai/depthai.hpp" | ||||||||||
|
|
@@ -40,3 +41,39 @@ TEST_CASE("Test IMU, all sensors") { | |||||||||
| TEST_CASE("Test IMU, gyroscope 480 Hz") { | ||||||||||
| basicIMUTest(480.0f, {dai::IMUSensor::GYROSCOPE_RAW}, 0.8f); // TODO(Morato) - debug why some devices need so much tolerance | ||||||||||
| } | ||||||||||
|
|
||||||||||
| TEST_CASE("At least one measurement should be updated") { | ||||||||||
| dai::Pipeline pipeline; | ||||||||||
| auto imu = pipeline.create<dai::node::IMU>(); | ||||||||||
| imu->enableIMUSensor(dai::IMUSensor::ACCELEROMETER_RAW, 400); | ||||||||||
| imu->enableIMUSensor(dai::IMUSensor::GYROSCOPE_RAW, 400); | ||||||||||
|
|
||||||||||
| imu->setBatchReportThreshold(10); | ||||||||||
| imu->setMaxBatchReports(20); | ||||||||||
|
Comment on lines
+51
to
+52
Contributor
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. 🧩 Analysis chain🏁 Script executed: #!/bin/bash
# Description: Verify maxBatchReports constraint documentation and runtime handling
# Check the IMUProperties documentation
echo "=== IMUProperties maxBatchReports documentation ==="
rg -n -A2 -B2 'maxBatchReports' --type=cpp
# Check if there's any validation/clamping logic for maxBatchReports
echo ""
echo "=== Searching for validation of maxBatchReports ==="
rg -n -C5 'setMaxBatchReports' --type=cppRepository: luxonis/depthai-core Length of output: 12251
According to 🔧 Proposed fix imu->setBatchReportThreshold(10);
- imu->setMaxBatchReports(20);
+ imu->setMaxBatchReports(5);📝 Committable suggestion
Suggested change
🤖 Prompt for AI Agents |
||||||||||
|
|
||||||||||
| auto imuQueue = imu->out.createOutputQueue(50, false); | ||||||||||
|
|
||||||||||
| pipeline.start(); | ||||||||||
|
|
||||||||||
| auto start = std::chrono::steady_clock::now(); | ||||||||||
|
|
||||||||||
| dai::IMUPacket previousPacket; | ||||||||||
|
|
||||||||||
| uint32_t numMessages = 0; | ||||||||||
|
|
||||||||||
| while(pipeline.isRunning() && std::chrono::steady_clock::now() - start <= std::chrono::seconds(10)) { | ||||||||||
| auto imuData = imuQueue->get<dai::IMUData>(); | ||||||||||
|
|
||||||||||
| if(imuData == nullptr) continue; | ||||||||||
|
|
||||||||||
| ++numMessages; | ||||||||||
|
|
||||||||||
| for(const auto& imuPacket : imuData->packets) { | ||||||||||
|
Comment on lines
+60
to
+70
|
||||||||||
| REQUIRE((imuPacket.acceleroMeter.sequence > previousPacket.acceleroMeter.sequence || imuPacket.gyroscope.sequence > previousPacket.gyroscope.sequence)); | ||||||||||
| previousPacket = imuPacket; | ||||||||||
| } | ||||||||||
|
Comment on lines
+70
to
+73
|
||||||||||
| } | ||||||||||
|
|
||||||||||
| REQUIRE(numMessages > 0); | ||||||||||
|
|
||||||||||
| pipeline.stop(); | ||||||||||
| } | ||||||||||
|
coderabbitai[bot] marked this conversation as resolved.
|
||||||||||
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
🧹 Nitpick | 🔵 Trivial
Consider a more descriptive test name.
The current name "At least one measurement should be updated" could be clearer. Consider renaming to something like "Test IMU sequence numbers strictly increase" or "Test IMU packets contain new data (no spurious wakeups)" to better reflect the test's purpose.
🤖 Prompt for AI Agents