18 #ifndef COVARIANCE_INSERTION__ADD_COVARIANCE_HPP_
19 #define COVARIANCE_INSERTION__ADD_COVARIANCE_HPP_
29 namespace covariance_insertion
39 template<
typename MsgT,
typename ScalarT>
42 const std::vector<ScalarT> & covariance,
47 throw std::runtime_error(
"Message has covariance directly, but asked for field: " + field);
49 if (msg->covariance.size() != covariance.size()) {
50 throw std::runtime_error(
51 "Number of covariance entries does not match. The message has " +
52 std::to_string(msg->covariance.size()) +
" entries, while there are " +
53 std::to_string(covariance.size()) +
" entries in parameters of this node.");
55 for (
auto i = 0U; i < covariance.size(); ++i) {
56 msg->covariance[i] = covariance[i];
60 template<
typename MsgT,
typename ScalarT>
63 const std::vector<ScalarT> & covariance,
64 const std::string & field)
74 template<
typename MsgT,
typename ScalarT>
77 const std::vector<ScalarT> & covariance,
78 const std::enable_if_t<
85 throw std::runtime_error(
"Cannot set: " + field);
90 template<
typename MsgT,
typename ScalarT>
93 const std::vector<ScalarT> & covariance,
94 const std::enable_if_t<
101 throw std::runtime_error(
"Cannot set: " + field);
106 template<
typename MsgT,
typename ScalarT>
109 const std::vector<ScalarT> & covariance,
110 const std::enable_if_t<
121 throw std::runtime_error(
"Cannot set: " + field);
128 #endif // COVARIANCE_INSERTION__ADD_COVARIANCE_HPP_