odometry_helper_ros.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: TKruse
36  *********************************************************************/
38 
39 namespace base_local_planner {
40 
41 OdometryHelperRos::OdometryHelperRos(std::string odom_topic) {
42  setOdomTopic( odom_topic );
43 }
44 
45 void OdometryHelperRos::odomCallback(const nav_msgs::Odometry::ConstPtr& msg) {
46  ROS_INFO_ONCE("odom received!");
47 
48  //we assume that the odometry is published in the frame of the base
49  boost::mutex::scoped_lock lock(odom_mutex_);
50  base_odom_.twist.twist.linear.x = msg->twist.twist.linear.x;
51  base_odom_.twist.twist.linear.y = msg->twist.twist.linear.y;
52  base_odom_.twist.twist.angular.z = msg->twist.twist.angular.z;
53  base_odom_.child_frame_id = msg->child_frame_id;
54 // ROS_DEBUG_NAMED("dwa_local_planner", "In the odometry callback with velocity values: (%.2f, %.2f, %.2f)",
55 // base_odom_.twist.twist.linear.x, base_odom_.twist.twist.linear.y, base_odom_.twist.twist.angular.z);
56 }
57 
58 //copy over the odometry information
59 void OdometryHelperRos::getOdom(nav_msgs::Odometry& base_odom) {
60  boost::mutex::scoped_lock lock(odom_mutex_);
61  base_odom = base_odom_;
62 }
63 
64 
66  // Set current velocities from odometry
67  geometry_msgs::Twist global_vel;
68  {
69  boost::mutex::scoped_lock lock(odom_mutex_);
70  global_vel.linear.x = base_odom_.twist.twist.linear.x;
71  global_vel.linear.y = base_odom_.twist.twist.linear.y;
72  global_vel.angular.z = base_odom_.twist.twist.angular.z;
73 
74  robot_vel.frame_id_ = base_odom_.child_frame_id;
75  }
76  robot_vel.setData(tf::Transform(tf::createQuaternionFromYaw(global_vel.angular.z), tf::Vector3(global_vel.linear.x, global_vel.linear.y, 0)));
77  robot_vel.stamp_ = ros::Time();
78 }
79 
80 void OdometryHelperRos::setOdomTopic(std::string odom_topic)
81 {
82  if( odom_topic != odom_topic_ )
83  {
84  odom_topic_ = odom_topic;
85 
86  if( odom_topic_ != "" )
87  {
88  ros::NodeHandle gn;
89  odom_sub_ = gn.subscribe<nav_msgs::Odometry>( odom_topic_, 1, boost::bind( &OdometryHelperRos::odomCallback, this, _1 ));
90  }
91  else
92  {
94  }
95  }
96 }
97 
98 } /* namespace base_local_planner */
void getRobotVel(tf::Stamped< tf::Pose > &robot_vel)
void setData(const T &input)
#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())
void getOdom(nav_msgs::Odometry &base_odom)
static Quaternion createQuaternionFromYaw(double yaw)
OdometryHelperRos(std::string odom_topic="")
Constructor.
ros::Time stamp_
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
Callback for receiving odometry data.
std::string frame_id_
void setOdomTopic(std::string odom_topic)
Set the odometry topic. This overrides what was set in the constructor, if anything.


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:44:25