odom_plugin.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
19 
21 
23 
26 
27 #include <std_srvs/Trigger.h>
28 
29 #include "GeomController.h"
30 
32 {
33 
34 // this controller gets access to the JointStateInterface
35 class OdometryController: public GeomController<hardware_interface::JointStateInterface, UndercarriageGeom>
36 {
37 public:
39 
40  virtual bool init(hardware_interface::JointStateInterface* hw, ros::NodeHandle &root_nh, ros::NodeHandle& controller_nh){
41 
42  if(!GeomController::init(hw, controller_nh)) return false;
43 
44  double publish_rate;
45  if (!controller_nh.getParam("publish_rate", publish_rate)){
46  ROS_ERROR("Parameter 'publish_rate' not set");
47  return false;
48  }
49  if(publish_rate <= 0){
50  ROS_ERROR_STREAM("publish_rate must be positive.");
51  return false;
52  }
53 
54  const std::string frame_id = controller_nh.param("frame_id", std::string("odom"));
55  const std::string child_frame_id = controller_nh.param("child_frame_id", std::string("base_footprint"));
56  const double cov_pose = controller_nh.param("cov_pose", 0.1);
57  const double cov_twist = controller_nh.param("cov_twist", 0.1);
58 
59  odom_tracker_.reset(new OdometryTracker(frame_id, child_frame_id, cov_pose, cov_twist));
60  odom_ = odom_tracker_->getOdometry();
61 
62  topic_pub_odometry_ = controller_nh.advertise<nav_msgs::Odometry>("odometry", 1);
63 
64  bool broadcast_tf = true;
65  controller_nh.getParam("broadcast_tf", broadcast_tf);
66 
67  if(broadcast_tf){
68  odom_tf_.header.frame_id = frame_id;
69  odom_tf_.child_frame_id = child_frame_id;
71  }
72 
73  publish_timer_ = controller_nh.createTimer(ros::Duration(1/publish_rate), &OdometryController::publish, this);
74  service_reset_ = controller_nh.advertiseService("reset_odometry", &OdometryController::srv_reset, this);
75 
76  return true;
77  }
78  virtual void starting(const ros::Time& time){
79  if(time != stop_time_) odom_tracker_->init(time); // do not init odometry on restart
80  reset_ = false;
81  }
82 
83  virtual bool srv_reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
84  {
85  if(!isRunning()){
86  res.message = "not running";
87  res.success = false;
88  }else{
89  boost::mutex::scoped_lock lock(mutex_);
90  reset_ = true;
91  lock.unlock();
92  res.success = true;
93  ROS_INFO("Resetting odometry to zero.");
94  }
95 
96  return true;
97  }
98 
99  virtual void update(const ros::Time& time, const ros::Duration& period){
100 
101  updateState();
102 
103  geom_->calcDirect(platform_state_);
104 
106 
107  boost::mutex::scoped_try_lock lock(mutex_);
108  if(lock){
109  if(reset_){
110  odom_tracker_->init(time);
111  reset_ = false;
112  }
113  odom_ = odom_tracker_->getOdometry();
114  }
115 
116  }
117  virtual void stopping(const ros::Time& time) { stop_time_ = time; }
118 
119 private:
121 
122  ros::Publisher topic_pub_odometry_; // calculated (measured) velocity, rotation and pose (odometry-based) for the robot
123  ros::ServiceServer service_reset_; // service to reset odometry to zero
124 
125  boost::scoped_ptr<tf::TransformBroadcaster> tf_broadcast_odometry_; // according transformation for the tf broadcaster
126  boost::scoped_ptr<OdometryTracker> odom_tracker_;
128  nav_msgs::Odometry odom_;
129  bool reset_;
130  boost::mutex mutex_;
131  geometry_msgs::TransformStamped odom_tf_;
133 
134 
135  void publish(const ros::TimerEvent& event){
136  if(!isRunning()) return;
137 
138  boost::mutex::scoped_lock lock(mutex_);
139 
140  topic_pub_odometry_.publish(odom_);
141 
142  if(tf_broadcast_odometry_){
143  // check prevents TF_REPEATED_DATA warning
144  if (odom_tf_.header.stamp == odom_.header.stamp){
145  // ROS_WARN_STREAM("OdometryController: already published odom_tf before");
146  // ROS_WARN_STREAM("\todom_tf: " << odom_tf_);
147  // ROS_WARN_STREAM("\todom_: " << odom_);
148  // ROS_WARN_STREAM("\tevent.last_expected: " << event.last_expected);
149  // ROS_WARN_STREAM("\tevent.last_real: " << event.last_real);
150  // ROS_WARN_STREAM("\tevent.current_expected: " << event.current_expected);
151  // ROS_WARN_STREAM("\tevent.current_real: " << event.current_real);
152  } else {
153  // compose and publish transform for tf package
154  // compose header
155  odom_tf_.header.stamp = odom_.header.stamp;
156  // compose data container
157  odom_tf_.transform.translation.x = odom_.pose.pose.position.x;
158  odom_tf_.transform.translation.y = odom_.pose.pose.position.y;
159  odom_tf_.transform.rotation = odom_.pose.pose.orientation;
160 
161  // publish the transform (for debugging, conflicts with robot-pose-ekf)
162  tf_broadcast_odometry_->sendTransform(odom_tf_);
163  }
164  }
165  }
166 };
167 
168 }
169 
void publish(const ros::TimerEvent &event)
virtual void starting(const ros::Time &time)
Definition: odom_plugin.cpp:78
const double getVelY()
void publish(const boost::shared_ptr< M > &message) const
virtual void update(const ros::Time &time, const ros::Duration &period)
Definition: odom_plugin.cpp:99
geometry_msgs::TransformStamped odom_tf_
virtual bool init(hardware_interface::JointStateInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Definition: odom_plugin.cpp:40
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
virtual void stopping(const ros::Time &time)
boost::scoped_ptr< tf::TransformBroadcaster > tf_broadcast_odometry_
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
const double getVelX()
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual bool srv_reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Definition: odom_plugin.cpp:83
bool init(Interface *hw, ros::NodeHandle &controller_nh)
boost::scoped_ptr< OdometryTracker > odom_tracker_
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR_STREAM(args)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)


cob_omni_drive_controller
Author(s): Christian Connette, Mathias Lüdtke
autogenerated on Thu Apr 8 2021 02:39:52