gazebo_ros_imu.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  * Desc: 3D position interface for ground truth.
19  * Author: Sachin Chitta and John Hsu
20  * Date: 1 June 2008
21  */
22 
24 #include <ignition/math/Rand.hh>
25 #ifdef ENABLE_PROFILER
26 #include <ignition/common/Profiler.hh>
27 #endif
28 
29 namespace gazebo
30 {
31 // Register this plugin with the simulator
32 GZ_REGISTER_MODEL_PLUGIN(GazeboRosIMU)
33 
34 // Constructor
37 {
38 }
39 
41 // Destructor
43 {
44  this->update_connection_.reset();
45  // Finalize the controller
46  this->rosnode_->shutdown();
47  this->callback_queue_thread_.join();
48  delete this->rosnode_;
49 }
50 
52 // Load the controller
53 void GazeboRosIMU::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
54 {
55  // save pointers
56  this->world_ = _parent->GetWorld();
57  this->sdf = _sdf;
58 
59  // ros callback queue for processing subscription
60  this->deferred_load_thread_ = boost::thread(
61  boost::bind(&GazeboRosIMU::LoadThread, this));
62 }
63 
65 // Load the controller
67 {
68  // load parameters
69  this->robot_namespace_ = "";
70  if (this->sdf->HasElement("robotNamespace"))
71  this->robot_namespace_ = this->sdf->Get<std::string>("robotNamespace") + "/";
72 
73  if (!this->sdf->HasElement("serviceName"))
74  {
75  ROS_INFO_NAMED("imu", "imu plugin missing <serviceName>, defaults to /default_imu");
76  this->service_name_ = "/default_imu";
77  }
78  else
79  this->service_name_ = this->sdf->Get<std::string>("serviceName");
80 
81  if (!this->sdf->HasElement("topicName"))
82  {
83  ROS_INFO_NAMED("imu", "imu plugin missing <topicName>, defaults to /default_imu");
84  this->topic_name_ = "/default_imu";
85  }
86  else
87  this->topic_name_ = this->sdf->Get<std::string>("topicName");
88 
89  if (!this->sdf->HasElement("gaussianNoise"))
90  {
91  ROS_INFO_NAMED("imu", "imu plugin missing <gaussianNoise>, defaults to 0.0");
92  this->gaussian_noise_ = 0.0;
93  }
94  else
95  this->gaussian_noise_ = this->sdf->Get<double>("gaussianNoise");
96 
97  if (!this->sdf->HasElement("bodyName"))
98  {
99  ROS_FATAL_NAMED("imu", "imu plugin missing <bodyName>, cannot proceed");
100  return;
101  }
102  else
103  this->link_name_ = this->sdf->Get<std::string>("bodyName");
104 
105  if (!this->sdf->HasElement("xyzOffset"))
106  {
107  ROS_INFO_NAMED("imu", "imu plugin missing <xyzOffset>, defaults to 0s");
108  this->offset_.Pos() = ignition::math::Vector3d(0, 0, 0);
109  }
110  else
111  this->offset_.Pos() = this->sdf->Get<ignition::math::Vector3d>("xyzOffset");
112 
113  if (!this->sdf->HasElement("rpyOffset"))
114  {
115  ROS_INFO_NAMED("imu", "imu 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(this->sdf->Get<ignition::math::Vector3d>("rpyOffset"));
120 
121  if (!this->sdf->HasElement("updateRate"))
122  {
123  ROS_DEBUG_NAMED("imu", "imu plugin missing <updateRate>, defaults to 0.0"
124  " (as fast as possible)");
125  this->update_rate_ = 0.0;
126  }
127  else
128  this->update_rate_ = this->sdf->GetElement("updateRate")->Get<double>();
129 
130  if (!this->sdf->HasElement("frameName"))
131  {
132  ROS_INFO_NAMED("imu", "imu plugin missing <frameName>, defaults to <bodyName>");
133  this->frame_name_ = link_name_;
134  }
135  else
136  this->frame_name_ = this->sdf->Get<std::string>("frameName");
137 
138  // Make sure the ROS node for Gazebo has already been initialized
139  if (!ros::isInitialized())
140  {
141  ROS_FATAL_STREAM_NAMED("imu", "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  // assert that the body by link_name_ exists
152  this->link = boost::dynamic_pointer_cast<physics::Link>(
153 #if GAZEBO_MAJOR_VERSION >= 8
154  this->world_->EntityByName(this->link_name_));
155 #else
156  this->world_->GetEntity(this->link_name_));
157 #endif
158  if (!this->link)
159  {
160  ROS_FATAL_NAMED("imu", "gazebo_ros_imu plugin error: bodyName: %s does not exist\n",
161  this->link_name_.c_str());
162  return;
163  }
164 
165  // if topic name specified as empty, do not publish
166  if (this->topic_name_ != "")
167  {
168  this->pub_Queue = this->pmq.addPub<sensor_msgs::Imu>();
169  this->pub_ = this->rosnode_->advertise<sensor_msgs::Imu>(
170  this->topic_name_, 1);
171 
172  // advertise services on the custom queue
174  ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
175  this->service_name_, boost::bind(&GazeboRosIMU::ServiceCallback,
176  this, _1, _2), ros::VoidPtr(), &this->imu_queue_);
177  this->srv_ = this->rosnode_->advertiseService(aso);
178  }
179 
180  // Initialize the controller
181 #if GAZEBO_MAJOR_VERSION >= 8
182  this->last_time_ = this->world_->SimTime();
183 #else
184  this->last_time_ = this->world_->GetSimTime();
185 #endif
186 
187  // this->initial_pose_ = this->link->GetPose();
188 #if GAZEBO_MAJOR_VERSION >= 8
189  this->last_vpos_ = this->link->WorldLinearVel();
190  this->last_veul_ = this->link->WorldAngularVel();
191 #else
192  this->last_vpos_ = this->link->GetWorldLinearVel().Ign();
193  this->last_veul_ = this->link->GetWorldAngularVel().Ign();
194 #endif
195  this->apos_ = 0;
196  this->aeul_ = 0;
197 
198  // start custom queue for imu
199  this->callback_queue_thread_ =
200  boost::thread(boost::bind(&GazeboRosIMU::IMUQueueThread, this));
201 
202 
203  // New Mechanism for Updating every World Cycle
204  // Listen to the update event. This event is broadcast every
205  // simulation iteration.
206  this->update_connection_ = event::Events::ConnectWorldUpdateBegin(
207  boost::bind(&GazeboRosIMU::UpdateChild, this));
208 }
209 
211 // returns true always, imu is always calibrated in sim
212 bool GazeboRosIMU::ServiceCallback(std_srvs::Empty::Request &req,
213  std_srvs::Empty::Response &res)
214 {
215  return true;
216 }
217 
219 // Update the controller
221 {
222 #ifdef ENABLE_PROFILER
223  IGN_PROFILE("GazeboRosIMU::UpdateChild");
224 #endif
225 #if GAZEBO_MAJOR_VERSION >= 8
226  common::Time cur_time = this->world_->SimTime();
227 #else
228  common::Time cur_time = this->world_->GetSimTime();
229 #endif
230 
231  // rate control
232  if (this->update_rate_ > 0 &&
233  (cur_time - this->last_time_).Double() < (1.0 / this->update_rate_))
234  return;
235 
236  if ((this->pub_.getNumSubscribers() > 0 && this->topic_name_ != ""))
237  {
238 #ifdef ENABLE_PROFILER
239  IGN_PROFILE_BEGIN("fill ROS message");
240 #endif
241  ignition::math::Pose3d pose;
242  ignition::math::Quaterniond rot;
243  ignition::math::Vector3d pos;
244 
245  // Get Pose/Orientation ///@todo: verify correctness
246 #if GAZEBO_MAJOR_VERSION >= 8
247  pose = this->link->WorldPose();
248 #else
249  pose = this->link->GetWorldPose().Ign();
250 #endif
251  // apply xyz offsets and get position and rotation components
252  pos = pose.Pos() + this->offset_.Pos();
253  rot = pose.Rot();
254 
255  // apply rpy offsets
256  rot = this->offset_.Rot()*rot;
257  rot.Normalize();
258 
259  // get Rates
260 #if GAZEBO_MAJOR_VERSION >= 8
261  ignition::math::Vector3d vpos = this->link->WorldLinearVel();
262  ignition::math::Vector3d veul = this->link->WorldAngularVel();
263 #else
264  ignition::math::Vector3d vpos = this->link->GetWorldLinearVel().Ign();
265  ignition::math::Vector3d veul = this->link->GetWorldAngularVel().Ign();
266 #endif
267 
268  // differentiate to get accelerations
269  double tmp_dt = this->last_time_.Double() - cur_time.Double();
270  if (tmp_dt != 0)
271  {
272  this->apos_ = (this->last_vpos_ - vpos) / tmp_dt;
273  this->aeul_ = (this->last_veul_ - veul) / tmp_dt;
274  this->last_vpos_ = vpos;
275  this->last_veul_ = veul;
276  }
277 
278  // copy data into pose message
279  this->imu_msg_.header.frame_id = this->frame_name_;
280  this->imu_msg_.header.stamp.sec = cur_time.sec;
281  this->imu_msg_.header.stamp.nsec = cur_time.nsec;
282 
283  // orientation quaternion
284 
285  // uncomment this if we are reporting orientation in the local frame
286  // not the case for our imu definition
287  // // apply fixed orientation offsets of initial pose
288  // rot = this->initial_pose_.Rot()*rot;
289  // rot.Normalize();
290 
291  this->imu_msg_.orientation.x = rot.X();
292  this->imu_msg_.orientation.y = rot.Y();
293  this->imu_msg_.orientation.z = rot.Z();
294  this->imu_msg_.orientation.w = rot.W();
295 
296  // pass euler angular rates
297  ignition::math::Vector3d linear_velocity(
298  veul.X() + this->GaussianKernel(0, this->gaussian_noise_),
299  veul.Y() + this->GaussianKernel(0, this->gaussian_noise_),
300  veul.Z() + this->GaussianKernel(0, this->gaussian_noise_));
301  // rotate into local frame
302  // @todo: deal with offsets!
303  linear_velocity = rot.RotateVector(linear_velocity);
304  this->imu_msg_.angular_velocity.x = linear_velocity.X();
305  this->imu_msg_.angular_velocity.y = linear_velocity.Y();
306  this->imu_msg_.angular_velocity.z = linear_velocity.Z();
307 
308  // pass accelerations
309  ignition::math::Vector3d linear_acceleration(
310  apos_.X() + this->GaussianKernel(0, this->gaussian_noise_),
311  apos_.Y() + this->GaussianKernel(0, this->gaussian_noise_),
312  apos_.Z() + this->GaussianKernel(0, this->gaussian_noise_));
313  // rotate into local frame
314  // @todo: deal with offsets!
315  linear_acceleration = rot.RotateVector(linear_acceleration);
316  this->imu_msg_.linear_acceleration.x = linear_acceleration.X();
317  this->imu_msg_.linear_acceleration.y = linear_acceleration.Y();
318  this->imu_msg_.linear_acceleration.z = linear_acceleration.Z();
319 
320  // fill in covariance matrix
323  double gn2 = this->gaussian_noise_*this->gaussian_noise_;
324  this->imu_msg_.orientation_covariance[0] = gn2;
325  this->imu_msg_.orientation_covariance[4] = gn2;
326  this->imu_msg_.orientation_covariance[8] = gn2;
327  this->imu_msg_.angular_velocity_covariance[0] = gn2;
328  this->imu_msg_.angular_velocity_covariance[4] = gn2;
329  this->imu_msg_.angular_velocity_covariance[8] = gn2;
330  this->imu_msg_.linear_acceleration_covariance[0] = gn2;
331  this->imu_msg_.linear_acceleration_covariance[4] = gn2;
332  this->imu_msg_.linear_acceleration_covariance[8] = gn2;
333 
334  {
335  boost::mutex::scoped_lock lock(this->lock_);
336  // publish to ros
337  if (this->pub_.getNumSubscribers() > 0 && this->topic_name_ != "")
338  this->pub_Queue->push(this->imu_msg_, this->pub_);
339  }
340 
341  // save last time stamp
342  this->last_time_ = cur_time;
343 #ifdef ENABLE_PROFILER
344  IGN_PROFILE_END();
345 #endif
346  }
347 }
348 
349 
351 // Utility for adding noise
352 double GazeboRosIMU::GaussianKernel(double mu, double sigma)
353 {
354  // using Box-Muller transform to generate two independent standard
355  // normally disbributed normal variables see wikipedia
356 
357  // normalized uniform random variable
358  double U = ignition::math::Rand::DblUniform();
359 
360  // normalized uniform random variable
361  double V = ignition::math::Rand::DblUniform();
362 
363  double X = sqrt(-2.0 * ::log(U)) * cos(2.0*M_PI * V);
364  // double Y = sqrt(-2.0 * ::log(U)) * sin(2.0*M_PI * V);
365 
366  // there are 2 indep. vars, we'll just use X
367  // scale to our mu and sigma
368  X = sigma * X + mu;
369  return X;
370 }
371 
373 // Put laser data to the interface
375 {
376  static const double timeout = 0.01;
377 
378  while (this->rosnode_->ok())
379  {
381  }
382 }
383 }
gazebo::GazeboRosIMU::aeul_
ignition::math::Vector3d aeul_
Definition: gazebo_ros_imu.h:89
PubQueue::push
void push(T &msg, ros::Publisher &pub)
Push a new message onto the queue.
Definition: PubQueue.h:73
gazebo::GazeboRosIMU::service_name_
std::string service_name_
Definition: gazebo_ros_imu.h:111
gazebo::GazeboRosIMU::rosnode_
ros::NodeHandle * rosnode_
pointer to ros node
Definition: gazebo_ros_imu.h:61
gazebo::GazeboRosIMU::offset_
ignition::math::Pose3d offset_
allow specifying constant xyz and rpy offsets
Definition: gazebo_ros_imu.h:78
boost::shared_ptr< void >
gazebo::GazeboRosIMU::update_connection_
event::ConnectionPtr update_connection_
Definition: gazebo_ros_imu.h:118
gazebo
gazebo::GazeboRosIMU::world_
physics::WorldPtr world_
The parent World.
Definition: gazebo_ros_imu.h:55
gazebo::GazeboRosIMU::link
physics::LinkPtr link
The link referred to by this plugin.
Definition: gazebo_ros_imu.h:58
gazebo::GazeboRosIMU::callback_queue_thread_
boost::thread callback_queue_thread_
Definition: gazebo_ros_imu.h:115
gazebo::GazeboRosIMU::robot_namespace_
std::string robot_namespace_
for setting ROS name space
Definition: gazebo_ros_imu.h:104
gazebo::GazeboRosIMU::GaussianKernel
double GaussianKernel(double mu, double sigma)
Gaussian noise generator.
Definition: gazebo_ros_imu.cpp:352
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
gazebo::GazeboRosIMU
Definition: gazebo_ros_imu.h:39
ROS_FATAL_NAMED
#define ROS_FATAL_NAMED(name,...)
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
gazebo::GazeboRosIMU::imu_queue_
ros::CallbackQueue imu_queue_
Definition: gazebo_ros_imu.h:113
gazebo::GazeboRosIMU::imu_msg_
sensor_msgs::Imu imu_msg_
ros message
Definition: gazebo_ros_imu.h:66
gazebo::GazeboRosIMU::pmq
PubMultiQueue pmq
Definition: gazebo_ros_imu.h:126
gazebo::GazeboRosIMU::last_veul_
ignition::math::Vector3d last_veul_
Definition: gazebo_ros_imu.h:87
gazebo::GazeboRosIMU::pub_Queue
PubQueue< sensor_msgs::Imu >::Ptr pub_Queue
Definition: gazebo_ros_imu.h:63
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,...)
gazebo::GazeboRosIMU::sdf
sdf::ElementPtr sdf
Definition: gazebo_ros_imu.h:121
gazebo::GZ_REGISTER_MODEL_PLUGIN
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
gazebo::GazeboRosIMU::IMUQueueThread
void IMUQueueThread()
Definition: gazebo_ros_imu.cpp:374
gazebo::GazeboRosIMU::ServiceCallback
bool ServiceCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
call back when using service
Definition: gazebo_ros_imu.cpp:212
gazebo::GazeboRosIMU::lock_
boost::mutex lock_
A mutex to lock access to fields that are used in message callbacks.
Definition: gazebo_ros_imu.h:82
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::GazeboRosIMU::LoadThread
void LoadThread()
Definition: gazebo_ros_imu.cpp:66
ros::AdvertiseServiceOptions
gazebo::GazeboRosIMU::pub_
ros::Publisher pub_
Definition: gazebo_ros_imu.h:62
gazebo_ros_imu.h
ros::NodeHandle::ok
bool ok() const
PubMultiQueue::startServiceThread
void startServiceThread()
Start a thread to call spin().
Definition: PubQueue.h:181
gazebo::GazeboRosIMU::gaussian_noise_
double gaussian_noise_
Gaussian noise.
Definition: gazebo_ros_imu.h:98
gazebo::GazeboRosIMU::link_name_
std::string link_name_
store link name
Definition: gazebo_ros_imu.h:69
gazebo::GazeboRosIMU::Load
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the controller.
Definition: gazebo_ros_imu.cpp:53
gazebo::GazeboRosIMU::last_vpos_
ignition::math::Vector3d last_vpos_
Definition: gazebo_ros_imu.h:86
gazebo::GazeboRosIMU::last_time_
common::Time last_time_
save last_time
Definition: gazebo_ros_imu.h:85
gazebo::GazeboRosIMU::srv_
ros::ServiceServer srv_
Definition: gazebo_ros_imu.h:110
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
ros::WallDuration
gazebo::GazeboRosIMU::update_rate_
double update_rate_
Definition: gazebo_ros_imu.h:92
ros::NodeHandle::shutdown
void shutdown()
gazebo::GazeboRosIMU::~GazeboRosIMU
virtual ~GazeboRosIMU()
Destructor.
Definition: gazebo_ros_imu.cpp:42
ros::CallbackQueue::callAvailable
void callAvailable()
gazebo::GazeboRosIMU::frame_name_
std::string frame_name_
store frame name
Definition: gazebo_ros_imu.h:72
ros::NodeHandle
gazebo::GazeboRosIMU::deferred_load_thread_
boost::thread deferred_load_thread_
Definition: gazebo_ros_imu.h:123
gazebo::GazeboRosIMU::apos_
ignition::math::Vector3d apos_
Definition: gazebo_ros_imu.h:88
gazebo::GazeboRosIMU::UpdateChild
virtual void UpdateChild()
Update the controller.
Definition: gazebo_ros_imu.cpp:220
gazebo::GazeboRosIMU::topic_name_
std::string topic_name_
topic name
Definition: gazebo_ros_imu.h:75


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