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