Skip to content

Commit 3a8c961

Browse files
authored
Merge pull request #93 from themightyoarfish/macos
apple clang compat
2 parents fdb815d + 846a2d0 commit 3a8c961

4 files changed

Lines changed: 7 additions & 7 deletions

File tree

include/gtsam_points/factors/impl/integrated_ct_gicp_factor_impl.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -195,7 +195,7 @@ void IntegratedCT_GICPFactor_<TargetFrame, SourceFrame>::update_correspondences(
195195
const Eigen::Matrix4d RCR = (cov_B + pose * cov_A * pose.transpose());
196196

197197
mahalanobis[i].setZero();
198-
mahalanobis[i].block<3, 3>(0, 0) = RCR.block<3, 3>(0, 0).inverse();
198+
mahalanobis[i].template block<3, 3>(0, 0) = RCR.block<3, 3>(0, 0).inverse();
199199
}
200200
};
201201

@@ -217,4 +217,4 @@ void IntegratedCT_GICPFactor_<TargetFrame, SourceFrame>::update_correspondences(
217217
#endif
218218
}
219219
}
220-
} // namespace gtsam_points
220+
} // namespace gtsam_points

include/gtsam_points/factors/impl/integrated_gicp_factor_impl.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -177,7 +177,7 @@ void IntegratedGICPFactor_<TargetFrame, SourceFrame>::update_correspondences(con
177177
const auto& target_cov = frame::cov(*target, correspondences[i]);
178178
const Eigen::Matrix4d RCR = (target_cov + delta.matrix() * frame::cov(*source, i) * delta.matrix().transpose());
179179
mahalanobis_full[i].setZero();
180-
mahalanobis_full[i].topLeftCorner<3, 3>() = RCR.topLeftCorner<3, 3>().inverse();
180+
mahalanobis_full[i].template topLeftCorner<3, 3>() = RCR.topLeftCorner<3, 3>().inverse();
181181
}
182182
break;
183183
case FusedCovCacheMode::COMPACT:

include/gtsam_points/factors/impl/integrated_vgicp_factor_impl.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -137,7 +137,7 @@ void IntegratedVGICPFactor_<SourceFrame>::update_correspondences(const Eigen::Is
137137
case FusedCovCacheMode::FULL: {
138138
const Eigen::Matrix4d RCR = (voxel->cov + delta.matrix() * frame::cov(*source, i) * delta.matrix().transpose());
139139
mahalanobis_full[i].setZero();
140-
mahalanobis_full[i].topLeftCorner<3, 3>() = RCR.topLeftCorner<3, 3>().inverse();
140+
mahalanobis_full[i].template topLeftCorner<3, 3>() = RCR.topLeftCorner<3, 3>().inverse();
141141
break;
142142
}
143143
case FusedCovCacheMode::COMPACT: {

src/gtsam_points/optimizers/incremental_fixed_lag_smoother_ext_with_fallback.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -177,8 +177,8 @@ void IncrementalFixedLagSmootherExtWithFallback::fallback_smoother() const {
177177
if (minmax_id == minmax_ids.end()) {
178178
minmax_ids.emplace_hint(minmax_id, symbol.chr(), std::make_pair(symbol.index(), symbol.index()));
179179
} else {
180-
minmax_id->second.first = std::min(minmax_id->second.first, symbol.index());
181-
minmax_id->second.second = std::max(minmax_id->second.second, symbol.index());
180+
minmax_id->second.first = std::min<std::uint64_t>(minmax_id->second.first, symbol.index());
181+
minmax_id->second.second = std::max<std::uint64_t>(minmax_id->second.second, symbol.index());
182182
}
183183
}
184184

@@ -332,4 +332,4 @@ void IncrementalFixedLagSmootherExtWithFallback::fallback_smoother() const {
332332
smoother->update(new_factors, values, new_stamps);
333333
}
334334

335-
} // namespace gtsam_points
335+
} // namespace gtsam_points

0 commit comments

Comments
 (0)