23 #ifdef ENABLE_PROFILER
24 #include <ignition/common/Profiler.hh>
26 #include <ignition/math/Rand.hh>
56 this->
world_ = _parent->GetWorld();
61 if (_sdf->HasElement(
"robotNamespace"))
63 _sdf->GetElement(
"robotNamespace")->Get<std::string>() +
"/";
65 if (!_sdf->HasElement(
"bodyName"))
67 ROS_FATAL_NAMED(
"p3d",
"p3d plugin missing <bodyName>, cannot proceed");
71 this->
link_name_ = _sdf->GetElement(
"bodyName")->Get<std::string>();
76 ROS_FATAL_NAMED(
"p3d",
"gazebo_ros_p3d plugin error: bodyName: %s does not exist\n",
81 if (!_sdf->HasElement(
"topicName"))
83 ROS_FATAL_NAMED(
"p3d",
"p3d plugin missing <topicName>, cannot proceed");
87 this->
topic_name_ = _sdf->GetElement(
"topicName")->Get<std::string>();
89 if (!_sdf->HasElement(
"frameName"))
91 ROS_DEBUG_NAMED(
"p3d",
"p3d plugin missing <frameName>, defaults to world");
95 this->
frame_name_ = _sdf->GetElement(
"frameName")->Get<std::string>();
97 if (!_sdf->HasElement(
"localTwist"))
99 ROS_DEBUG_NAMED(
"p3d",
"p3d plugin missing <localTwist>, defaults to false");
103 this->
local_twist_= _sdf->GetElement(
"localTwist")->Get<
bool>();
105 if (!_sdf->HasElement(
"xyzOffset"))
107 ROS_DEBUG_NAMED(
"p3d",
"p3d plugin missing <xyzOffset>, defaults to 0s");
108 this->
offset_.Pos() = ignition::math::Vector3d(0, 0, 0);
111 this->
offset_.Pos() = _sdf->GetElement(
"xyzOffset")->Get<ignition::math::Vector3d>();
113 if (!_sdf->HasElement(
"rpyOffset"))
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));
119 this->
offset_.Rot() = ignition::math::Quaterniond(_sdf->GetElement(
"rpyOffset")->Get<ignition::math::Vector3d>());
121 if (!_sdf->HasElement(
"gaussianNoise"))
123 ROS_DEBUG_NAMED(
"p3d",
"p3d plugin missing <gaussianNoise>, defaults to 0.0");
127 this->
gaussian_noise_ = _sdf->GetElement(
"gaussianNoise")->Get<
double>();
129 if (!_sdf->HasElement(
"updateRate"))
131 ROS_DEBUG_NAMED(
"p3d",
"p3d plugin missing <updateRate>, defaults to 0.0"
132 " (as fast as possible)");
136 this->
update_rate_ = _sdf->GetElement(
"updateRate")->Get<
double>();
142 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
163 #if GAZEBO_MAJOR_VERSION >= 8
169 #if GAZEBO_MAJOR_VERSION >= 8
170 this->
last_vpos_ = this->link_->WorldLinearVel();
171 this->
last_veul_ = this->link_->WorldAngularVel();
173 this->
last_vpos_ = this->link_->GetWorldLinearVel().Ign();
174 this->
last_veul_ = this->link_->GetWorldAngularVel().Ign();
189 ROS_ERROR_NAMED(
"p3d",
"gazebo_ros_p3d plugin: frameName: %s does not exist, will"
201 #if GAZEBO_MAJOR_VERSION >= 8
226 #ifdef ENABLE_PROFILER
227 IGN_PROFILE(
"GazeboRosP3D::UpdateChild");
232 #if GAZEBO_MAJOR_VERSION >= 8
233 common::Time cur_time = this->
world_->SimTime();
235 common::Time cur_time = this->
world_->GetSimTime();
237 #ifdef ENABLE_PROFILER
238 IGN_PROFILE_BEGIN(
"fill ROS message");
242 ROS_WARN_NAMED(
"p3d",
"Negative update time difference detected.");
243 this->last_time_ = cur_time;
248 (cur_time-this->last_time_).Double() < (1.0/this->
update_rate_))
254 double tmp_dt = cur_time.Double() - this->last_time_.Double();
263 this->
pose_msg_.header.stamp.sec = cur_time.sec;
264 this->
pose_msg_.header.stamp.nsec = cur_time.nsec;
268 ignition::math::Pose3d pose, frame_pose;
269 ignition::math::Vector3d frame_vpos;
270 ignition::math::Vector3d frame_veul;
274 #if GAZEBO_MAJOR_VERSION >= 8
275 ignition::math::Vector3d vpos;
276 ignition::math::Vector3d veul;
280 vpos = this->
link_->RelativeLinearVel();
281 veul = this->
link_->RelativeAngularVel();
285 vpos = this->
link_->WorldLinearVel();
286 veul = this->
link_->WorldAngularVel();
289 pose = this->
link_->WorldPose();
291 ignition::math::Vector3d vpos = this->
link_->GetWorldLinearVel().Ign();
292 ignition::math::Vector3d veul = this->
link_->GetWorldAngularVel().Ign();
294 pose = this->
link_->GetWorldPose().Ign();
301 #if GAZEBO_MAJOR_VERSION >= 8
310 pose.Pos() = pose.Pos() - frame_pose.Pos();
311 pose.Pos() = frame_pose.Rot().RotateVectorReverse(pose.Pos());
312 pose.Rot() *= frame_pose.Rot().Inverse();
316 vpos = frame_pose.Rot().RotateVector(vpos - frame_vpos);
317 veul = frame_pose.Rot().RotateVector(veul - frame_veul);
323 pose.Pos() = pose.Pos() + this->
offset_.Pos();
325 pose.Rot() = this->
offset_.Rot()*pose.Rot();
326 pose.Rot().Normalize();
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();
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();
349 this->
pose_msg_.twist.twist.linear.x = vpos.X() +
351 this->
pose_msg_.twist.twist.linear.y = vpos.Y() +
353 this->
pose_msg_.twist.twist.linear.z = vpos.Z() +
356 this->
pose_msg_.twist.twist.angular.x = veul.X() +
358 this->
pose_msg_.twist.twist.angular.y = veul.Y() +
360 this->
pose_msg_.twist.twist.angular.z = veul.Z() +
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;
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;
387 this->last_time_ = cur_time;
390 #ifdef ENABLE_PROFILER
403 double U = ignition::math::Rand::DblUniform();
406 double V = ignition::math::Rand::DblUniform();
408 double X = sqrt(-2.0 * ::log(U)) * cos(2.0*M_PI * V);
421 static const double timeout = 0.01;