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 <boost/thread/mutex.hpp>
43 #include <string>
44 
45 namespace nav_2d_utils
46 {
47 
53 {
54 public:
61  explicit OdomSubscriber(ros::NodeHandle& nh, std::string default_topic = "odom")
62  {
63  std::string odom_topic;
64  nh.param("odom_topic", odom_topic, default_topic);
65  odom_sub_ = nh.subscribe<nav_msgs::Odometry>(odom_topic, 1, boost::bind(&OdomSubscriber::odomCallback, this, _1));
66  }
67 
68  inline nav_2d_msgs::Twist2D getTwist() { return odom_vel_.velocity; }
69  inline nav_2d_msgs::Twist2DStamped getTwistStamped() { return odom_vel_; }
70 
71 protected:
72  void odomCallback(const nav_msgs::Odometry::ConstPtr& msg)
73  {
74  ROS_INFO_ONCE("odom received!");
75  boost::mutex::scoped_lock lock(odom_mutex_);
76  odom_vel_.header = msg->header;
77  odom_vel_.velocity = twist3Dto2D(msg->twist.twist);
78  }
79 
81  nav_2d_msgs::Twist2DStamped odom_vel_;
82  boost::mutex odom_mutex_;
83 };
84 
85 } // namespace nav_2d_utils
86 
87 #endif // NAV_2D_UTILS_ODOM_SUBSCRIBER_H
A set of utility functions for Bounds objects interacting with other messages/types.
Definition: bounds.h:45
nav_2d_msgs::Twist2DStamped getTwistStamped()
#define ROS_INFO_ONCE(...)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
nav_2d_msgs::Twist2D getTwist()
bool param(const std::string &param_name, T &param_val, const T &default_val) const
OdomSubscriber(ros::NodeHandle &nh, std::string default_topic="odom")
Constructor that subscribes to an Odometry topic.
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
nav_2d_msgs::Twist2D twist3Dto2D(const geometry_msgs::Twist &cmd_vel)
Definition: conversions.cpp:51
nav_2d_msgs::Twist2DStamped odom_vel_


nav_2d_utils
Author(s):
autogenerated on Sun Jan 10 2021 04:08:32