18 #ifndef COVARIANCE_INSERTION__OUTPUT_TYPE_TRAIT_HPP_
19 #define COVARIANCE_INSERTION__OUTPUT_TYPE_TRAIT_HPP_
22 #include <nav_msgs/msg/odometry.hpp>
23 #include <geometry_msgs/msg/pose_stamped.hpp>
24 #include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
25 #include <geometry_msgs/msg/twist_stamped.hpp>
26 #include <geometry_msgs/msg/twist_with_covariance_stamped.hpp>
29 template<
typename InputT>
35 template<
typename InputT,
typename Enable =
void>
38 template<
typename InputT>
40 std::is_same<typename output<InputT>::type, InputT>::value>>:
public std::false_type {};
44 struct output<geometry_msgs::msg::Pose>
46 using type = geometry_msgs::msg::PoseWithCovariance;
50 struct output<geometry_msgs::msg::PoseStamped>
52 using type = geometry_msgs::msg::PoseWithCovarianceStamped;
56 struct output<geometry_msgs::msg::Twist>
58 using type = geometry_msgs::msg::TwistWithCovariance;
62 struct output<geometry_msgs::msg::TwistStamped>
64 using type = geometry_msgs::msg::TwistWithCovarianceStamped;
67 #endif // COVARIANCE_INSERTION__OUTPUT_TYPE_TRAIT_HPP_