00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #include <algorithm>
00041 #include <assert.h>
00042
00043 #include <gazebo_plugins/gazebo_ros_skid_steer_drive.h>
00044
00045 #include <gazebo/math/gzmath.hh>
00046 #include <sdf/sdf.hh>
00047
00048 #include <ros/ros.h>
00049 #include <tf/transform_broadcaster.h>
00050 #include <tf/transform_listener.h>
00051 #include <geometry_msgs/Twist.h>
00052 #include <nav_msgs/GetMap.h>
00053 #include <nav_msgs/Odometry.h>
00054 #include <boost/bind.hpp>
00055 #include <boost/thread/mutex.hpp>
00056
00057 namespace gazebo {
00058
00059 enum {
00060 RIGHT_FRONT=0,
00061 LEFT_FRONT=1,
00062 RIGHT_REAR=2,
00063 LEFT_REAR=3,
00064 };
00065
00066 GazeboRosSkidSteerDrive::GazeboRosSkidSteerDrive() {}
00067
00068
00069 GazeboRosSkidSteerDrive::~GazeboRosSkidSteerDrive() {
00070 delete rosnode_;
00071 delete transform_broadcaster_;
00072 }
00073
00074
00075 void GazeboRosSkidSteerDrive::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf) {
00076
00077 this->parent = _parent;
00078 this->world = _parent->GetWorld();
00079
00080 this->robot_namespace_ = "";
00081 if (!_sdf->HasElement("robotNamespace")) {
00082 ROS_INFO("GazeboRosSkidSteerDrive Plugin missing <robotNamespace>, defaults to \"%s\"",
00083 this->robot_namespace_.c_str());
00084 } else {
00085 this->robot_namespace_ =
00086 _sdf->GetElement("robotNamespace")->Get<std::string>() + "/";
00087 }
00088
00089 this->broadcast_tf_ = false;
00090 if (!_sdf->HasElement("broadcastTF")) {
00091 if (!this->broadcast_tf_)
00092 ROS_INFO("GazeboRosSkidSteerDrive Plugin (ns = %s) missing <broadcastTF>, defaults to false.",this->robot_namespace_.c_str());
00093 else ROS_INFO("GazeboRosSkidSteerDrive Plugin (ns = %s) missing <broadcastTF>, defaults to true.",this->robot_namespace_.c_str());
00094
00095 } else {
00096 this->broadcast_tf_ = _sdf->GetElement("broadcastTF")->Get<bool>();
00097 }
00098
00099
00100 this->left_front_joint_name_ = "left_front_joint";
00101 if (!_sdf->HasElement("leftFrontJoint")) {
00102 ROS_WARN("GazeboRosSkidSteerDrive Plugin (ns = %s) missing <leftFrontJoint>, defaults to \"%s\"",
00103 this->robot_namespace_.c_str(), this->left_front_joint_name_.c_str());
00104 } else {
00105 this->left_front_joint_name_ = _sdf->GetElement("leftFrontJoint")->Get<std::string>();
00106 }
00107
00108 this->right_front_joint_name_ = "right_front_joint";
00109 if (!_sdf->HasElement("rightFrontJoint")) {
00110 ROS_WARN("GazeboRosSkidSteerDrive Plugin (ns = %s) missing <rightFrontJoint>, defaults to \"%s\"",
00111 this->robot_namespace_.c_str(), this->right_front_joint_name_.c_str());
00112 } else {
00113 this->right_front_joint_name_ = _sdf->GetElement("rightFrontJoint")->Get<std::string>();
00114 }
00115
00116 this->left_rear_joint_name_ = "left_rear_joint";
00117 if (!_sdf->HasElement("leftRearJoint")) {
00118 ROS_WARN("GazeboRosSkidSteerDrive Plugin (ns = %s) missing <leftRearJoint>, defaults to \"%s\"",
00119 this->robot_namespace_.c_str(), this->left_rear_joint_name_.c_str());
00120 } else {
00121 this->left_rear_joint_name_ = _sdf->GetElement("leftRearJoint")->Get<std::string>();
00122 }
00123
00124 this->right_rear_joint_name_ = "right_rear_joint";
00125 if (!_sdf->HasElement("rightRearJoint")) {
00126 ROS_WARN("GazeboRosSkidSteerDrive Plugin (ns = %s) missing <rightRearJoint>, defaults to \"%s\"",
00127 this->robot_namespace_.c_str(), this->right_rear_joint_name_.c_str());
00128 } else {
00129 this->right_rear_joint_name_ = _sdf->GetElement("rightRearJoint")->Get<std::string>();
00130 }
00131
00132
00133
00134
00135
00136
00137 this->wheel_separation_ = 0.4;
00138
00139 if (!_sdf->HasElement("wheelSeparation")) {
00140 ROS_WARN("GazeboRosSkidSteerDrive Plugin (ns = %s) missing <wheelSeparation>, defaults to value from robot_description: %f",
00141 this->robot_namespace_.c_str(), this->wheel_separation_);
00142 } else {
00143 this->wheel_separation_ =
00144 _sdf->GetElement("wheelSeparation")->Get<double>();
00145 }
00146
00147
00148 this->wheel_diameter_ = 0.15;
00149 if (!_sdf->HasElement("wheelDiameter")) {
00150 ROS_WARN("GazeboRosSkidSteerDrive Plugin (ns = %s) missing <wheelDiameter>, defaults to %f",
00151 this->robot_namespace_.c_str(), this->wheel_diameter_);
00152 } else {
00153 this->wheel_diameter_ = _sdf->GetElement("wheelDiameter")->Get<double>();
00154 }
00155
00156 this->torque = 5.0;
00157 if (!_sdf->HasElement("torque")) {
00158 ROS_WARN("GazeboRosSkidSteerDrive Plugin (ns = %s) missing <torque>, defaults to %f",
00159 this->robot_namespace_.c_str(), this->torque);
00160 } else {
00161 this->torque = _sdf->GetElement("torque")->Get<double>();
00162 }
00163
00164 this->command_topic_ = "cmd_vel";
00165 if (!_sdf->HasElement("commandTopic")) {
00166 ROS_WARN("GazeboRosSkidSteerDrive Plugin (ns = %s) missing <commandTopic>, defaults to \"%s\"",
00167 this->robot_namespace_.c_str(), this->command_topic_.c_str());
00168 } else {
00169 this->command_topic_ = _sdf->GetElement("commandTopic")->Get<std::string>();
00170 }
00171
00172 this->odometry_topic_ = "odom";
00173 if (!_sdf->HasElement("odometryTopic")) {
00174 ROS_WARN("GazeboRosSkidSteerDrive Plugin (ns = %s) missing <odometryTopic>, defaults to \"%s\"",
00175 this->robot_namespace_.c_str(), this->odometry_topic_.c_str());
00176 } else {
00177 this->odometry_topic_ = _sdf->GetElement("odometryTopic")->Get<std::string>();
00178 }
00179
00180 this->odometry_frame_ = "odom";
00181 if (!_sdf->HasElement("odometryFrame")) {
00182 ROS_WARN("GazeboRosSkidSteerDrive Plugin (ns = %s) missing <odometryFrame>, defaults to \"%s\"",
00183 this->robot_namespace_.c_str(), this->odometry_frame_.c_str());
00184 } else {
00185 this->odometry_frame_ = _sdf->GetElement("odometryFrame")->Get<std::string>();
00186 }
00187
00188 this->robot_base_frame_ = "base_footprint";
00189 if (!_sdf->HasElement("robotBaseFrame")) {
00190 ROS_WARN("GazeboRosSkidSteerDrive Plugin (ns = %s) missing <robotBaseFrame>, defaults to \"%s\"",
00191 this->robot_namespace_.c_str(), this->robot_base_frame_.c_str());
00192 } else {
00193 this->robot_base_frame_ = _sdf->GetElement("robotBaseFrame")->Get<std::string>();
00194 }
00195
00196 this->update_rate_ = 100.0;
00197 if (!_sdf->HasElement("updateRate")) {
00198 ROS_WARN("GazeboRosSkidSteerDrive Plugin (ns = %s) missing <updateRate>, defaults to %f",
00199 this->robot_namespace_.c_str(), this->update_rate_);
00200 } else {
00201 this->update_rate_ = _sdf->GetElement("updateRate")->Get<double>();
00202 }
00203
00204
00205 if (this->update_rate_ > 0.0) {
00206 this->update_period_ = 1.0 / this->update_rate_;
00207 } else {
00208 this->update_period_ = 0.0;
00209 }
00210 last_update_time_ = this->world->GetSimTime();
00211
00212
00213 wheel_speed_[RIGHT_FRONT] = 0;
00214 wheel_speed_[LEFT_FRONT] = 0;
00215 wheel_speed_[RIGHT_REAR] = 0;
00216 wheel_speed_[LEFT_REAR] = 0;
00217
00218 x_ = 0;
00219 rot_ = 0;
00220 alive_ = true;
00221
00222 joints[LEFT_FRONT] = this->parent->GetJoint(left_front_joint_name_);
00223 joints[RIGHT_FRONT] = this->parent->GetJoint(right_front_joint_name_);
00224 joints[LEFT_REAR] = this->parent->GetJoint(left_rear_joint_name_);
00225 joints[RIGHT_REAR] = this->parent->GetJoint(right_rear_joint_name_);
00226
00227 if (!joints[LEFT_FRONT]) {
00228 char error[200];
00229 snprintf(error, 200,
00230 "GazeboRosSkidSteerDrive Plugin (ns = %s) couldn't get left front hinge joint named \"%s\"",
00231 this->robot_namespace_.c_str(), this->left_front_joint_name_.c_str());
00232 gzthrow(error);
00233 }
00234
00235 if (!joints[RIGHT_FRONT]) {
00236 char error[200];
00237 snprintf(error, 200,
00238 "GazeboRosSkidSteerDrive Plugin (ns = %s) couldn't get right front hinge joint named \"%s\"",
00239 this->robot_namespace_.c_str(), this->right_front_joint_name_.c_str());
00240 gzthrow(error);
00241 }
00242
00243 if (!joints[LEFT_REAR]) {
00244 char error[200];
00245 snprintf(error, 200,
00246 "GazeboRosSkidSteerDrive Plugin (ns = %s) couldn't get left rear hinge joint named \"%s\"",
00247 this->robot_namespace_.c_str(), this->left_rear_joint_name_.c_str());
00248 gzthrow(error);
00249 }
00250
00251 if (!joints[RIGHT_REAR]) {
00252 char error[200];
00253 snprintf(error, 200,
00254 "GazeboRosSkidSteerDrive Plugin (ns = %s) couldn't get right rear hinge joint named \"%s\"",
00255 this->robot_namespace_.c_str(), this->right_rear_joint_name_.c_str());
00256 gzthrow(error);
00257 }
00258
00259 #if GAZEBO_MAJOR_VERSION > 2
00260 joints[LEFT_FRONT]->SetParam("fmax", 0, torque);
00261 joints[RIGHT_FRONT]->SetParam("fmax", 0, torque);
00262 joints[LEFT_REAR]->SetParam("fmax", 0, torque);
00263 joints[RIGHT_REAR]->SetParam("fmax", 0, torque);
00264 #else
00265 joints[LEFT_FRONT]->SetMaxForce(0, torque);
00266 joints[RIGHT_FRONT]->SetMaxForce(0, torque);
00267 joints[LEFT_REAR]->SetMaxForce(0, torque);
00268 joints[RIGHT_REAR]->SetMaxForce(0, torque);
00269 #endif
00270
00271
00272 if (!ros::isInitialized())
00273 {
00274 ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00275 << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00276 return;
00277 }
00278
00279 rosnode_ = new ros::NodeHandle(this->robot_namespace_);
00280
00281 ROS_INFO("Starting GazeboRosSkidSteerDrive Plugin (ns = %s)!", this->robot_namespace_.c_str());
00282
00283 tf_prefix_ = tf::getPrefixParam(*rosnode_);
00284 transform_broadcaster_ = new tf::TransformBroadcaster();
00285
00286
00287 ros::SubscribeOptions so =
00288 ros::SubscribeOptions::create<geometry_msgs::Twist>(command_topic_, 1,
00289 boost::bind(&GazeboRosSkidSteerDrive::cmdVelCallback, this, _1),
00290 ros::VoidPtr(), &queue_);
00291
00292 cmd_vel_subscriber_ = rosnode_->subscribe(so);
00293
00294 odometry_publisher_ = rosnode_->advertise<nav_msgs::Odometry>(odometry_topic_, 1);
00295
00296
00297 this->callback_queue_thread_ =
00298 boost::thread(boost::bind(&GazeboRosSkidSteerDrive::QueueThread, this));
00299
00300
00301 this->update_connection_ =
00302 event::Events::ConnectWorldUpdateBegin(
00303 boost::bind(&GazeboRosSkidSteerDrive::UpdateChild, this));
00304
00305 }
00306
00307
00308 void GazeboRosSkidSteerDrive::UpdateChild() {
00309 common::Time current_time = this->world->GetSimTime();
00310 double seconds_since_last_update =
00311 (current_time - last_update_time_).Double();
00312 if (seconds_since_last_update > update_period_) {
00313
00314 publishOdometry(seconds_since_last_update);
00315
00316
00317 getWheelVelocities();
00318 #if GAZEBO_MAJOR_VERSION > 2
00319 joints[LEFT_FRONT]->SetParam("vel", 0, wheel_speed_[LEFT_FRONT] / (wheel_diameter_ / 2.0));
00320 joints[RIGHT_FRONT]->SetParam("vel", 0, wheel_speed_[RIGHT_FRONT] / (wheel_diameter_ / 2.0));
00321 joints[LEFT_REAR]->SetParam("vel", 0, wheel_speed_[LEFT_REAR] / (wheel_diameter_ / 2.0));
00322 joints[RIGHT_REAR]->SetParam("vel", 0, wheel_speed_[RIGHT_REAR] / (wheel_diameter_ / 2.0));
00323 #else
00324 joints[LEFT_FRONT]->SetVelocity(0, wheel_speed_[LEFT_FRONT] / (wheel_diameter_ / 2.0));
00325 joints[RIGHT_FRONT]->SetVelocity(0, wheel_speed_[RIGHT_FRONT] / (wheel_diameter_ / 2.0));
00326 joints[LEFT_REAR]->SetVelocity(0, wheel_speed_[LEFT_REAR] / (wheel_diameter_ / 2.0));
00327 joints[RIGHT_REAR]->SetVelocity(0, wheel_speed_[RIGHT_REAR] / (wheel_diameter_ / 2.0));
00328 #endif
00329
00330 last_update_time_+= common::Time(update_period_);
00331
00332 }
00333 }
00334
00335
00336 void GazeboRosSkidSteerDrive::FiniChild() {
00337 alive_ = false;
00338 queue_.clear();
00339 queue_.disable();
00340 rosnode_->shutdown();
00341 callback_queue_thread_.join();
00342 }
00343
00344 void GazeboRosSkidSteerDrive::getWheelVelocities() {
00345 boost::mutex::scoped_lock scoped_lock(lock);
00346
00347 double vr = x_;
00348 double va = rot_;
00349
00350 wheel_speed_[RIGHT_FRONT] = vr + va * wheel_separation_ / 2.0;
00351 wheel_speed_[RIGHT_REAR] = vr + va * wheel_separation_ / 2.0;
00352
00353 wheel_speed_[LEFT_FRONT] = vr - va * wheel_separation_ / 2.0;
00354 wheel_speed_[LEFT_REAR] = vr - va * wheel_separation_ / 2.0;
00355
00356 }
00357
00358 void GazeboRosSkidSteerDrive::cmdVelCallback(
00359 const geometry_msgs::Twist::ConstPtr& cmd_msg) {
00360
00361 boost::mutex::scoped_lock scoped_lock(lock);
00362 x_ = cmd_msg->linear.x;
00363 rot_ = cmd_msg->angular.z;
00364 }
00365
00366 void GazeboRosSkidSteerDrive::QueueThread() {
00367 static const double timeout = 0.01;
00368
00369 while (alive_ && rosnode_->ok()) {
00370 queue_.callAvailable(ros::WallDuration(timeout));
00371 }
00372 }
00373
00374 void GazeboRosSkidSteerDrive::publishOdometry(double step_time) {
00375 ros::Time current_time = ros::Time::now();
00376 std::string odom_frame =
00377 tf::resolve(tf_prefix_, odometry_frame_);
00378 std::string base_footprint_frame =
00379 tf::resolve(tf_prefix_, robot_base_frame_);
00380
00381
00382
00383 math::Pose pose = this->parent->GetWorldPose();
00384
00385 tf::Quaternion qt(pose.rot.x, pose.rot.y, pose.rot.z, pose.rot.w);
00386 tf::Vector3 vt(pose.pos.x, pose.pos.y, pose.pos.z);
00387
00388 tf::Transform base_footprint_to_odom(qt, vt);
00389 if (this->broadcast_tf_) {
00390
00391 transform_broadcaster_->sendTransform(
00392 tf::StampedTransform(base_footprint_to_odom, current_time,
00393 odom_frame, base_footprint_frame));
00394
00395 }
00396
00397
00398 odom_.pose.pose.position.x = pose.pos.x;
00399 odom_.pose.pose.position.y = pose.pos.y;
00400
00401 odom_.pose.pose.orientation.x = pose.rot.x;
00402 odom_.pose.pose.orientation.y = pose.rot.y;
00403 odom_.pose.pose.orientation.z = pose.rot.z;
00404 odom_.pose.pose.orientation.w = pose.rot.w;
00405 odom_.pose.covariance[0] = 0.00001;
00406 odom_.pose.covariance[7] = 0.00001;
00407 odom_.pose.covariance[14] = 1000000000000.0;
00408 odom_.pose.covariance[21] = 1000000000000.0;
00409 odom_.pose.covariance[28] = 1000000000000.0;
00410 odom_.pose.covariance[35] = 0.01;
00411
00412
00413 math::Vector3 linear;
00414 linear = this->parent->GetWorldLinearVel();
00415 odom_.twist.twist.angular.z = this->parent->GetWorldAngularVel().z;
00416
00417
00418 float yaw = pose.rot.GetYaw();
00419 odom_.twist.twist.linear.x = cosf(yaw) * linear.x + sinf(yaw) * linear.y;
00420 odom_.twist.twist.linear.y = cosf(yaw) * linear.y - sinf(yaw) * linear.x;
00421
00422 odom_.header.stamp = current_time;
00423 odom_.header.frame_id = odom_frame;
00424 odom_.child_frame_id = base_footprint_frame;
00425
00426 odometry_publisher_.publish(odom_);
00427 }
00428
00429 GZ_REGISTER_MODEL_PLUGIN(GazeboRosSkidSteerDrive)
00430 }