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