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

WIP: Gyro calibration #11

Draft
wants to merge 8 commits into
base: main
Choose a base branch
from
Draft

WIP: Gyro calibration #11

wants to merge 8 commits into from

Conversation

clanegge
Copy link
Contributor

Adds gyro calibration which can be started through a ROS service call

Copy link
Contributor

@rikba rikba left a comment

Choose a reason for hiding this comment

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

Great feature! Linked to #5

auto ygyro_off = readReg(0x1C);
auto zgyro_off = readReg(0x1E);

std::cout << "Gyro offers after reset:\n" << xgyro_off[0] << " , " << xgyro_off[1] << " , " << ygyro_off[1] << " , " << zgyro_off[1] << std::endl;
Copy link
Contributor

Choose a reason for hiding this comment

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

Use lpp

Suggested change
std::cout << "Gyro offers after reset:\n" << xgyro_off[0] << " , " << xgyro_off[1] << " , " << ygyro_off[1] << " , " << zgyro_off[1] << std::endl;
LOG(I, std::hex << "Gyro offset after reset: " << ": 0x" << +xgyro_off[0] << ", 0x" << +xgyro_off[1] << ", 0x" << +xgyro_off[2]);

@@ -226,6 +226,47 @@ int Adis16448::signedWordToInt(const std::vector<byte> &word) {
return (((int) *(signed char *) (word.data())) * 1 << CHAR_BIT) | word[1];
}

bool Adis16448::calibrateGyro(){
// set offsets to zero
writeReg(0x1A, {0x00, 0x00}, "XGYRO_OFF");
Copy link
Contributor

Choose a reason for hiding this comment

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

Use the command definitions, e.g.,

Suggested change
writeReg(0x1A, {0x00, 0x00}, "XGYRO_OFF");
writeReg(XGYRO_OFF, {0x00, 0x00}, "XGYRO_OFF");

std::cout << "Starting Gyro Calibration. Keep IMU steady and wait for 40s.." << std::endl;
writeReg(SENS_AVG, calib_sens_avg, "CALIB_SENS_AVG");
writeReg(SMPL_PRD, calib_smpl_prd, "CALIB_SMPL_PRD");
usleep(40*1e6); // wait for next measurement
Copy link
Contributor

Choose a reason for hiding this comment

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

I think instead of a fixed sleeping time, you can also poll the IMU and see if the value changes... But not sure how robust this is. Or calculate the sampling time from the register value to make it adaptable.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

good idea!

writeReg(SENS_AVG, sens_avg, "SENS_AVG");
writeReg(SMPL_PRD, smpl_prd, "SMPL_PRD");

return true;
Copy link
Contributor

Choose a reason for hiding this comment

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

It would be nice to configure the alarm on the IMU in case the platform is moved during calibration progress and then return false.

@clanegge
Copy link
Contributor Author

clanegge commented Nov 1, 2022

Ah, nice! Thanks for the feedback! I will change the stuff and still need to test it as well.

I also want to look at how/if the gyro_off values reset when the imu is power cycled. If they get reset we could call the calibration method once at the first start (when all gyro_off values are zero) and then leave them until the imu is turned off again.

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.

2 participants