24 #include <ignition/math/Rand.hh>
25 #ifdef ENABLE_PROFILER
26 #include <ignition/common/Profiler.hh>
56 this->
world_ = _parent->GetWorld();
70 if (this->
sdf->HasElement(
"robotNamespace"))
73 if (!this->
sdf->HasElement(
"serviceName"))
75 ROS_INFO_NAMED(
"imu",
"imu plugin missing <serviceName>, defaults to /default_imu");
81 if (!this->
sdf->HasElement(
"topicName"))
83 ROS_INFO_NAMED(
"imu",
"imu plugin missing <topicName>, defaults to /default_imu");
89 if (!this->
sdf->HasElement(
"gaussianNoise"))
91 ROS_INFO_NAMED(
"imu",
"imu plugin missing <gaussianNoise>, defaults to 0.0");
97 if (!this->
sdf->HasElement(
"bodyName"))
99 ROS_FATAL_NAMED(
"imu",
"imu plugin missing <bodyName>, cannot proceed");
105 if (!this->
sdf->HasElement(
"xyzOffset"))
107 ROS_INFO_NAMED(
"imu",
"imu plugin missing <xyzOffset>, defaults to 0s");
108 this->
offset_.Pos() = ignition::math::Vector3d(0, 0, 0);
111 this->
offset_.Pos() = this->
sdf->Get<ignition::math::Vector3d>(
"xyzOffset");
113 if (!this->
sdf->HasElement(
"rpyOffset"))
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));
119 this->
offset_.Rot() = ignition::math::Quaterniond(this->
sdf->Get<ignition::math::Vector3d>(
"rpyOffset"));
121 if (!this->
sdf->HasElement(
"updateRate"))
123 ROS_DEBUG_NAMED(
"imu",
"imu plugin missing <updateRate>, defaults to 0.0"
124 " (as fast as possible)");
128 this->
update_rate_ = this->
sdf->GetElement(
"updateRate")->Get<
double>();
130 if (!this->
sdf->HasElement(
"frameName"))
132 ROS_INFO_NAMED(
"imu",
"imu plugin missing <frameName>, defaults to <bodyName>");
142 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
152 this->
link = boost::dynamic_pointer_cast<physics::Link>(
153 #
if GAZEBO_MAJOR_VERSION >= 8
154 this->
world_->EntityByName(this->link_name_));
160 ROS_FATAL_NAMED(
"imu",
"gazebo_ros_imu plugin error: bodyName: %s does not exist\n",
174 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
181 #if GAZEBO_MAJOR_VERSION >= 8
188 #if GAZEBO_MAJOR_VERSION >= 8
213 std_srvs::Empty::Response &res)
222 #ifdef ENABLE_PROFILER
223 IGN_PROFILE(
"GazeboRosIMU::UpdateChild");
225 #if GAZEBO_MAJOR_VERSION >= 8
226 common::Time cur_time = this->
world_->SimTime();
228 common::Time cur_time = this->
world_->GetSimTime();
238 #ifdef ENABLE_PROFILER
239 IGN_PROFILE_BEGIN(
"fill ROS message");
241 ignition::math::Pose3d pose;
242 ignition::math::Quaterniond rot;
243 ignition::math::Vector3d pos;
246 #if GAZEBO_MAJOR_VERSION >= 8
247 pose = this->
link->WorldPose();
249 pose = this->
link->GetWorldPose().Ign();
252 pos = pose.Pos() + this->
offset_.Pos();
260 #if GAZEBO_MAJOR_VERSION >= 8
261 ignition::math::Vector3d vpos = this->
link->WorldLinearVel();
262 ignition::math::Vector3d veul = this->
link->WorldAngularVel();
264 ignition::math::Vector3d vpos = this->
link->GetWorldLinearVel().Ign();
265 ignition::math::Vector3d veul = this->
link->GetWorldAngularVel().Ign();
269 double tmp_dt = this->
last_time_.Double() - cur_time.Double();
280 this->
imu_msg_.header.stamp.sec = cur_time.sec;
281 this->
imu_msg_.header.stamp.nsec = cur_time.nsec;
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();
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_));
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();
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_));
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();
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;
335 boost::mutex::scoped_lock lock(this->
lock_);
343 #ifdef ENABLE_PROFILER
358 double U = ignition::math::Rand::DblUniform();
361 double V = ignition::math::Rand::DblUniform();
363 double X = sqrt(-2.0 * ::log(U)) * cos(2.0*M_PI * V);
376 static const double timeout = 0.01;