35 #ifndef NAV_2D_UTILS__ODOM_SUBSCRIBER_HPP_
36 #define NAV_2D_UTILS__ODOM_SUBSCRIBER_HPP_
42 #include "nav_2d_msgs/msg/twist2_d_stamped.hpp"
43 #include "nav_msgs/msg/odometry.hpp"
44 #include "nav2_util/lifecycle_node.hpp"
45 #include "rclcpp/rclcpp.hpp"
46 #include "nav2_util/node_utils.hpp"
48 namespace nav_2d_utils
65 nav2_util::LifecycleNode::SharedPtr nh,
66 std::string default_topic =
"odom")
68 nav2_util::declare_parameter_if_not_declared(
69 nh,
"odom_topic", rclcpp::ParameterValue(default_topic));
71 std::string odom_topic;
72 nh->get_parameter_or(
"odom_topic", odom_topic, default_topic);
74 nh->create_subscription<nav_msgs::msg::Odometry>(
76 rclcpp::SystemDefaultsQoS(),
77 std::bind(&OdomSubscriber::odomCallback,
this, std::placeholders::_1));
80 inline nav_2d_msgs::msg::Twist2D getTwist() {
return odom_vel_.velocity;}
81 inline nav_2d_msgs::msg::Twist2DStamped getTwistStamped() {
return odom_vel_;}
84 void odomCallback(
const nav_msgs::msg::Odometry::SharedPtr msg)
87 std::lock_guard<std::mutex> lock(odom_mutex_);
88 odom_vel_.header = msg->header;
89 odom_vel_.velocity.x = msg->twist.twist.linear.x;
90 odom_vel_.velocity.y = msg->twist.twist.linear.y;
91 odom_vel_.velocity.theta = msg->twist.twist.angular.z;
94 rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_sub_;
95 nav_2d_msgs::msg::Twist2DStamped odom_vel_;
96 std::mutex odom_mutex_;
OdomSubscriber(nav2_util::LifecycleNode::SharedPtr nh, std::string default_topic="odom")
Constructor that subscribes to an Odometry topic.