55 #ifdef ENABLE_PROFILER
56 #include <ignition/common/Profiler.hh>
59 #include <ignition/math/Angle.hh>
60 #include <ignition/math/Pose3.hh>
61 #include <ignition/math/Quaternion.hh>
62 #include <ignition/math/Vector3.hh>
104 std::map<std::string, OdomSource> odomOptions;
105 odomOptions[
"encoder"] =
ENCODER;
106 odomOptions[
"world"] =
WORLD;
119 if (!_sdf->HasElement(
"publishTf")) {
120 ROS_WARN_NAMED(
"diff_drive",
"GazeboRosDiffDrive Plugin (ns = %s) missing <publishTf>, defaults to %d",
123 this->
publish_tf_ = _sdf->GetElement(
"publishTf")->Get<
bool>();
129 #if GAZEBO_MAJOR_VERSION >= 8
160 ros::SubscribeOptions::create<geometry_msgs::Twist>(
command_topic_, 1,
185 #if GAZEBO_MAJOR_VERSION >= 8
207 for (
int i = 0; i < 2; i++ ) {
208 physics::JointPtr joint =
joints_[i];
209 #if GAZEBO_MAJOR_VERSION >= 8
210 double position = joint->Position ( 0 );
212 double position = joint->GetAngle ( 0 ).Radian();
223 for (
int i = 0; i < 2; i++ ) {
226 std::string wheel_parent_frame =
gazebo_ros_->resolveTF(
joints_[i]->GetParent()->GetName ());
228 #if GAZEBO_MAJOR_VERSION >= 8
229 ignition::math::Pose3d poseWheel =
joints_[i]->GetChild()->RelativePose();
231 ignition::math::Pose3d poseWheel =
joints_[i]->GetChild()->GetRelativePose().Ign();
234 tf::Quaternion qt ( poseWheel.Rot().X(), poseWheel.Rot().Y(), poseWheel.Rot().Z(), poseWheel.Rot().W() );
235 tf::Vector3 vt ( poseWheel.Pos().X(), poseWheel.Pos().Y(), poseWheel.Pos().Z() );
246 #ifdef ENABLE_PROFILER
247 IGN_PROFILE(
"GazeboRosDiffDrive::UpdateChild");
248 IGN_PROFILE_BEGIN(
"update");
256 for (
int i = 0; i < 2; i++ ) {
264 #if GAZEBO_MAJOR_VERSION >= 8
265 common::Time current_time =
parent->GetWorld()->SimTime();
267 common::Time current_time =
parent->GetWorld()->GetSimTime();
269 double seconds_since_last_update = ( current_time -
last_update_time_ ).Double();
279 double current_speed[2];
309 #ifdef ENABLE_PROFILER
326 boost::mutex::scoped_lock scoped_lock (
lock );
337 boost::mutex::scoped_lock scoped_lock (
lock );
338 x_ = cmd_msg->linear.x;
339 rot_ = cmd_msg->angular.z;
344 static const double timeout = 0.01;
355 #if GAZEBO_MAJOR_VERSION >= 8
356 common::Time current_time =
parent->GetWorld()->SimTime();
358 common::Time current_time =
parent->GetWorld()->GetSimTime();
360 double seconds_since_last_update = ( current_time -
last_odom_update_ ).Double();
366 double sl = vl * (
wheel_diameter_ / 2.0 ) * seconds_since_last_update;
367 double sr = vr * (
wheel_diameter_ / 2.0 ) * seconds_since_last_update;
368 double ssum = sl + sr;
370 double sdiff = sr - sl;
372 double dx = ( ssum ) /2.0 * cos (
pose_encoder_.theta + ( sdiff ) / ( 2.0*b ) );
373 double dy = ( ssum ) /2.0 * sin (
pose_encoder_.theta + ( sdiff ) / ( 2.0*b ) );
374 double dtheta = ( sdiff ) /b;
380 double w = dtheta/seconds_since_last_update;
381 double v = sqrt ( dx*dx+dy*dy ) /seconds_since_last_update;
388 odom_.pose.pose.position.x = vt.x();
389 odom_.pose.pose.position.y = vt.y();
390 odom_.pose.pose.position.z = vt.z();
392 odom_.pose.pose.orientation.x = qt.x();
393 odom_.pose.pose.orientation.y = qt.y();
394 odom_.pose.pose.orientation.z = qt.z();
395 odom_.pose.pose.orientation.w = qt.w();
397 odom_.twist.twist.angular.z = w;
398 odom_.twist.twist.linear.x = v;
399 odom_.twist.twist.linear.y = 0;
415 vt = tf::Vector3 (
odom_.pose.pose.position.x,
odom_.pose.pose.position.y,
odom_.pose.pose.position.z );
420 #if GAZEBO_MAJOR_VERSION >= 8
421 ignition::math::Pose3d pose =
parent->WorldPose();
423 ignition::math::Pose3d pose =
parent->GetWorldPose().Ign();
425 qt =
tf::Quaternion ( pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W() );
426 vt = tf::Vector3 ( pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z() );
428 odom_.pose.pose.position.x = vt.x();
429 odom_.pose.pose.position.y = vt.y();
430 odom_.pose.pose.position.z = vt.z();
432 odom_.pose.pose.orientation.x = qt.x();
433 odom_.pose.pose.orientation.y = qt.y();
434 odom_.pose.pose.orientation.z = qt.z();
435 odom_.pose.pose.orientation.w = qt.w();
438 ignition::math::Vector3d linear;
439 #if GAZEBO_MAJOR_VERSION >= 8
440 linear =
parent->WorldLinearVel();
441 odom_.twist.twist.angular.z =
parent->WorldAngularVel().Z();
443 linear =
parent->GetWorldLinearVel().Ign();
444 odom_.twist.twist.angular.z =
parent->GetWorldAngularVel().Ign().Z();
448 float yaw = pose.Rot().Yaw();
449 odom_.twist.twist.linear.x = cosf ( yaw ) * linear.X() + sinf ( yaw ) * linear.Y();
450 odom_.twist.twist.linear.y = cosf ( yaw ) * linear.Y() - sinf ( yaw ) * linear.X();
457 odom_frame, base_footprint_frame ) );
462 odom_.pose.covariance[0] = 0.00001;
463 odom_.pose.covariance[7] = 0.00001;
464 odom_.pose.covariance[14] = 1000000000000.0;
465 odom_.pose.covariance[21] = 1000000000000.0;
466 odom_.pose.covariance[28] = 1000000000000.0;
467 odom_.pose.covariance[35] = 0.001;
471 odom_.header.stamp = current_time;
472 odom_.header.frame_id = odom_frame;
473 odom_.child_frame_id = base_footprint_frame;