gazebo_ros_p3d.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 #include <string>
19 #include <tf/tf.h>
20 #include <stdlib.h>
21 
23 #ifdef ENABLE_PROFILER
24 #include <ignition/common/Profiler.hh>
25 #endif
26 #include <ignition/math/Rand.hh>
27 
28 namespace gazebo
29 {
30 GZ_REGISTER_MODEL_PLUGIN(GazeboRosP3D);
31 
33 // Constructor
35 {
36 }
37 
39 // Destructor
41 {
42  this->update_connection_.reset();
43  // Finalize the controller
44  this->rosnode_->shutdown();
45  this->p3d_queue_.clear();
46  this->p3d_queue_.disable();
47  this->callback_queue_thread_.join();
48  delete this->rosnode_;
49 }
50 
52 // Load the controller
53 void GazeboRosP3D::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
54 {
55  // Get the world name.
56  this->world_ = _parent->GetWorld();
57  this->model_ = _parent;
58 
59  // load parameters
60  this->robot_namespace_ = "";
61  if (_sdf->HasElement("robotNamespace"))
62  this->robot_namespace_ =
63  _sdf->GetElement("robotNamespace")->Get<std::string>() + "/";
64 
65  if (!_sdf->HasElement("bodyName"))
66  {
67  ROS_FATAL_NAMED("p3d", "p3d plugin missing <bodyName>, cannot proceed");
68  return;
69  }
70  else
71  this->link_name_ = _sdf->GetElement("bodyName")->Get<std::string>();
72 
73  this->link_ = _parent->GetLink(this->link_name_);
74  if (!this->link_)
75  {
76  ROS_FATAL_NAMED("p3d", "gazebo_ros_p3d plugin error: bodyName: %s does not exist\n",
77  this->link_name_.c_str());
78  return;
79  }
80 
81  if (!_sdf->HasElement("topicName"))
82  {
83  ROS_FATAL_NAMED("p3d", "p3d plugin missing <topicName>, cannot proceed");
84  return;
85  }
86  else
87  this->topic_name_ = _sdf->GetElement("topicName")->Get<std::string>();
88 
89  if (!_sdf->HasElement("frameName"))
90  {
91  ROS_DEBUG_NAMED("p3d", "p3d plugin missing <frameName>, defaults to world");
92  this->frame_name_ = "world";
93  }
94  else
95  this->frame_name_ = _sdf->GetElement("frameName")->Get<std::string>();
96 
97  if (!_sdf->HasElement("xyzOffset"))
98  {
99  ROS_DEBUG_NAMED("p3d", "p3d plugin missing <xyzOffset>, defaults to 0s");
100  this->offset_.Pos() = ignition::math::Vector3d(0, 0, 0);
101  }
102  else
103  this->offset_.Pos() = _sdf->GetElement("xyzOffset")->Get<ignition::math::Vector3d>();
104 
105  if (!_sdf->HasElement("rpyOffset"))
106  {
107  ROS_DEBUG_NAMED("p3d", "p3d plugin missing <rpyOffset>, defaults to 0s");
108  this->offset_.Rot() = ignition::math::Quaterniond(ignition::math::Vector3d(0, 0, 0));
109  }
110  else
111  this->offset_.Rot() = ignition::math::Quaterniond(_sdf->GetElement("rpyOffset")->Get<ignition::math::Vector3d>());
112 
113  if (!_sdf->HasElement("gaussianNoise"))
114  {
115  ROS_DEBUG_NAMED("p3d", "p3d plugin missing <gaussianNoise>, defaults to 0.0");
116  this->gaussian_noise_ = 0;
117  }
118  else
119  this->gaussian_noise_ = _sdf->GetElement("gaussianNoise")->Get<double>();
120 
121  if (!_sdf->HasElement("updateRate"))
122  {
123  ROS_DEBUG_NAMED("p3d", "p3d plugin missing <updateRate>, defaults to 0.0"
124  " (as fast as possible)");
125  this->update_rate_ = 0;
126  }
127  else
128  this->update_rate_ = _sdf->GetElement("updateRate")->Get<double>();
129 
130  // Make sure the ROS node for Gazebo has already been initialized
131  if (!ros::isInitialized())
132  {
133  ROS_FATAL_STREAM_NAMED("p3d", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
134  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
135  return;
136  }
137 
138  this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
139 
140  // publish multi queue
141  this->pmq.startServiceThread();
142 
143  // resolve tf prefix
144  std::string prefix;
145  this->rosnode_->getParam(std::string("tf_prefix"), prefix);
146  this->tf_frame_name_ = tf::resolve(prefix, this->frame_name_);
147 
148  if (this->topic_name_ != "")
149  {
150  this->pub_Queue = this->pmq.addPub<nav_msgs::Odometry>();
151  this->pub_ =
152  this->rosnode_->advertise<nav_msgs::Odometry>(this->topic_name_, 1);
153  }
154 
155 #if GAZEBO_MAJOR_VERSION >= 8
156  this->last_time_ = this->world_->SimTime();
157 #else
158  this->last_time_ = this->world_->GetSimTime();
159 #endif
160  // initialize body
161 #if GAZEBO_MAJOR_VERSION >= 8
162  this->last_vpos_ = this->link_->WorldLinearVel();
163  this->last_veul_ = this->link_->WorldAngularVel();
164 #else
165  this->last_vpos_ = this->link_->GetWorldLinearVel().Ign();
166  this->last_veul_ = this->link_->GetWorldAngularVel().Ign();
167 #endif
168  this->apos_ = 0;
169  this->aeul_ = 0;
170 
171  // if frameName specified is "/world", "world", "/map" or "map" report
172  // back inertial values in the gazebo world
173  if (this->frame_name_ != "/world" &&
174  this->frame_name_ != "world" &&
175  this->frame_name_ != "/map" &&
176  this->frame_name_ != "map")
177  {
178  this->reference_link_ = this->model_->GetLink(this->frame_name_);
179  if (!this->reference_link_)
180  {
181  ROS_ERROR_NAMED("p3d", "gazebo_ros_p3d plugin: frameName: %s does not exist, will"
182  " not publish pose\n", this->frame_name_.c_str());
183  return;
184  }
185  }
186 
187  // init reference frame state
188  if (this->reference_link_)
189  {
190  ROS_DEBUG_NAMED("p3d", "got body %s", this->reference_link_->GetName().c_str());
191  this->frame_apos_ = 0;
192  this->frame_aeul_ = 0;
193 #if GAZEBO_MAJOR_VERSION >= 8
194  this->last_frame_vpos_ = this->reference_link_->WorldLinearVel();
195  this->last_frame_veul_ = this->reference_link_->WorldAngularVel();
196 #else
197  this->last_frame_vpos_ = this->reference_link_->GetWorldLinearVel().Ign();
198  this->last_frame_veul_ = this->reference_link_->GetWorldAngularVel().Ign();
199 #endif
200  }
201 
202 
203  // start custom queue for p3d
204  this->callback_queue_thread_ = boost::thread(
205  boost::bind(&GazeboRosP3D::P3DQueueThread, this));
206 
207  // New Mechanism for Updating every World Cycle
208  // Listen to the update event. This event is broadcast every
209  // simulation iteration.
210  this->update_connection_ = event::Events::ConnectWorldUpdateBegin(
211  boost::bind(&GazeboRosP3D::UpdateChild, this));
212 }
213 
215 // Update the controller
217 {
218 #ifdef ENABLE_PROFILER
219  IGN_PROFILE("GazeboRosP3D::UpdateChild");
220 #endif
221  if (!this->link_)
222  return;
223 
224 #if GAZEBO_MAJOR_VERSION >= 8
225  common::Time cur_time = this->world_->SimTime();
226 #else
227  common::Time cur_time = this->world_->GetSimTime();
228 #endif
229 #ifdef ENABLE_PROFILER
230  IGN_PROFILE_BEGIN("fill ROS message");
231 #endif
232  if (cur_time < this->last_time_)
233  {
234  ROS_WARN_NAMED("p3d", "Negative update time difference detected.");
235  this->last_time_ = cur_time;
236  }
237 
238  // rate control
239  if (this->update_rate_ > 0 &&
240  (cur_time-this->last_time_).Double() < (1.0/this->update_rate_))
241  return;
242 
243  if (this->pub_.getNumSubscribers() > 0)
244  {
245  // differentiate to get accelerations
246  double tmp_dt = cur_time.Double() - this->last_time_.Double();
247  if (tmp_dt != 0)
248  {
249  this->lock.lock();
250 
251  if (this->topic_name_ != "")
252  {
253  // copy data into pose message
254  this->pose_msg_.header.frame_id = this->tf_frame_name_;
255  this->pose_msg_.header.stamp.sec = cur_time.sec;
256  this->pose_msg_.header.stamp.nsec = cur_time.nsec;
257 
258  this->pose_msg_.child_frame_id = this->link_name_;
259 
260  ignition::math::Pose3d pose, frame_pose;
261  ignition::math::Vector3d frame_vpos;
262  ignition::math::Vector3d frame_veul;
263 
264  // get inertial Rates
265  // Get Pose/Orientation
266 #if GAZEBO_MAJOR_VERSION >= 8
267  ignition::math::Vector3d vpos = this->link_->WorldLinearVel();
268  ignition::math::Vector3d veul = this->link_->WorldAngularVel();
269 
270  pose = this->link_->WorldPose();
271 #else
272  ignition::math::Vector3d vpos = this->link_->GetWorldLinearVel().Ign();
273  ignition::math::Vector3d veul = this->link_->GetWorldAngularVel().Ign();
274 
275  pose = this->link_->GetWorldPose().Ign();
276 #endif
277 
278  // Apply Reference Frame
279  if (this->reference_link_)
280  {
281  // convert to relative pose, rates
282 #if GAZEBO_MAJOR_VERSION >= 8
283  frame_pose = this->reference_link_->WorldPose();
284  frame_vpos = this->reference_link_->WorldLinearVel();
285  frame_veul = this->reference_link_->WorldAngularVel();
286 #else
287  frame_pose = this->reference_link_->GetWorldPose().Ign();
288  frame_vpos = this->reference_link_->GetWorldLinearVel().Ign();
289  frame_veul = this->reference_link_->GetWorldAngularVel().Ign();
290 #endif
291  pose.Pos() = pose.Pos() - frame_pose.Pos();
292  pose.Pos() = frame_pose.Rot().RotateVectorReverse(pose.Pos());
293  pose.Rot() *= frame_pose.Rot().Inverse();
294 
295  vpos = frame_pose.Rot().RotateVector(vpos - frame_vpos);
296  veul = frame_pose.Rot().RotateVector(veul - frame_veul);
297  }
298 
299  // Apply Constant Offsets
300  // apply xyz offsets and get position and rotation components
301  pose.Pos() = pose.Pos() + this->offset_.Pos();
302  // apply rpy offsets
303  pose.Rot() = this->offset_.Rot()*pose.Rot();
304  pose.Rot().Normalize();
305 
306  // compute accelerations (not used)
307  this->apos_ = (this->last_vpos_ - vpos) / tmp_dt;
308  this->aeul_ = (this->last_veul_ - veul) / tmp_dt;
309  this->last_vpos_ = vpos;
310  this->last_veul_ = veul;
311 
312  this->frame_apos_ = (this->last_frame_vpos_ - frame_vpos) / tmp_dt;
313  this->frame_aeul_ = (this->last_frame_veul_ - frame_veul) / tmp_dt;
314  this->last_frame_vpos_ = frame_vpos;
315  this->last_frame_veul_ = frame_veul;
316 
317  // Fill out messages
318  this->pose_msg_.pose.pose.position.x = pose.Pos().X();
319  this->pose_msg_.pose.pose.position.y = pose.Pos().Y();
320  this->pose_msg_.pose.pose.position.z = pose.Pos().Z();
321 
322  this->pose_msg_.pose.pose.orientation.x = pose.Rot().X();
323  this->pose_msg_.pose.pose.orientation.y = pose.Rot().Y();
324  this->pose_msg_.pose.pose.orientation.z = pose.Rot().Z();
325  this->pose_msg_.pose.pose.orientation.w = pose.Rot().W();
326 
327  this->pose_msg_.twist.twist.linear.x = vpos.X() +
328  this->GaussianKernel(0, this->gaussian_noise_);
329  this->pose_msg_.twist.twist.linear.y = vpos.Y() +
330  this->GaussianKernel(0, this->gaussian_noise_);
331  this->pose_msg_.twist.twist.linear.z = vpos.Z() +
332  this->GaussianKernel(0, this->gaussian_noise_);
333  // pass euler angular rates
334  this->pose_msg_.twist.twist.angular.x = veul.X() +
335  this->GaussianKernel(0, this->gaussian_noise_);
336  this->pose_msg_.twist.twist.angular.y = veul.Y() +
337  this->GaussianKernel(0, this->gaussian_noise_);
338  this->pose_msg_.twist.twist.angular.z = veul.Z() +
339  this->GaussianKernel(0, this->gaussian_noise_);
340 
341  // fill in covariance matrix
343  double gn2 = this->gaussian_noise_*this->gaussian_noise_;
344  this->pose_msg_.pose.covariance[0] = gn2;
345  this->pose_msg_.pose.covariance[7] = gn2;
346  this->pose_msg_.pose.covariance[14] = gn2;
347  this->pose_msg_.pose.covariance[21] = gn2;
348  this->pose_msg_.pose.covariance[28] = gn2;
349  this->pose_msg_.pose.covariance[35] = gn2;
350 
351  this->pose_msg_.twist.covariance[0] = gn2;
352  this->pose_msg_.twist.covariance[7] = gn2;
353  this->pose_msg_.twist.covariance[14] = gn2;
354  this->pose_msg_.twist.covariance[21] = gn2;
355  this->pose_msg_.twist.covariance[28] = gn2;
356  this->pose_msg_.twist.covariance[35] = gn2;
357 
358  // publish to ros
359  this->pub_Queue->push(this->pose_msg_, this->pub_);
360  }
361 
362  this->lock.unlock();
363 
364  // save last time stamp
365  this->last_time_ = cur_time;
366  }
367  }
368 #ifdef ENABLE_PROFILER
369  IGN_PROFILE_END();
370 #endif
371 }
372 
374 // Utility for adding noise
375 double GazeboRosP3D::GaussianKernel(double mu, double sigma)
376 {
377  // using Box-Muller transform to generate two independent standard
378  // normally disbributed normal variables see wikipedia
379 
380  // normalized uniform random variable
381  double U = ignition::math::Rand::DblUniform();
382 
383  // normalized uniform random variable
384  double V = ignition::math::Rand::DblUniform();
385 
386  double X = sqrt(-2.0 * ::log(U)) * cos(2.0*M_PI * V);
387  // double Y = sqrt(-2.0 * ::log(U)) * sin(2.0*M_PI * V);
388 
389  // there are 2 indep. vars, we'll just use X
390  // scale to our mu and sigma
391  X = sigma * X + mu;
392  return X;
393 }
394 
396 // Put laser data to the interface
398 {
399  static const double timeout = 0.01;
400 
401  while (this->rosnode_->ok())
402  {
404  }
405 }
406 }
PubQueue::push
void push(T &msg, ros::Publisher &pub)
Push a new message onto the queue.
Definition: PubQueue.h:73
gazebo::GazeboRosP3D::last_vpos_
ignition::math::Vector3d last_vpos_
Definition: gazebo_ros_p3d.h:99
gazebo::GazeboRosP3D::last_frame_vpos_
ignition::math::Vector3d last_frame_vpos_
Definition: gazebo_ros_p3d.h:103
gazebo::GazeboRosP3D::link_
physics::LinkPtr link_
The parent Model.
Definition: gazebo_ros_p3d.h:66
gazebo
gazebo::GazeboRosP3D::update_rate_
double update_rate_
Definition: gazebo_ros_p3d.h:109
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros::CallbackQueue::clear
void clear()
gazebo::GazeboRosP3D::pub_Queue
PubQueue< nav_msgs::Odometry >::Ptr pub_Queue
Definition: gazebo_ros_p3d.h:75
gazebo::GazeboRosP3D::last_time_
common::Time last_time_
save last_time
Definition: gazebo_ros_p3d.h:98
gazebo::GazeboRosP3D::world_
physics::WorldPtr world_
Definition: gazebo_ros_p3d.h:62
gazebo::GazeboRosP3D::tf_frame_name_
std::string tf_frame_name_
Definition: gazebo_ros_p3d.h:89
gazebo::GazeboRosP3D::p3d_queue_
ros::CallbackQueue p3d_queue_
Definition: gazebo_ros_p3d.h:120
gazebo::GazeboRosP3D::link_name_
std::string link_name_
store bodyname
Definition: gazebo_ros_p3d.h:81
tf::resolve
std::string resolve(const std::string &prefix, const std::string &frame_name)
gazebo::GazeboRosP3D::pose_msg_
nav_msgs::Odometry pose_msg_
ros message
Definition: gazebo_ros_p3d.h:78
gazebo::GazeboRosP3D::callback_queue_thread_
boost::thread callback_queue_thread_
Definition: gazebo_ros_p3d.h:122
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
gazebo::GazeboRosP3D::frame_name_
std::string frame_name_
frame transform name, should match link name FIXME: extract link name directly?
Definition: gazebo_ros_p3d.h:88
gazebo_ros_p3d.h
ROS_FATAL_NAMED
#define ROS_FATAL_NAMED(name,...)
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
gazebo::GazeboRosP3D::frame_apos_
ignition::math::Vector3d frame_apos_
Definition: gazebo_ros_p3d.h:105
gazebo::GazeboRosP3D::reference_link_
physics::LinkPtr reference_link_
The body of the frame to display pose, twist.
Definition: gazebo_ros_p3d.h:69
gazebo::GazeboRosP3D::P3DQueueThread
void P3DQueueThread()
Definition: gazebo_ros_p3d.cpp:397
gazebo::GazeboRosP3D::update_connection_
event::ConnectionPtr update_connection_
Definition: gazebo_ros_p3d.h:125
gazebo::GazeboRosP3D::rosnode_
ros::NodeHandle * rosnode_
pointer to ros node
Definition: gazebo_ros_p3d.h:73
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
gazebo::GazeboRosP3D::Load
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the controller.
Definition: gazebo_ros_p3d.cpp:53
gazebo::GZ_REGISTER_MODEL_PLUGIN
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
gazebo::GazeboRosP3D::robot_namespace_
std::string robot_namespace_
for setting ROS name space
Definition: gazebo_ros_p3d.h:118
gazebo::GazeboRosP3D::pub_
ros::Publisher pub_
Definition: gazebo_ros_p3d.h:74
ros::isInitialized
ROSCPP_DECL bool isInitialized()
PubMultiQueue::addPub
boost::shared_ptr< PubQueue< T > > addPub()
Add a new queue. Call this once for each published topic (or at least each type of publish message).
Definition: PubQueue.h:143
gazebo::GazeboRosP3D::last_frame_veul_
ignition::math::Vector3d last_frame_veul_
Definition: gazebo_ros_p3d.h:104
tf.h
gazebo::GazeboRosP3D::topic_name_
std::string topic_name_
topic name
Definition: gazebo_ros_p3d.h:84
ros::NodeHandle::ok
bool ok() const
PubMultiQueue::startServiceThread
void startServiceThread()
Start a thread to call spin().
Definition: PubQueue.h:181
gazebo::GazeboRosP3D::GazeboRosP3D
GazeboRosP3D()
Constructor.
Definition: gazebo_ros_p3d.cpp:34
gazebo::GazeboRosP3D::model_
physics::ModelPtr model_
Definition: gazebo_ros_p3d.h:63
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
gazebo::GazeboRosP3D::pmq
PubMultiQueue pmq
Definition: gazebo_ros_p3d.h:128
gazebo::GazeboRosP3D::aeul_
ignition::math::Vector3d aeul_
Definition: gazebo_ros_p3d.h:102
gazebo::GazeboRosP3D::lock
boost::mutex lock
mutex to lock access to fields used in message callbacks
Definition: gazebo_ros_p3d.h:95
gazebo::GazeboRosP3D::offset_
ignition::math::Pose3d offset_
allow specifying constant xyz and rpy offsets
Definition: gazebo_ros_p3d.h:92
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
ros::WallDuration
gazebo::GazeboRosP3D::gaussian_noise_
double gaussian_noise_
Gaussian noise.
Definition: gazebo_ros_p3d.h:112
gazebo::GazeboRosP3D::GaussianKernel
double GaussianKernel(double mu, double sigma)
Gaussian noise generator.
Definition: gazebo_ros_p3d.cpp:375
ros::NodeHandle::shutdown
void shutdown()
gazebo::GazeboRosP3D::last_veul_
ignition::math::Vector3d last_veul_
Definition: gazebo_ros_p3d.h:100
gazebo::GazeboRosP3D::frame_aeul_
ignition::math::Vector3d frame_aeul_
Definition: gazebo_ros_p3d.h:106
gazebo::GazeboRosP3D::UpdateChild
virtual void UpdateChild()
Update the controller.
Definition: gazebo_ros_p3d.cpp:216
gazebo::GazeboRosP3D::apos_
ignition::math::Vector3d apos_
Definition: gazebo_ros_p3d.h:101
ros::CallbackQueue::callAvailable
void callAvailable()
gazebo::GazeboRosP3D::~GazeboRosP3D
virtual ~GazeboRosP3D()
Destructor.
Definition: gazebo_ros_p3d.cpp:40
ros::CallbackQueue::disable
void disable()
ros::NodeHandle


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