18 #ifndef NODE_ADDERS_UTILITIES_H_
19 #define NODE_ADDERS_UTILITIES_H_
24 #include <gtsam/inference/Key.h>
25 #include <gtsam/nonlinear/NonlinearFactorGraph.h>
29 template <
typename FactorType>
30 bool RemoveFactor(
const gtsam::KeyVector& keys, gtsam::NonlinearFactorGraph& factors);
33 template <
typename FactorType,
typename NodesType>
35 const NodesType&
nodes, gtsam::NonlinearFactorGraph& factors);
38 gtsam::Matrix
Covariance(
const gtsam::SharedNoiseModel& robust_gaussian_noise);
41 template <
typename FactorType>
42 bool RemoveFactor(
const gtsam::KeyVector& keys, gtsam::NonlinearFactorGraph& factors) {
43 for (
auto factor_it = factors.begin(); factor_it != factors.end(); ++factor_it) {
44 if (!
dynamic_cast<FactorType*
>(factor_it->get()))
continue;
45 bool contains_keys =
true;
46 for (
const auto& key : keys) {
47 if ((*factor_it)->find(key) == std::end((*factor_it)->keys())) {
48 contains_keys =
false;
53 factors.erase(factor_it);
60 template <
typename FactorType,
typename NodesType>
62 const NodesType&
nodes, gtsam::NonlinearFactorGraph& factors) {
63 const auto keys_a =
nodes.Keys(timestamp_a);
65 LogError(
"RemoveRelativeFactor: Failed to get keys for timestamp_a.");
69 const auto keys_b =
nodes.Keys(timestamp_b);
71 LogError(
"RemoveRelativeFactor: Failed to get keys for timestamp_b.");
75 gtsam::KeyVector combined_keys = keys_a;
76 combined_keys.insert(combined_keys.cend(), keys_b.cbegin(), keys_b.cend());
77 return RemoveFactor<FactorType>(combined_keys, factors);
81 #endif // NODE_ADDERS_UTILITIES_H_