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