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