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
00042
00043
00044
00045
00046
00047
00048
00049
00050 #include <algorithm>
00051 #include <assert.h>
00052
00053 #include <gazebo_plugins/gazebo_ros_diff_drive.h>
00054
00055 #include <gazebo/math/gzmath.hh>
00056 #include <sdf/sdf.hh>
00057
00058 #include <ros/ros.h>
00059
00060 namespace gazebo
00061 {
00062
00063 enum {
00064 RIGHT,
00065 LEFT,
00066 };
00067
00068 GazeboRosDiffDrive::GazeboRosDiffDrive() {}
00069
00070
00071 GazeboRosDiffDrive::~GazeboRosDiffDrive() {}
00072
00073
00074 void GazeboRosDiffDrive::Load ( physics::ModelPtr _parent, sdf::ElementPtr _sdf )
00075 {
00076
00077 this->parent = _parent;
00078 gazebo_ros_ = GazeboRosPtr ( new GazeboRos ( _parent, _sdf, "DiffDrive" ) );
00079
00080 gazebo_ros_->isInitialized();
00081
00082 gazebo_ros_->getParameter<std::string> ( command_topic_, "commandTopic", "cmd_vel" );
00083 gazebo_ros_->getParameter<std::string> ( odometry_topic_, "odometryTopic", "odom" );
00084 gazebo_ros_->getParameter<std::string> ( odometry_frame_, "odometryFrame", "odom" );
00085 gazebo_ros_->getParameter<std::string> ( robot_base_frame_, "robotBaseFrame", "base_footprint" );
00086 gazebo_ros_->getParameterBoolean ( publishWheelTF_, "publishWheelTF", false );
00087 gazebo_ros_->getParameterBoolean ( publishWheelJointState_, "publishWheelJointState", false );
00088 gazebo_ros_->getParameterBoolean ( legacy_mode_, "legacyMode", true );
00089
00090 if (!_sdf->HasElement("legacyMode"))
00091 {
00092 ROS_ERROR("GazeboRosDiffDrive Plugin missing <legacyMode>, defaults to true\n"
00093 "This setting assumes you have a old package, where the right and left wheel are changed to fix a former code issue\n"
00094 "To get rid of this error just set <legacyMode> to false if you just created a new package.\n"
00095 "To fix an old package you have to exchange left wheel by the right wheel.\n"
00096 "If you do not want to fix this issue in an old package or your z axis points down instead of the ROS standard defined in REP 103\n"
00097 "just set <legacyMode> to true.\n"
00098 );
00099 }
00100
00101 gazebo_ros_->getParameter<double> ( wheel_separation_, "wheelSeparation", 0.34 );
00102 gazebo_ros_->getParameter<double> ( wheel_diameter_, "wheelDiameter", 0.15 );
00103 gazebo_ros_->getParameter<double> ( wheel_accel, "wheelAcceleration", 0.0 );
00104 gazebo_ros_->getParameter<double> ( wheel_torque, "wheelTorque", 5.0 );
00105 gazebo_ros_->getParameter<double> ( update_rate_, "updateRate", 100.0 );
00106 std::map<std::string, OdomSource> odomOptions;
00107 odomOptions["encoder"] = ENCODER;
00108 odomOptions["world"] = WORLD;
00109 gazebo_ros_->getParameter<OdomSource> ( odom_source_, "odometrySource", odomOptions, WORLD );
00110
00111
00112 joints_.resize ( 2 );
00113 joints_[LEFT] = gazebo_ros_->getJoint ( parent, "leftJoint", "left_joint" );
00114 joints_[RIGHT] = gazebo_ros_->getJoint ( parent, "rightJoint", "right_joint" );
00115 #if GAZEBO_MAJOR_VERSION > 2
00116 joints_[LEFT]->SetParam ( "fmax", 0, wheel_torque );
00117 joints_[RIGHT]->SetParam ( "fmax", 0, wheel_torque );
00118 #else
00119 joints_[LEFT]->SetMaxForce ( 0, wheel_torque );
00120 joints_[RIGHT]->SetMaxForce ( 0, wheel_torque );
00121 #endif
00122
00123
00124
00125 this->publish_tf_ = true;
00126 if (!_sdf->HasElement("publishTf")) {
00127 ROS_WARN("GazeboRosDiffDrive Plugin (ns = %s) missing <publishTf>, defaults to %d",
00128 this->robot_namespace_.c_str(), this->publish_tf_);
00129 } else {
00130 this->publish_tf_ = _sdf->GetElement("publishTf")->Get<bool>();
00131 }
00132
00133
00134 if ( this->update_rate_ > 0.0 ) this->update_period_ = 1.0 / this->update_rate_;
00135 else this->update_period_ = 0.0;
00136 last_update_time_ = parent->GetWorld()->GetSimTime();
00137
00138
00139 wheel_speed_[RIGHT] = 0;
00140 wheel_speed_[LEFT] = 0;
00141
00142
00143 wheel_speed_instr_[RIGHT] = 0;
00144 wheel_speed_instr_[LEFT] = 0;
00145
00146 x_ = 0;
00147 rot_ = 0;
00148 alive_ = true;
00149
00150
00151 if (this->publishWheelJointState_)
00152 {
00153 joint_state_publisher_ = gazebo_ros_->node()->advertise<sensor_msgs::JointState>("joint_states", 1000);
00154 ROS_INFO("%s: Advertise joint_states!", gazebo_ros_->info());
00155 }
00156
00157 transform_broadcaster_ = boost::shared_ptr<tf::TransformBroadcaster>(new tf::TransformBroadcaster());
00158
00159
00160 ROS_INFO("%s: Try to subscribe to %s!", gazebo_ros_->info(), command_topic_.c_str());
00161
00162 ros::SubscribeOptions so =
00163 ros::SubscribeOptions::create<geometry_msgs::Twist>(command_topic_, 1,
00164 boost::bind(&GazeboRosDiffDrive::cmdVelCallback, this, _1),
00165 ros::VoidPtr(), &queue_);
00166
00167 cmd_vel_subscriber_ = gazebo_ros_->node()->subscribe(so);
00168 ROS_INFO("%s: Subscribe to %s!", gazebo_ros_->info(), command_topic_.c_str());
00169
00170 if (this->publish_tf_)
00171 {
00172 odometry_publisher_ = gazebo_ros_->node()->advertise<nav_msgs::Odometry>(odometry_topic_, 1);
00173 ROS_INFO("%s: Advertise odom on %s !", gazebo_ros_->info(), odometry_topic_.c_str());
00174 }
00175
00176
00177 this->callback_queue_thread_ =
00178 boost::thread ( boost::bind ( &GazeboRosDiffDrive::QueueThread, this ) );
00179
00180
00181 this->update_connection_ =
00182 event::Events::ConnectWorldUpdateBegin ( boost::bind ( &GazeboRosDiffDrive::UpdateChild, this ) );
00183
00184 }
00185
00186 void GazeboRosDiffDrive::Reset()
00187 {
00188 last_update_time_ = parent->GetWorld()->GetSimTime();
00189 pose_encoder_.x = 0;
00190 pose_encoder_.y = 0;
00191 pose_encoder_.theta = 0;
00192 x_ = 0;
00193 rot_ = 0;
00194 #if GAZEBO_MAJOR_VERSION > 2
00195 joints_[LEFT]->SetParam ( "fmax", 0, wheel_torque );
00196 joints_[RIGHT]->SetParam ( "fmax", 0, wheel_torque );
00197 #else
00198 joints_[LEFT]->SetMaxForce ( 0, wheel_torque );
00199 joints_[RIGHT]->SetMaxForce ( 0, wheel_torque );
00200 #endif
00201 }
00202
00203 void GazeboRosDiffDrive::publishWheelJointState()
00204 {
00205 ros::Time current_time = ros::Time::now();
00206
00207 joint_state_.header.stamp = current_time;
00208 joint_state_.name.resize ( joints_.size() );
00209 joint_state_.position.resize ( joints_.size() );
00210
00211 for ( int i = 0; i < 2; i++ ) {
00212 physics::JointPtr joint = joints_[i];
00213 math::Angle angle = joint->GetAngle ( 0 );
00214 joint_state_.name[i] = joint->GetName();
00215 joint_state_.position[i] = angle.Radian () ;
00216 }
00217 joint_state_publisher_.publish ( joint_state_ );
00218 }
00219
00220 void GazeboRosDiffDrive::publishWheelTF()
00221 {
00222 ros::Time current_time = ros::Time::now();
00223 for ( int i = 0; i < 2; i++ ) {
00224
00225 std::string wheel_frame = gazebo_ros_->resolveTF(joints_[i]->GetChild()->GetName ());
00226 std::string wheel_parent_frame = gazebo_ros_->resolveTF(joints_[i]->GetParent()->GetName ());
00227
00228 math::Pose poseWheel = joints_[i]->GetChild()->GetRelativePose();
00229
00230 tf::Quaternion qt ( poseWheel.rot.x, poseWheel.rot.y, poseWheel.rot.z, poseWheel.rot.w );
00231 tf::Vector3 vt ( poseWheel.pos.x, poseWheel.pos.y, poseWheel.pos.z );
00232
00233 tf::Transform tfWheel ( qt, vt );
00234 transform_broadcaster_->sendTransform (
00235 tf::StampedTransform ( tfWheel, current_time, wheel_parent_frame, wheel_frame ) );
00236 }
00237 }
00238
00239
00240 void GazeboRosDiffDrive::UpdateChild()
00241 {
00242
00243
00244
00245
00246
00247
00248
00249 for ( int i = 0; i < 2; i++ ) {
00250 #if GAZEBO_MAJOR_VERSION > 2
00251 if ( fabs(wheel_torque -joints_[i]->GetParam ( "fmax", 0 )) > 1e-6 ) {
00252 joints_[i]->SetParam ( "fmax", 0, wheel_torque );
00253 #else
00254 if ( fabs(wheel_torque -joints_[i]->GetMaxForce ( 0 )) > 1e-6 ) {
00255 joints_[i]->SetMaxForce ( 0, wheel_torque );
00256 #endif
00257 }
00258 }
00259
00260
00261 if ( odom_source_ == ENCODER ) UpdateOdometryEncoder();
00262 common::Time current_time = parent->GetWorld()->GetSimTime();
00263 double seconds_since_last_update = ( current_time - last_update_time_ ).Double();
00264
00265 if ( seconds_since_last_update > update_period_ ) {
00266 if (this->publish_tf_) publishOdometry ( seconds_since_last_update );
00267 if ( publishWheelTF_ ) publishWheelTF();
00268 if ( publishWheelJointState_ ) publishWheelJointState();
00269
00270
00271 getWheelVelocities();
00272
00273 double current_speed[2];
00274
00275 current_speed[LEFT] = joints_[LEFT]->GetVelocity ( 0 ) * ( wheel_diameter_ / 2.0 );
00276 current_speed[RIGHT] = joints_[RIGHT]->GetVelocity ( 0 ) * ( wheel_diameter_ / 2.0 );
00277
00278 if ( wheel_accel == 0 ||
00279 ( fabs ( wheel_speed_[LEFT] - current_speed[LEFT] ) < 0.01 ) ||
00280 ( fabs ( wheel_speed_[RIGHT] - current_speed[RIGHT] ) < 0.01 ) ) {
00281
00282 #if GAZEBO_MAJOR_VERSION > 2
00283 joints_[LEFT]->SetParam ( "vel", 0, wheel_speed_[LEFT]/ ( wheel_diameter_ / 2.0 ) );
00284 joints_[RIGHT]->SetParam ( "vel", 0, wheel_speed_[RIGHT]/ ( wheel_diameter_ / 2.0 ) );
00285 #else
00286 joints_[LEFT]->SetVelocity ( 0, wheel_speed_[LEFT]/ ( wheel_diameter_ / 2.0 ) );
00287 joints_[RIGHT]->SetVelocity ( 0, wheel_speed_[RIGHT]/ ( wheel_diameter_ / 2.0 ) );
00288 #endif
00289 } else {
00290 if ( wheel_speed_[LEFT]>=current_speed[LEFT] )
00291 wheel_speed_instr_[LEFT]+=fmin ( wheel_speed_[LEFT]-current_speed[LEFT], wheel_accel * seconds_since_last_update );
00292 else
00293 wheel_speed_instr_[LEFT]+=fmax ( wheel_speed_[LEFT]-current_speed[LEFT], -wheel_accel * seconds_since_last_update );
00294
00295 if ( wheel_speed_[RIGHT]>current_speed[RIGHT] )
00296 wheel_speed_instr_[RIGHT]+=fmin ( wheel_speed_[RIGHT]-current_speed[RIGHT], wheel_accel * seconds_since_last_update );
00297 else
00298 wheel_speed_instr_[RIGHT]+=fmax ( wheel_speed_[RIGHT]-current_speed[RIGHT], -wheel_accel * seconds_since_last_update );
00299
00300
00301
00302
00303 #if GAZEBO_MAJOR_VERSION > 2
00304 joints_[LEFT]->SetParam ( "vel", 0, wheel_speed_instr_[LEFT] / ( wheel_diameter_ / 2.0 ) );
00305 joints_[RIGHT]->SetParam ( "vel", 0, wheel_speed_instr_[RIGHT] / ( wheel_diameter_ / 2.0 ) );
00306 #else
00307 joints_[LEFT]->SetVelocity ( 0,wheel_speed_instr_[LEFT] / ( wheel_diameter_ / 2.0 ) );
00308 joints_[RIGHT]->SetVelocity ( 0,wheel_speed_instr_[RIGHT] / ( wheel_diameter_ / 2.0 ) );
00309 #endif
00310 }
00311 last_update_time_+= common::Time ( update_period_ );
00312 }
00313 }
00314
00315
00316 void GazeboRosDiffDrive::FiniChild()
00317 {
00318 alive_ = false;
00319 queue_.clear();
00320 queue_.disable();
00321 gazebo_ros_->node()->shutdown();
00322 callback_queue_thread_.join();
00323 }
00324
00325 void GazeboRosDiffDrive::getWheelVelocities()
00326 {
00327 boost::mutex::scoped_lock scoped_lock ( lock );
00328
00329 double vr = x_;
00330 double va = rot_;
00331
00332 if(legacy_mode_)
00333 {
00334 wheel_speed_[LEFT] = vr + va * wheel_separation_ / 2.0;
00335 wheel_speed_[RIGHT] = vr - va * wheel_separation_ / 2.0;
00336 }
00337 else
00338 {
00339 wheel_speed_[LEFT] = vr - va * wheel_separation_ / 2.0;
00340 wheel_speed_[RIGHT] = vr + va * wheel_separation_ / 2.0;
00341 }
00342 }
00343
00344 void GazeboRosDiffDrive::cmdVelCallback ( const geometry_msgs::Twist::ConstPtr& cmd_msg )
00345 {
00346 boost::mutex::scoped_lock scoped_lock ( lock );
00347 x_ = cmd_msg->linear.x;
00348 rot_ = cmd_msg->angular.z;
00349 }
00350
00351 void GazeboRosDiffDrive::QueueThread()
00352 {
00353 static const double timeout = 0.01;
00354
00355 while ( alive_ && gazebo_ros_->node()->ok() ) {
00356 queue_.callAvailable ( ros::WallDuration ( timeout ) );
00357 }
00358 }
00359
00360 void GazeboRosDiffDrive::UpdateOdometryEncoder()
00361 {
00362 double vl = joints_[LEFT]->GetVelocity ( 0 );
00363 double vr = joints_[RIGHT]->GetVelocity ( 0 );
00364 common::Time current_time = parent->GetWorld()->GetSimTime();
00365 double seconds_since_last_update = ( current_time - last_odom_update_ ).Double();
00366 last_odom_update_ = current_time;
00367
00368 double b = wheel_separation_;
00369
00370
00371 double sl = vl * ( wheel_diameter_ / 2.0 ) * seconds_since_last_update;
00372 double sr = vr * ( wheel_diameter_ / 2.0 ) * seconds_since_last_update;
00373 double ssum = sl + sr;
00374
00375 double sdiff;
00376 if(legacy_mode_)
00377 {
00378 sdiff = sl - sr;
00379 }
00380 else
00381 {
00382
00383 sdiff = sr - sl;
00384 }
00385
00386 double dx = ( ssum ) /2.0 * cos ( pose_encoder_.theta + ( sdiff ) / ( 2.0*b ) );
00387 double dy = ( ssum ) /2.0 * sin ( pose_encoder_.theta + ( sdiff ) / ( 2.0*b ) );
00388 double dtheta = ( sdiff ) /b;
00389
00390 pose_encoder_.x += dx;
00391 pose_encoder_.y += dy;
00392 pose_encoder_.theta += dtheta;
00393
00394 double w = dtheta/seconds_since_last_update;
00395 double v = sqrt ( dx*dx+dy*dy ) /seconds_since_last_update;
00396
00397 tf::Quaternion qt;
00398 tf::Vector3 vt;
00399 qt.setRPY ( 0,0,pose_encoder_.theta );
00400 vt = tf::Vector3 ( pose_encoder_.x, pose_encoder_.y, 0 );
00401
00402 odom_.pose.pose.position.x = vt.x();
00403 odom_.pose.pose.position.y = vt.y();
00404 odom_.pose.pose.position.z = vt.z();
00405
00406 odom_.pose.pose.orientation.x = qt.x();
00407 odom_.pose.pose.orientation.y = qt.y();
00408 odom_.pose.pose.orientation.z = qt.z();
00409 odom_.pose.pose.orientation.w = qt.w();
00410
00411 odom_.twist.twist.angular.z = w;
00412 odom_.twist.twist.linear.x = dx/seconds_since_last_update;
00413 odom_.twist.twist.linear.y = dy/seconds_since_last_update;
00414 }
00415
00416 void GazeboRosDiffDrive::publishOdometry ( double step_time )
00417 {
00418
00419 ros::Time current_time = ros::Time::now();
00420 std::string odom_frame = gazebo_ros_->resolveTF ( odometry_frame_ );
00421 std::string base_footprint_frame = gazebo_ros_->resolveTF ( robot_base_frame_ );
00422
00423 tf::Quaternion qt;
00424 tf::Vector3 vt;
00425
00426 if ( odom_source_ == ENCODER ) {
00427
00428 qt = tf::Quaternion ( odom_.pose.pose.orientation.x, odom_.pose.pose.orientation.y, odom_.pose.pose.orientation.z, odom_.pose.pose.orientation.w );
00429 vt = tf::Vector3 ( odom_.pose.pose.position.x, odom_.pose.pose.position.y, odom_.pose.pose.position.z );
00430
00431 }
00432 if ( odom_source_ == WORLD ) {
00433
00434 math::Pose pose = parent->GetWorldPose();
00435 qt = tf::Quaternion ( pose.rot.x, pose.rot.y, pose.rot.z, pose.rot.w );
00436 vt = tf::Vector3 ( pose.pos.x, pose.pos.y, pose.pos.z );
00437
00438 odom_.pose.pose.position.x = vt.x();
00439 odom_.pose.pose.position.y = vt.y();
00440 odom_.pose.pose.position.z = vt.z();
00441
00442 odom_.pose.pose.orientation.x = qt.x();
00443 odom_.pose.pose.orientation.y = qt.y();
00444 odom_.pose.pose.orientation.z = qt.z();
00445 odom_.pose.pose.orientation.w = qt.w();
00446
00447
00448 math::Vector3 linear;
00449 linear = parent->GetWorldLinearVel();
00450 odom_.twist.twist.angular.z = parent->GetWorldAngularVel().z;
00451
00452
00453 float yaw = pose.rot.GetYaw();
00454 odom_.twist.twist.linear.x = cosf ( yaw ) * linear.x + sinf ( yaw ) * linear.y;
00455 odom_.twist.twist.linear.y = cosf ( yaw ) * linear.y - sinf ( yaw ) * linear.x;
00456 }
00457
00458 tf::Transform base_footprint_to_odom ( qt, vt );
00459 transform_broadcaster_->sendTransform (
00460 tf::StampedTransform ( base_footprint_to_odom, current_time,
00461 odom_frame, base_footprint_frame ) );
00462
00463
00464
00465 odom_.pose.covariance[0] = 0.00001;
00466 odom_.pose.covariance[7] = 0.00001;
00467 odom_.pose.covariance[14] = 1000000000000.0;
00468 odom_.pose.covariance[21] = 1000000000000.0;
00469 odom_.pose.covariance[28] = 1000000000000.0;
00470 odom_.pose.covariance[35] = 0.001;
00471
00472
00473
00474 odom_.header.stamp = current_time;
00475 odom_.header.frame_id = odom_frame;
00476 odom_.child_frame_id = base_footprint_frame;
00477
00478 odometry_publisher_.publish ( odom_ );
00479 }
00480
00481 GZ_REGISTER_MODEL_PLUGIN ( GazeboRosDiffDrive )
00482 }
00483