Skip to content

IMU to Camera constraint? #1739

Answered by scott-robotics
lowellm91 asked this question in Q&A
Discussion options

You must be logged in to vote

The local transform / extrinsic between the sensors is handled in the Preintegration routine (via PreintegratedRotationParams).

gtsam::imuBias::ConstantBias prior_imu_bias;  // assume zero initial bias

auto parameters = gtsam::PreintegratedCombinedMeasurements::Params::MakeSharedD(0.0);
parameters->setBodyPSensor(local_transform); // <- Put your calibration info here
auto preintegration = std::make_shared<gtsam::PreintegratedImuMeasurements>(parameters, prior_imu_bias);

Here's an example using IMU preintegration: https://github.com/borglab/gtsam/blob/develop/examples/ImuFactorsExample.cpp

Replies: 1 comment 2 replies

Comment options

You must be logged in to vote
2 replies
@lowellm91
Comment options

@scott-robotics
Comment options

Answer selected by ProfFan
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Category
Q&A
Labels
None yet
3 participants