Skip to content

Commit

Permalink
Merge pull request #1181 from borglab/fix/warnings
Browse files Browse the repository at this point in the history
Fix warnings and docs
  • Loading branch information
jlblancoc authored May 1, 2022
2 parents 6931084 + 287279f commit f4bcb11
Show file tree
Hide file tree
Showing 5 changed files with 17 additions and 6 deletions.
2 changes: 1 addition & 1 deletion gtsam/geometry/Pose2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -365,7 +365,7 @@ boost::optional<Pose2> Pose2::Align(const Matrix& a, const Matrix& b) {
"Pose2:Align expects 2*N matrices of equal shape.");
}
Point2Pairs ab_pairs;
for (size_t j=0; j < a.cols(); j++) {
for (Eigen::Index j = 0; j < a.cols(); j++) {
ab_pairs.emplace_back(a.col(j), b.col(j));
}
return Pose2::Align(ab_pairs);
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Pose3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -473,7 +473,7 @@ boost::optional<Pose3> Pose3::Align(const Matrix& a, const Matrix& b) {
"Pose3:Align expects 3*N matrices of equal shape.");
}
Point3Pairs abPointPairs;
for (size_t j=0; j < a.cols(); j++) {
for (Eigen::Index j = 0; j < a.cols(); j++) {
abPointPairs.emplace_back(a.col(j), b.col(j));
}
return Pose3::Align(abPointPairs);
Expand Down
6 changes: 5 additions & 1 deletion gtsam/navigation/AHRSFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,11 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation

/**
* Add a single Gyroscope measurement to the preintegration.
* @param measureOmedga Measured angular velocity (in body frame)
* Measurements are taken to be in the sensor
* frame and conversion to the body frame is handled by `body_P_sensor` in
* `PreintegratedRotationParams` (if provided).
*
* @param measuredOmega Measured angular velocity (as given by the sensor)
* @param deltaT Time step
*/
void integrateMeasurement(const Vector3& measuredOmega, double deltaT);
Expand Down
7 changes: 5 additions & 2 deletions gtsam/navigation/CombinedImuFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -208,8 +208,11 @@ class GTSAM_EXPORT PreintegratedCombinedMeasurements : public PreintegrationType

/**
* Add a single IMU measurement to the preintegration.
* @param measuredAcc Measured acceleration (in body frame, as given by the
* sensor)
* Both accelerometer and gyroscope measurements are taken to be in the sensor
* frame and conversion to the body frame is handled by `body_P_sensor` in
* `PreintegrationParams`.
*
* @param measuredAcc Measured acceleration (as given by the sensor)
* @param measuredOmega Measured angular velocity (as given by the sensor)
* @param dt Time interval between two consecutive IMU measurements
*/
Expand Down
6 changes: 5 additions & 1 deletion gtsam/navigation/ImuFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,11 @@ class GTSAM_EXPORT PreintegratedImuMeasurements: public PreintegrationType {

/**
* Add a single IMU measurement to the preintegration.
* @param measuredAcc Measured acceleration (in body frame, as given by the sensor)
* Both accelerometer and gyroscope measurements are taken to be in the sensor
* frame and conversion to the body frame is handled by `body_P_sensor` in
* `PreintegrationParams`.
*
* @param measuredAcc Measured acceleration (as given by the sensor)
* @param measuredOmega Measured angular velocity (as given by the sensor)
* @param dt Time interval between this and the last IMU measurement
*/
Expand Down

0 comments on commit f4bcb11

Please sign in to comment.