45 #ifdef ENABLE_PROFILER
46 #include <ignition/common/Profiler.hh>
48 #include <ignition/math/Pose3.hh>
49 #include <ignition/math/Vector3.hh>
55 #include <geometry_msgs/Twist.h>
56 #include <nav_msgs/GetMap.h>
57 #include <nav_msgs/Odometry.h>
58 #include <boost/bind.hpp>
59 #include <boost/thread/mutex.hpp>
82 this->
world = _parent->GetWorld();
85 if (!_sdf->HasElement(
"robotNamespace")) {
86 ROS_INFO_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin missing <robotNamespace>, defaults to \"%s\"",
90 _sdf->GetElement(
"robotNamespace")->Get<std::string>() +
"/";
94 if (!_sdf->HasElement(
"broadcastTF")) {
96 ROS_INFO_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin (ns = %s) missing <broadcastTF>, defaults to false.",this->
robot_namespace_.c_str());
97 else ROS_INFO_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin (ns = %s) missing <broadcastTF>, defaults to true.",this->
robot_namespace_.c_str());
100 this->
broadcast_tf_ = _sdf->GetElement(
"broadcastTF")->Get<
bool>();
105 if (!_sdf->HasElement(
"leftFrontJoint")) {
106 ROS_WARN_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin (ns = %s) missing <leftFrontJoint>, defaults to \"%s\"",
113 if (!_sdf->HasElement(
"rightFrontJoint")) {
114 ROS_WARN_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin (ns = %s) missing <rightFrontJoint>, defaults to \"%s\"",
121 if (!_sdf->HasElement(
"leftRearJoint")) {
122 ROS_WARN_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin (ns = %s) missing <leftRearJoint>, defaults to \"%s\"",
129 if (!_sdf->HasElement(
"rightRearJoint")) {
130 ROS_WARN_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin (ns = %s) missing <rightRearJoint>, defaults to \"%s\"",
143 if (!_sdf->HasElement(
"wheelSeparation")) {
144 ROS_WARN_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin (ns = %s) missing <wheelSeparation>, defaults to value from robot_description: %f",
148 _sdf->GetElement(
"wheelSeparation")->Get<
double>();
153 if (!_sdf->HasElement(
"wheelDiameter")) {
154 ROS_WARN_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin (ns = %s) missing <wheelDiameter>, defaults to %f",
157 this->
wheel_diameter_ = _sdf->GetElement(
"wheelDiameter")->Get<
double>();
161 if (!_sdf->HasElement(
"torque")) {
162 ROS_WARN_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin (ns = %s) missing <torque>, defaults to %f",
165 this->
torque = _sdf->GetElement(
"torque")->Get<
double>();
169 if (!_sdf->HasElement(
"commandTopic")) {
170 ROS_WARN_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin (ns = %s) missing <commandTopic>, defaults to \"%s\"",
173 this->
command_topic_ = _sdf->GetElement(
"commandTopic")->Get<std::string>();
177 if (!_sdf->HasElement(
"odometryTopic")) {
178 ROS_WARN_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin (ns = %s) missing <odometryTopic>, defaults to \"%s\"",
181 this->
odometry_topic_ = _sdf->GetElement(
"odometryTopic")->Get<std::string>();
185 if (!_sdf->HasElement(
"odometryFrame")) {
186 ROS_WARN_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin (ns = %s) missing <odometryFrame>, defaults to \"%s\"",
189 this->
odometry_frame_ = _sdf->GetElement(
"odometryFrame")->Get<std::string>();
193 if (!_sdf->HasElement(
"robotBaseFrame")) {
194 ROS_WARN_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin (ns = %s) missing <robotBaseFrame>, defaults to \"%s\"",
197 this->
robot_base_frame_ = _sdf->GetElement(
"robotBaseFrame")->Get<std::string>();
201 if (!_sdf->HasElement(
"updateRate")) {
202 ROS_WARN_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin (ns = %s) missing <updateRate>, defaults to %f",
205 this->
update_rate_ = _sdf->GetElement(
"updateRate")->Get<
double>();
209 if (!_sdf->HasElement(
"covariance_x")) {
210 ROS_WARN_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin (ns = %s) missing <covariance_x>, defaults to %f",
213 covariance_x_ = _sdf->GetElement(
"covariance_x")->Get<
double>();
217 if (!_sdf->HasElement(
"covariance_y")) {
218 ROS_WARN_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin (ns = %s) missing <covariance_y>, defaults to %f",
221 covariance_y_ = _sdf->GetElement(
"covariance_y")->Get<
double>();
225 if (!_sdf->HasElement(
"covariance_yaw")) {
226 ROS_WARN_NAMED(
"skid_steer_drive",
"GazeboRosSkidSteerDrive Plugin (ns = %s) missing <covariance_yaw>, defaults to %f",
238 #if GAZEBO_MAJOR_VERSION >= 8
262 "GazeboRosSkidSteerDrive Plugin (ns = %s) couldn't get left front hinge joint named \"%s\"",
270 "GazeboRosSkidSteerDrive Plugin (ns = %s) couldn't get right front hinge joint named \"%s\"",
278 "GazeboRosSkidSteerDrive Plugin (ns = %s) couldn't get left rear hinge joint named \"%s\"",
286 "GazeboRosSkidSteerDrive Plugin (ns = %s) couldn't get right rear hinge joint named \"%s\"",
291 #if GAZEBO_MAJOR_VERSION > 2
306 ROS_FATAL_STREAM_NAMED(
"skid_steer_drive",
"A ROS node for Gazebo has not been initialized, unable to load plugin. "
307 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
320 ros::SubscribeOptions::create<geometry_msgs::Twist>(
command_topic_, 1,
334 event::Events::ConnectWorldUpdateBegin(
342 #ifdef ENABLE_PROFILER
343 IGN_PROFILE(
"GazeboRosSkidSteerDrive::UpdateChild");
345 #if GAZEBO_MAJOR_VERSION >= 8
346 common::Time current_time = this->
world->SimTime();
348 common::Time current_time = this->
world->GetSimTime();
350 double seconds_since_last_update =
353 #ifdef ENABLE_PROFILER
354 IGN_PROFILE_BEGIN(
"publishOdometry");
357 #ifdef ENABLE_PROFILER
361 IGN_PROFILE_BEGIN(
"getWheelVelocities");
364 #ifdef ENABLE_PROFILER
366 IGN_PROFILE_BEGIN(
"SetVelocity");
368 #if GAZEBO_MAJOR_VERSION > 2
379 #ifdef ENABLE_PROFILER
396 boost::mutex::scoped_lock scoped_lock(
lock);
410 const geometry_msgs::Twist::ConstPtr& cmd_msg) {
412 boost::mutex::scoped_lock scoped_lock(
lock);
413 x_ = cmd_msg->linear.x;
414 rot_ = cmd_msg->angular.z;
418 static const double timeout = 0.01;
427 std::string odom_frame =
429 std::string base_footprint_frame =
434 #if GAZEBO_MAJOR_VERSION >= 8
435 ignition::math::Pose3d pose = this->
parent->WorldPose();
437 ignition::math::Pose3d pose = this->
parent->GetWorldPose().Ign();
440 tf::Quaternion qt(pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W());
441 tf::Vector3 vt(pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z());
448 odom_frame, base_footprint_frame));
453 odom_.pose.pose.position.x = pose.Pos().X();
454 odom_.pose.pose.position.y = pose.Pos().Y();
456 odom_.pose.pose.orientation.x = pose.Rot().X();
457 odom_.pose.pose.orientation.y = pose.Rot().Y();
458 odom_.pose.pose.orientation.z = pose.Rot().Z();
459 odom_.pose.pose.orientation.w = pose.Rot().W();
462 odom_.pose.covariance[14] = 1000000000000.0;
463 odom_.pose.covariance[21] = 1000000000000.0;
464 odom_.pose.covariance[28] = 1000000000000.0;
468 ignition::math::Vector3d linear;
469 #if GAZEBO_MAJOR_VERSION >= 8
470 linear = this->
parent->WorldLinearVel();
471 odom_.twist.twist.angular.z = this->
parent->WorldAngularVel().Z();
473 linear = this->
parent->GetWorldLinearVel().Ign();
474 odom_.twist.twist.angular.z = this->
parent->GetWorldAngularVel().Ign().Z();
478 float yaw = pose.Rot().Yaw();
479 odom_.twist.twist.linear.x = cosf(yaw) * linear.X() + sinf(yaw) * linear.Y();
480 odom_.twist.twist.linear.y = cosf(yaw) * linear.Y() - sinf(yaw) * linear.X();
483 odom_.twist.covariance[14] = 1000000000000.0;
484 odom_.twist.covariance[21] = 1000000000000.0;
485 odom_.twist.covariance[28] = 1000000000000.0;
488 odom_.header.stamp = current_time;
489 odom_.header.frame_id = odom_frame;
490 odom_.child_frame_id = base_footprint_frame;