odom_subscriber.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #ifndef NAV_2D_UTILS_ODOM_SUBSCRIBER_H
36 #define NAV_2D_UTILS_ODOM_SUBSCRIBER_H
37 
38 #include <ros/ros.h>
40 #include <nav_msgs/Odometry.h>
41 #include <nav_2d_msgs/Twist2DStamped.h>
42 #include <string>
43 
44 namespace nav_2d_utils
45 {
46 
52 {
53 public:
60  explicit OdomSubscriber(ros::NodeHandle& nh, std::string default_topic = "odom")
61  {
62  std::string odom_topic;
63  nh.param("odom_topic", odom_topic, default_topic);
64  odom_sub_ = nh.subscribe<nav_msgs::Odometry>(odom_topic, 1,
65  std::bind(&OdomSubscriber::odomCallback, this,
66  std::placeholders::_1));
67  }
68 
69  inline nav_2d_msgs::Twist2D getTwist() { return odom_vel_.velocity; }
70  inline nav_2d_msgs::Twist2DStamped getTwistStamped() { return odom_vel_; }
71 
72 protected:
73  void odomCallback(const nav_msgs::Odometry::ConstPtr& msg)
74  {
75  ROS_INFO_ONCE("odom received!");
76  boost::mutex::scoped_lock lock(odom_mutex_);
77  odom_vel_.header = msg->header;
78  odom_vel_.velocity = twist3Dto2D(msg->twist.twist);
79  }
80 
82  nav_2d_msgs::Twist2DStamped odom_vel_;
83  boost::mutex odom_mutex_;
84 };
85 
86 } // namespace nav_2d_utils
87 
88 #endif // NAV_2D_UTILS_ODOM_SUBSCRIBER_H
nav_2d_utils::OdomSubscriber
Definition: odom_subscriber.h:51
nav_2d_utils::OdomSubscriber::odom_sub_
ros::Subscriber odom_sub_
Definition: odom_subscriber.h:81
ros.h
nav_2d_utils::OdomSubscriber::OdomSubscriber
OdomSubscriber(ros::NodeHandle &nh, std::string default_topic="odom")
Constructor that subscribes to an Odometry topic.
Definition: odom_subscriber.h:60
nav_2d_utils::OdomSubscriber::odomCallback
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
Definition: odom_subscriber.h:73
conversions.h
nav_2d_utils::OdomSubscriber::getTwistStamped
nav_2d_msgs::Twist2DStamped getTwistStamped()
Definition: odom_subscriber.h:70
ROS_INFO_ONCE
#define ROS_INFO_ONCE(...)
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
nav_2d_utils::OdomSubscriber::odom_mutex_
boost::mutex odom_mutex_
Definition: odom_subscriber.h:83
nav_2d_utils::OdomSubscriber::getTwist
nav_2d_msgs::Twist2D getTwist()
Definition: odom_subscriber.h:69
nav_2d_utils
A set of utility functions for Bounds objects interacting with other messages/types.
Definition: bounds.h:45
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
nav_2d_utils::OdomSubscriber::odom_vel_
nav_2d_msgs::Twist2DStamped odom_vel_
Definition: odom_subscriber.h:82
nav_2d_utils::twist3Dto2D
nav_2d_msgs::Twist2D twist3Dto2D(const geometry_msgs::Twist &cmd_vel)
Definition: conversions.cpp:51
ros::NodeHandle
ros::Subscriber


nav_2d_utils
Author(s):
autogenerated on Sun May 18 2025 02:47:23