23 #include <ignition/math/Rand.hh> 53 this->
world_ = _parent->GetWorld();
58 if (_sdf->HasElement(
"robotNamespace"))
60 _sdf->GetElement(
"robotNamespace")->Get<std::string>() +
"/";
62 if (!_sdf->HasElement(
"bodyName"))
64 ROS_FATAL_NAMED(
"p3d",
"p3d plugin missing <bodyName>, cannot proceed");
68 this->
link_name_ = _sdf->GetElement(
"bodyName")->Get<std::string>();
73 ROS_FATAL_NAMED(
"p3d",
"gazebo_ros_p3d plugin error: bodyName: %s does not exist\n",
78 if (!_sdf->HasElement(
"topicName"))
80 ROS_FATAL_NAMED(
"p3d",
"p3d plugin missing <topicName>, cannot proceed");
84 this->
topic_name_ = _sdf->GetElement(
"topicName")->Get<std::string>();
86 if (!_sdf->HasElement(
"frameName"))
88 ROS_DEBUG_NAMED(
"p3d",
"p3d plugin missing <frameName>, defaults to world");
92 this->
frame_name_ = _sdf->GetElement(
"frameName")->Get<std::string>();
94 if (!_sdf->HasElement(
"xyzOffset"))
96 ROS_DEBUG_NAMED(
"p3d",
"p3d plugin missing <xyzOffset>, defaults to 0s");
97 this->
offset_.Pos() = ignition::math::Vector3d(0, 0, 0);
100 this->
offset_.Pos() = _sdf->GetElement(
"xyzOffset")->Get<ignition::math::Vector3d>();
102 if (!_sdf->HasElement(
"rpyOffset"))
104 ROS_DEBUG_NAMED(
"p3d",
"p3d plugin missing <rpyOffset>, defaults to 0s");
105 this->
offset_.Rot() = ignition::math::Quaterniond(ignition::math::Vector3d(0, 0, 0));
108 this->
offset_.Rot() = ignition::math::Quaterniond(_sdf->GetElement(
"rpyOffset")->Get<ignition::math::Vector3d>());
110 if (!_sdf->HasElement(
"gaussianNoise"))
112 ROS_DEBUG_NAMED(
"p3d",
"p3d plugin missing <gaussianNoise>, defaults to 0.0");
116 this->
gaussian_noise_ = _sdf->GetElement(
"gaussianNoise")->Get<
double>();
118 if (!_sdf->HasElement(
"updateRate"))
120 ROS_DEBUG_NAMED(
"p3d",
"p3d plugin missing <updateRate>, defaults to 0.0" 121 " (as fast as possible)");
125 this->
update_rate_ = _sdf->GetElement(
"updateRate")->Get<
double>();
131 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
152 #if GAZEBO_MAJOR_VERSION >= 8 155 this->last_time_ = this->
world_->GetSimTime();
158 #if GAZEBO_MAJOR_VERSION >= 8 159 this->
last_vpos_ = this->link_->WorldLinearVel();
160 this->
last_veul_ = this->link_->WorldAngularVel();
162 this->
last_vpos_ = this->link_->GetWorldLinearVel().Ign();
163 this->
last_veul_ = this->link_->GetWorldAngularVel().Ign();
178 ROS_ERROR_NAMED(
"p3d",
"gazebo_ros_p3d plugin: frameName: %s does not exist, will" 190 #if GAZEBO_MAJOR_VERSION >= 8 218 #if GAZEBO_MAJOR_VERSION >= 8 219 common::Time cur_time = this->
world_->SimTime();
221 common::Time cur_time = this->
world_->GetSimTime();
226 ROS_WARN_NAMED(
"p3d",
"Negative update time difference detected.");
227 this->last_time_ = cur_time;
232 (cur_time-this->last_time_).Double() < (1.0/this->
update_rate_))
238 double tmp_dt = cur_time.Double() - this->last_time_.Double();
247 this->
pose_msg_.header.stamp.sec = cur_time.sec;
248 this->
pose_msg_.header.stamp.nsec = cur_time.nsec;
252 ignition::math::Pose3d pose, frame_pose;
253 ignition::math::Vector3d frame_vpos;
254 ignition::math::Vector3d frame_veul;
258 #if GAZEBO_MAJOR_VERSION >= 8 259 ignition::math::Vector3d vpos = this->
link_->WorldLinearVel();
260 ignition::math::Vector3d veul = this->
link_->WorldAngularVel();
262 pose = this->
link_->WorldPose();
264 ignition::math::Vector3d vpos = this->
link_->GetWorldLinearVel().Ign();
265 ignition::math::Vector3d veul = this->
link_->GetWorldAngularVel().Ign();
267 pose = this->
link_->GetWorldPose().Ign();
274 #if GAZEBO_MAJOR_VERSION >= 8 283 pose.Pos() = pose.Pos() - frame_pose.Pos();
284 pose.Pos() = frame_pose.Rot().RotateVectorReverse(pose.Pos());
285 pose.Rot() *= frame_pose.Rot().Inverse();
287 vpos = frame_pose.Rot().RotateVector(vpos - frame_vpos);
288 veul = frame_pose.Rot().RotateVector(veul - frame_veul);
293 pose.Pos() = pose.Pos() + this->
offset_.Pos();
295 pose.Rot() = this->
offset_.Rot()*pose.Rot();
296 pose.Rot().Normalize();
310 this->
pose_msg_.pose.pose.position.x = pose.Pos().X();
311 this->
pose_msg_.pose.pose.position.y = pose.Pos().Y();
312 this->
pose_msg_.pose.pose.position.z = pose.Pos().Z();
314 this->
pose_msg_.pose.pose.orientation.x = pose.Rot().X();
315 this->
pose_msg_.pose.pose.orientation.y = pose.Rot().Y();
316 this->
pose_msg_.pose.pose.orientation.z = pose.Rot().Z();
317 this->
pose_msg_.pose.pose.orientation.w = pose.Rot().W();
319 this->
pose_msg_.twist.twist.linear.x = vpos.X() +
321 this->
pose_msg_.twist.twist.linear.y = vpos.Y() +
323 this->
pose_msg_.twist.twist.linear.z = vpos.Z() +
326 this->
pose_msg_.twist.twist.angular.x = veul.X() +
328 this->
pose_msg_.twist.twist.angular.y = veul.Y() +
330 this->
pose_msg_.twist.twist.angular.z = veul.Z() +
336 this->
pose_msg_.pose.covariance[0] = gn2;
337 this->
pose_msg_.pose.covariance[7] = gn2;
338 this->
pose_msg_.pose.covariance[14] = gn2;
339 this->
pose_msg_.pose.covariance[21] = gn2;
340 this->
pose_msg_.pose.covariance[28] = gn2;
341 this->
pose_msg_.pose.covariance[35] = gn2;
343 this->
pose_msg_.twist.covariance[0] = gn2;
344 this->
pose_msg_.twist.covariance[7] = gn2;
345 this->
pose_msg_.twist.covariance[14] = gn2;
346 this->
pose_msg_.twist.covariance[21] = gn2;
347 this->
pose_msg_.twist.covariance[28] = gn2;
348 this->
pose_msg_.twist.covariance[35] = gn2;
357 this->last_time_ = cur_time;
370 double U = ignition::math::Rand::DblUniform();
373 double V = ignition::math::Rand::DblUniform();
375 double X = sqrt(-2.0 * ::log(U)) * cos(2.0*M_PI * V);
388 static const double timeout = 0.01;
ignition::math::Pose3d offset_
allow specifying constant xyz and rpy offsets
void push(T &msg, ros::Publisher &pub)
Push a new message onto the queue.
double gaussian_noise_
Gaussian noise.
double GaussianKernel(double mu, double sigma)
Gaussian noise generator.
GazeboRosP3D()
Constructor.
ignition::math::Vector3d frame_aeul_
physics::LinkPtr reference_link_
The body of the frame to display pose, twist.
std::string frame_name_
frame transform name, should match link name FIXME: extract link name directly?
#define ROS_WARN_NAMED(name,...)
event::ConnectionPtr update_connection_
virtual void UpdateChild()
Update the controller.
ROSCPP_DECL bool isInitialized()
boost::mutex lock
mutex to lock access to fields used in message callbacks
ros::NodeHandle * rosnode_
pointer to ros node
virtual ~GazeboRosP3D()
Destructor.
std::string robot_namespace_
for setting ROS name space
ignition::math::Vector3d aeul_
ignition::math::Vector3d last_frame_vpos_
std::string resolve(const std::string &prefix, const std::string &frame_name)
#define ROS_DEBUG_NAMED(name,...)
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
ignition::math::Vector3d last_vpos_
PubQueue< nav_msgs::Odometry >::Ptr pub_Queue
ros::CallbackQueue p3d_queue_
ignition::math::Vector3d apos_
#define ROS_FATAL_STREAM_NAMED(name, args)
bool getParam(const std::string &key, std::string &s) const
ignition::math::Vector3d last_veul_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
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)...
common::Time last_time_
save last_time
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the controller.
physics::LinkPtr link_
The parent Model.
#define ROS_FATAL_NAMED(name,...)
#define ROS_ERROR_NAMED(name,...)
void startServiceThread()
Start a thread to call spin().
ignition::math::Vector3d frame_apos_
boost::thread callback_queue_thread_
ignition::math::Vector3d last_frame_veul_
std::string topic_name_
topic name
nav_msgs::Odometry pose_msg_
ros message
uint32_t getNumSubscribers() const
std::string tf_frame_name_
std::string link_name_
store bodyname