gazebo_ros_planar_move.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2013 Open Source Robotics Foundation
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 
18 /*
19  * Desc: Simple model controller that uses a twist message to move a robot on
20  * the xy plane.
21  * Author: Piyush Khandelwal
22  * Date: 29 July 2013
23  */
24 
26 #ifdef ENABLE_PROFILER
27 #include <ignition/common/Profiler.hh>
28 #endif
29 
30 namespace gazebo
31 {
32 
34 
36 
37  // Load the controller
38  void GazeboRosPlanarMove::Load(physics::ModelPtr parent,
39  sdf::ElementPtr sdf)
40  {
41 
42  parent_ = parent;
43 
44  /* Parse parameters */
45 
46  robot_namespace_ = "";
47  if (!sdf->HasElement("robotNamespace"))
48  {
49  ROS_INFO_NAMED("planar_move", "PlanarMovePlugin missing <robotNamespace>, "
50  "defaults to \"%s\"", robot_namespace_.c_str());
51  }
52  else
53  {
55  sdf->GetElement("robotNamespace")->Get<std::string>();
56  }
57 
58  command_topic_ = "cmd_vel";
59  if (!sdf->HasElement("commandTopic"))
60  {
61  ROS_WARN_NAMED("planar_move", "PlanarMovePlugin (ns = %s) missing <commandTopic>, "
62  "defaults to \"%s\"",
63  robot_namespace_.c_str(), command_topic_.c_str());
64  }
65  else
66  {
67  command_topic_ = sdf->GetElement("commandTopic")->Get<std::string>();
68  }
69 
70  odometry_topic_ = "odom";
71  if (!sdf->HasElement("odometryTopic"))
72  {
73  ROS_WARN_NAMED("planar_move", "PlanarMovePlugin (ns = %s) missing <odometryTopic>, "
74  "defaults to \"%s\"",
75  robot_namespace_.c_str(), odometry_topic_.c_str());
76  }
77  else
78  {
79  odometry_topic_ = sdf->GetElement("odometryTopic")->Get<std::string>();
80  }
81 
82  odometry_frame_ = "odom";
83  if (!sdf->HasElement("odometryFrame"))
84  {
85  ROS_WARN_NAMED("planar_move", "PlanarMovePlugin (ns = %s) missing <odometryFrame>, "
86  "defaults to \"%s\"",
87  robot_namespace_.c_str(), odometry_frame_.c_str());
88  }
89  else
90  {
91  odometry_frame_ = sdf->GetElement("odometryFrame")->Get<std::string>();
92  }
93 
94  robot_base_frame_ = "base_footprint";
95  if (!sdf->HasElement("robotBaseFrame"))
96  {
97  ROS_WARN_NAMED("planar_move", "PlanarMovePlugin (ns = %s) missing <robotBaseFrame>, "
98  "defaults to \"%s\"",
99  robot_namespace_.c_str(), robot_base_frame_.c_str());
100  }
101  else
102  {
103  robot_base_frame_ = sdf->GetElement("robotBaseFrame")->Get<std::string>();
104  }
105 
106  odometry_rate_ = 20.0;
107  if (!sdf->HasElement("odometryRate"))
108  {
109  ROS_WARN_NAMED("planar_move", "PlanarMovePlugin (ns = %s) missing <odometryRate>, "
110  "defaults to %f",
112  }
113  else
114  {
115  odometry_rate_ = sdf->GetElement("odometryRate")->Get<double>();
116  }
117  cmd_timeout_ = -1;
118  if (!sdf->HasElement("cmdTimeout"))
119  {
120  ROS_WARN_NAMED("planar_move", "PlanarMovePlugin (ns = %s) missing <cmdTimeout>, "
121  "defaults to %f",
122  robot_namespace_.c_str(), cmd_timeout_);
123  }
124  else
125  {
126  cmd_timeout_ = sdf->GetElement("cmdTimeout")->Get<double>();
127  }
128 
129 #if GAZEBO_MAJOR_VERSION >= 8
130  last_odom_publish_time_ = parent_->GetWorld()->SimTime();
131 #else
132  last_odom_publish_time_ = parent_->GetWorld()->GetSimTime();
133 #endif
134 #if GAZEBO_MAJOR_VERSION >= 8
135  last_odom_pose_ = parent_->WorldPose();
136 #else
137  last_odom_pose_ = parent_->GetWorldPose().Ign();
138 #endif
139  x_ = 0;
140  y_ = 0;
141  rot_ = 0;
142  alive_ = true;
143 
144  // Ensure that ROS has been initialized and subscribe to cmd_vel
145  if (!ros::isInitialized())
146  {
147  ROS_FATAL_STREAM_NAMED("planar_move", "PlanarMovePlugin (ns = " << robot_namespace_
148  << "). A ROS node for Gazebo has not been initialized, "
149  << "unable to load plugin. Load the Gazebo system plugin "
150  << "'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
151  return;
152  }
154 
155  ROS_DEBUG_NAMED("planar_move", "OCPlugin (%s) has started",
156  robot_namespace_.c_str());
157 
160 
161  // subscribe to the odometry topic
163  ros::SubscribeOptions::create<geometry_msgs::Twist>(command_topic_, 1,
164  boost::bind(&GazeboRosPlanarMove::cmdVelCallback, this, _1),
165  ros::VoidPtr(), &queue_);
166 
167  vel_sub_ = rosnode_->subscribe(so);
168  odometry_pub_ = rosnode_->advertise<nav_msgs::Odometry>(odometry_topic_, 1);
169 
170  // start custom queue for diff drive
172  boost::thread(boost::bind(&GazeboRosPlanarMove::QueueThread, this));
173 
174  // listen to the update event (broadcast every simulation iteration)
176  event::Events::ConnectWorldUpdateBegin(
177  boost::bind(&GazeboRosPlanarMove::UpdateChild, this));
178 
179  }
180 
181  // Update the controller
183  {
184 #ifdef ENABLE_PROFILER
185  IGN_PROFILE("GazeboRosPlanarMove::UpdateChild");
186  IGN_PROFILE_BEGIN("fill ROS message");
187 #endif
188  boost::mutex::scoped_lock scoped_lock(lock);
189  if (cmd_timeout_>=0)
190  {
192  {
193  x_ = 0;
194  y_ = 0;
195  rot_ = 0;
196  }
197  }
198 #if GAZEBO_MAJOR_VERSION >= 8
199  ignition::math::Pose3d pose = parent_->WorldPose();
200 #else
201  ignition::math::Pose3d pose = parent_->GetWorldPose().Ign();
202 #endif
203  float yaw = pose.Rot().Yaw();
204  parent_->SetLinearVel(ignition::math::Vector3d(
205  x_ * cosf(yaw) - y_ * sinf(yaw),
206  y_ * cosf(yaw) + x_ * sinf(yaw),
207  0));
208  parent_->SetAngularVel(ignition::math::Vector3d(0, 0, rot_));
209 #ifdef ENABLE_PROFILER
210  IGN_PROFILE_END();
211 #endif
212  if (odometry_rate_ > 0.0) {
213 #if GAZEBO_MAJOR_VERSION >= 8
214  common::Time current_time = parent_->GetWorld()->SimTime();
215 #else
216  common::Time current_time = parent_->GetWorld()->GetSimTime();
217 #endif
218  double seconds_since_last_update =
219  (current_time - last_odom_publish_time_).Double();
220  if (seconds_since_last_update > (1.0 / odometry_rate_)) {
221 #ifdef ENABLE_PROFILER
222  IGN_PROFILE_BEGIN("publishOdometry");
223 #endif
224  publishOdometry(seconds_since_last_update);
225 #ifdef ENABLE_PROFILER
226  IGN_PROFILE_END();
227 #endif
228  last_odom_publish_time_ = current_time;
229  }
230  }
231  }
232 
233  // Finalize the controller
235  alive_ = false;
236  queue_.clear();
237  queue_.disable();
238  rosnode_->shutdown();
239  callback_queue_thread_.join();
240  }
241 
243  const geometry_msgs::Twist::ConstPtr& cmd_msg)
244  {
245  boost::mutex::scoped_lock scoped_lock(lock);
247  x_ = cmd_msg->linear.x;
248  y_ = cmd_msg->linear.y;
249  rot_ = cmd_msg->angular.z;
250  }
251 
253  {
254  static const double timeout = 0.01;
255  while (alive_ && rosnode_->ok())
256  {
258  }
259  }
260 
262  {
263 
264  ros::Time current_time = ros::Time::now();
265  std::string odom_frame = tf::resolve(tf_prefix_, odometry_frame_);
266  std::string base_footprint_frame =
268 
269  // getting data for base_footprint to odom transform
270 #if GAZEBO_MAJOR_VERSION >= 8
271  ignition::math::Pose3d pose = this->parent_->WorldPose();
272 #else
273  ignition::math::Pose3d pose = this->parent_->GetWorldPose().Ign();
274 #endif
275 
276  tf::Quaternion qt(pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W());
277  tf::Vector3 vt(pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z());
278 
279  tf::Transform base_footprint_to_odom(qt, vt);
280  transform_broadcaster_->sendTransform(
281  tf::StampedTransform(base_footprint_to_odom, current_time, odom_frame,
282  base_footprint_frame));
283 
284  // publish odom topic
285  odom_.pose.pose.position.x = pose.Pos().X();
286  odom_.pose.pose.position.y = pose.Pos().Y();
287 
288  odom_.pose.pose.orientation.x = pose.Rot().X();
289  odom_.pose.pose.orientation.y = pose.Rot().Y();
290  odom_.pose.pose.orientation.z = pose.Rot().Z();
291  odom_.pose.pose.orientation.w = pose.Rot().W();
292  odom_.pose.covariance[0] = 0.00001;
293  odom_.pose.covariance[7] = 0.00001;
294  odom_.pose.covariance[14] = 1000000000000.0;
295  odom_.pose.covariance[21] = 1000000000000.0;
296  odom_.pose.covariance[28] = 1000000000000.0;
297  odom_.pose.covariance[35] = 0.001;
298 
299  // get velocity in /odom frame
300  ignition::math::Vector3d linear;
301  linear.X() = (pose.Pos().X() - last_odom_pose_.Pos().X()) / step_time;
302  linear.Y() = (pose.Pos().Y() - last_odom_pose_.Pos().Y()) / step_time;
303  if (rot_ > M_PI / step_time)
304  {
305  // we cannot calculate the angular velocity correctly
306  odom_.twist.twist.angular.z = rot_;
307  }
308  else
309  {
310  float last_yaw = last_odom_pose_.Rot().Yaw();
311  float current_yaw = pose.Rot().Yaw();
312  while (current_yaw < last_yaw - M_PI) current_yaw += 2 * M_PI;
313  while (current_yaw > last_yaw + M_PI) current_yaw -= 2 * M_PI;
314  float angular_diff = current_yaw - last_yaw;
315  odom_.twist.twist.angular.z = angular_diff / step_time;
316  }
317  last_odom_pose_ = pose;
318 
319  // convert velocity to child_frame_id (aka base_footprint)
320  float yaw = pose.Rot().Yaw();
321  odom_.twist.twist.linear.x = cosf(yaw) * linear.X() + sinf(yaw) * linear.Y();
322  odom_.twist.twist.linear.y = cosf(yaw) * linear.Y() - sinf(yaw) * linear.X();
323 
324  odom_.header.stamp = current_time;
325  odom_.header.frame_id = odom_frame;
326  odom_.child_frame_id = base_footprint_frame;
327 
329  }
330 
332 }
gazebo::GazeboRosPlanarMove::rosnode_
boost::shared_ptr< ros::NodeHandle > rosnode_
Definition: gazebo_ros_planar_move.h:64
gazebo::GazeboRosPlanarMove::odom_
nav_msgs::Odometry odom_
Definition: gazebo_ros_planar_move.h:68
boost::shared_ptr< void >
gazebo
gazebo::GazeboRosPlanarMove::cmd_timeout_
double cmd_timeout_
Definition: gazebo_ros_planar_move.h:79
gazebo::GazeboRosPlanarMove::rot_
double rot_
Definition: gazebo_ros_planar_move.h:92
gazebo::GazeboRosPlanarMove
Definition: gazebo_ros_planar_move.h:47
gazebo_ros_planar_move.h
ros::CallbackQueue::clear
void clear()
gazebo::GazeboRosPlanarMove::publishOdometry
void publishOdometry(double step_time)
Definition: gazebo_ros_planar_move.cpp:261
gazebo::GazeboRosPlanarMove::vel_sub_
ros::Subscriber vel_sub_
Definition: gazebo_ros_planar_move.h:66
tf::resolve
std::string resolve(const std::string &prefix, const std::string &frame_name)
gazebo::GazeboRosPlanarMove::queue_
ros::CallbackQueue queue_
Definition: gazebo_ros_planar_move.h:83
tf::StampedTransform
gazebo::GazeboRosPlanarMove::callback_queue_thread_
boost::thread callback_queue_thread_
Definition: gazebo_ros_planar_move.h:84
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
gazebo::GazeboRosPlanarMove::FiniChild
virtual void FiniChild()
Definition: gazebo_ros_planar_move.cpp:234
gazebo::GazeboRosPlanarMove::parent_
physics::ModelPtr parent_
Definition: gazebo_ros_planar_move.h:61
gazebo::GazeboRosPlanarMove::UpdateChild
virtual void UpdateChild()
Definition: gazebo_ros_planar_move.cpp:182
gazebo::GazeboRosPlanarMove::Load
void Load(physics::ModelPtr parent, sdf::ElementPtr sdf)
Definition: gazebo_ros_planar_move.cpp:38
gazebo::GazeboRosPlanarMove::cmdVelCallback
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
Definition: gazebo_ros_planar_move.cpp:242
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
tf::TransformBroadcaster
tf::getPrefixParam
std::string getPrefixParam(ros::NodeHandle &nh)
gazebo::GZ_REGISTER_MODEL_PLUGIN
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
gazebo::GazeboRosPlanarMove::~GazeboRosPlanarMove
~GazeboRosPlanarMove()
Definition: gazebo_ros_planar_move.cpp:35
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo::GazeboRosPlanarMove::odometry_frame_
std::string odometry_frame_
Definition: gazebo_ros_planar_move.h:76
gazebo::GazeboRosPlanarMove::update_connection_
event::ConnectionPtr update_connection_
Definition: gazebo_ros_planar_move.h:62
gazebo::GazeboRosPlanarMove::alive_
bool alive_
Definition: gazebo_ros_planar_move.h:93
tf::Transform
gazebo::GazeboRosPlanarMove::odometry_rate_
double odometry_rate_
Definition: gazebo_ros_planar_move.h:78
gazebo::GazeboRosPlanarMove::robot_base_frame_
std::string robot_base_frame_
Definition: gazebo_ros_planar_move.h:77
gazebo::GazeboRosPlanarMove::x_
double x_
Definition: gazebo_ros_planar_move.h:90
gazebo::GazeboRosPlanarMove::last_odom_publish_time_
common::Time last_odom_publish_time_
Definition: gazebo_ros_planar_move.h:94
gazebo::GazeboRosPlanarMove::odometry_pub_
ros::Publisher odometry_pub_
Definition: gazebo_ros_planar_move.h:65
ros::SubscribeOptions
ros::Time
gazebo::GazeboRosPlanarMove::lock
boost::mutex lock
Definition: gazebo_ros_planar_move.h:71
gazebo::GazeboRosPlanarMove::odometry_topic_
std::string odometry_topic_
Definition: gazebo_ros_planar_move.h:75
gazebo::GazeboRosPlanarMove::transform_broadcaster_
boost::shared_ptr< tf::TransformBroadcaster > transform_broadcaster_
Definition: gazebo_ros_planar_move.h:67
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
gazebo::GazeboRosPlanarMove::command_topic_
std::string command_topic_
Definition: gazebo_ros_planar_move.h:74
gazebo::GazeboRosPlanarMove::GazeboRosPlanarMove
GazeboRosPlanarMove()
Definition: gazebo_ros_planar_move.cpp:33
gazebo::GazeboRosPlanarMove::tf_prefix_
std::string tf_prefix_
Definition: gazebo_ros_planar_move.h:69
ros::WallDuration
tf::Quaternion
ros::CallbackQueue::callAvailable
void callAvailable()
gazebo::GazeboRosPlanarMove::y_
double y_
Definition: gazebo_ros_planar_move.h:91
gazebo::GazeboRosPlanarMove::QueueThread
void QueueThread()
Definition: gazebo_ros_planar_move.cpp:252
ros::CallbackQueue::disable
void disable()
ros::NodeHandle
gazebo::GazeboRosPlanarMove::last_odom_pose_
ignition::math::Pose3d last_odom_pose_
Definition: gazebo_ros_planar_move.h:95
ros::Time::now
static Time now()
gazebo::GazeboRosPlanarMove::last_cmd_received_time_
ros::Time last_cmd_received_time_
Definition: gazebo_ros_planar_move.h:80
gazebo::GazeboRosPlanarMove::robot_namespace_
std::string robot_namespace_
Definition: gazebo_ros_planar_move.h:73


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Nov 23 2023 03:50:28