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
00042 #include <algorithm>
00043 #include <assert.h>
00044
00045 #include <gazebo_plugins/gazebo_ros_tricycle_drive.h>
00046
00047 #include <gazebo/math/gzmath.hh>
00048 #include <sdf/sdf.hh>
00049
00050 #include <ros/ros.h>
00051 #include <tf/transform_broadcaster.h>
00052 #include <tf/transform_listener.h>
00053 #include <geometry_msgs/Twist.h>
00054 #include <nav_msgs/GetMap.h>
00055 #include <nav_msgs/Odometry.h>
00056 #include <boost/bind.hpp>
00057 #include <boost/thread/mutex.hpp>
00058
00059 namespace gazebo
00060 {
00061
00062 enum {
00063 RIGHT,
00064 LEFT,
00065 };
00066
00067 GazeboRosTricycleDrive::GazeboRosTricycleDrive() {}
00068
00069
00070 GazeboRosTricycleDrive::~GazeboRosTricycleDrive() {}
00071
00072
00073 void GazeboRosTricycleDrive::Load ( physics::ModelPtr _parent, sdf::ElementPtr _sdf )
00074 {
00075 parent = _parent;
00076 gazebo_ros_ = GazeboRosPtr ( new GazeboRos ( _parent, _sdf, "TricycleDrive" ) );
00077
00078 gazebo_ros_->isInitialized();
00079
00080 gazebo_ros_->getParameter<double> ( diameter_actuated_wheel_, "actuatedWheelDiameter", 0.15 );
00081 gazebo_ros_->getParameter<double> ( diameter_encoder_wheel_, "encoderWheelDiameter", 0.15 );
00082 gazebo_ros_->getParameter<double> ( wheel_torque_, "wheelTorque", 5.0 );
00083 gazebo_ros_->getParameter<std::string> ( command_topic_, "commandTopic", "cmd_vel" );
00084 gazebo_ros_->getParameter<std::string> ( odometry_topic_, "odometryTopic", "odom" );
00085 gazebo_ros_->getParameter<std::string> ( odometry_frame_, "odometryFrame", "odom" );
00086 gazebo_ros_->getParameter<std::string> ( robot_base_frame_, "robotBaseFrame", "base_link" );
00087
00088 gazebo_ros_->getParameter<double> ( update_rate_, "updateRate", 100.0 );
00089 gazebo_ros_->getParameter<double> ( wheel_acceleration_, "wheelAcceleration", 0 );
00090 gazebo_ros_->getParameter<double> ( wheel_deceleration_, "wheelDeceleration", wheel_acceleration_ );
00091 gazebo_ros_->getParameter<double> ( wheel_speed_tolerance_, "wheelSpeedTolerance", 0.01 );
00092 gazebo_ros_->getParameter<double> ( steering_speed_, "steeringSpeed", 0 );
00093 gazebo_ros_->getParameter<double> ( steering_angle_tolerance_, "steeringAngleTolerance", 0.01 );
00094 gazebo_ros_->getParameter<double> ( separation_encoder_wheel_, "encoderWheelSeparation", 0.5 );
00095
00096 gazebo_ros_->getParameterBoolean ( publishWheelTF_, "publishWheelTF", false );
00097 gazebo_ros_->getParameterBoolean ( publishWheelJointState_, "publishWheelJointState", false );
00098
00099 gazebo_ros_->getParameterBoolean ( publishWheelJointState_, "publishWheelJointState", false );
00100
00101 joint_steering_ = gazebo_ros_->getJoint ( parent, "steeringJoint", "front_steering_joint" );
00102 joint_wheel_actuated_ = gazebo_ros_->getJoint ( parent, "actuatedWheelJoint", "front_wheel_joint" );
00103 joint_wheel_encoder_left_ = gazebo_ros_->getJoint ( parent, "encoderWheelLeftJoint", "left_wheel_joint" );
00104 joint_wheel_encoder_right_ = gazebo_ros_->getJoint ( parent, "encoderWheelRightJoint", "right_wheel_joint" );
00105
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 #if GAZEBO_MAJOR_VERSION > 2
00112 joint_wheel_actuated_->SetParam ( "fmax", 0, wheel_torque_ );
00113 joint_steering_->SetParam ( "fmax", 0, wheel_torque_ );
00114 #else
00115 joint_wheel_actuated_->SetMaxForce ( 0, wheel_torque_ );
00116 joint_steering_->SetMaxForce ( 0, wheel_torque_ );
00117 #endif
00118
00119
00120
00121 if ( this->update_rate_ > 0.0 ) this->update_period_ = 1.0 / this->update_rate_;
00122 else this->update_period_ = 0.0;
00123 last_actuator_update_ = parent->GetWorld()->GetSimTime();
00124
00125
00126 alive_ = true;
00127
00128 if ( this->publishWheelJointState_ ) {
00129 joint_state_publisher_ = gazebo_ros_->node()->advertise<sensor_msgs::JointState> ( "joint_states", 1000 );
00130 ROS_INFO ( "%s: Advertise joint_states!", gazebo_ros_->info() );
00131 }
00132
00133 transform_broadcaster_ = boost::shared_ptr<tf::TransformBroadcaster> ( new tf::TransformBroadcaster() );
00134
00135
00136 ROS_INFO ( "%s: Try to subscribe to %s!", gazebo_ros_->info(), command_topic_.c_str() );
00137
00138 ros::SubscribeOptions so =
00139 ros::SubscribeOptions::create<geometry_msgs::Twist> ( command_topic_, 1,
00140 boost::bind ( &GazeboRosTricycleDrive::cmdVelCallback, this, _1 ),
00141 ros::VoidPtr(), &queue_ );
00142
00143 cmd_vel_subscriber_ = gazebo_ros_->node()->subscribe ( so );
00144 ROS_INFO ( "%s: Subscribe to %s!", gazebo_ros_->info(), command_topic_.c_str() );
00145
00146 odometry_publisher_ = gazebo_ros_->node()->advertise<nav_msgs::Odometry> ( odometry_topic_, 1 );
00147 ROS_INFO ( "%s: Advertise odom on %s !", gazebo_ros_->info(), odometry_topic_.c_str() );
00148
00149
00150 this->callback_queue_thread_ = boost::thread ( boost::bind ( &GazeboRosTricycleDrive::QueueThread, this ) );
00151
00152
00153 this->update_connection_ = event::Events::ConnectWorldUpdateBegin ( boost::bind ( &GazeboRosTricycleDrive::UpdateChild, this ) );
00154
00155 }
00156
00157 void GazeboRosTricycleDrive::publishWheelJointState()
00158 {
00159 std::vector<physics::JointPtr> joints;
00160 joints.push_back ( joint_steering_ );
00161 joints.push_back ( joint_wheel_actuated_ );
00162 joints.push_back ( joint_wheel_encoder_left_ );
00163 joints.push_back ( joint_wheel_encoder_right_ );
00164
00165 ros::Time current_time = ros::Time::now();
00166 joint_state_.header.stamp = current_time;
00167 joint_state_.name.resize ( joints.size() );
00168 joint_state_.position.resize ( joints.size() );
00169 joint_state_.velocity.resize ( joints.size() );
00170 joint_state_.effort.resize ( joints.size() );
00171 for ( std::size_t i = 0; i < joints.size(); i++ ) {
00172 joint_state_.name[i] = joints[i]->GetName();
00173 joint_state_.position[i] = joints[i]->GetAngle ( 0 ).Radian();
00174 joint_state_.velocity[i] = joints[i]->GetVelocity ( 0 );
00175 joint_state_.effort[i] = joints[i]->GetForce ( 0 );
00176 }
00177 joint_state_publisher_.publish ( joint_state_ );
00178 }
00179
00180 void GazeboRosTricycleDrive::publishWheelTF()
00181 {
00182 ros::Time current_time = ros::Time::now();
00183 std::vector<physics::JointPtr> joints;
00184 joints.push_back ( joint_steering_ );
00185 joints.push_back ( joint_wheel_actuated_ );
00186 joints.push_back ( joint_wheel_encoder_left_ );
00187 joints.push_back ( joint_wheel_encoder_right_ );
00188 for ( std::size_t i = 0; i < joints.size(); i++ ) {
00189 std::string frame = gazebo_ros_->resolveTF ( joints[i]->GetName() );
00190 std::string parent_frame = gazebo_ros_->resolveTF ( joints[i]->GetParent()->GetName() );
00191
00192 math::Pose pose = joints[i]->GetChild()->GetRelativePose();
00193
00194 tf::Quaternion qt ( pose.rot.x, pose.rot.y, pose.rot.z, pose.rot.w );
00195 tf::Vector3 vt ( pose.pos.x, pose.pos.y, pose.pos.z );
00196
00197 tf::Transform transform ( qt, vt );
00198 transform_broadcaster_->sendTransform ( tf::StampedTransform ( transform, current_time, parent_frame, frame ) );
00199 }
00200
00201 }
00202
00203 void GazeboRosTricycleDrive::UpdateChild()
00204 {
00205 if ( odom_source_ == ENCODER ) UpdateOdometryEncoder();
00206 common::Time current_time = parent->GetWorld()->GetSimTime();
00207 double seconds_since_last_update = ( current_time - last_actuator_update_ ).Double();
00208 if ( seconds_since_last_update > update_period_ ) {
00209
00210 publishOdometry ( seconds_since_last_update );
00211 if ( publishWheelTF_ ) publishWheelTF();
00212 if ( publishWheelJointState_ ) publishWheelJointState();
00213
00214 double target_wheel_roation_speed = cmd_.speed / ( diameter_actuated_wheel_ / 2.0 );
00215 double target_steering_angle = cmd_.angle;
00216
00217 motorController ( target_wheel_roation_speed, target_steering_angle, seconds_since_last_update );
00218
00219
00220
00221 last_actuator_update_ += common::Time ( update_period_ );
00222 }
00223 }
00224
00225
00226 void GazeboRosTricycleDrive::motorController ( double target_speed, double target_angle, double dt )
00227 {
00228 double applied_speed = target_speed;
00229 double applied_angle = target_angle;
00230 double applied_steering_speed = 0;
00231
00232 double current_speed = joint_wheel_actuated_->GetVelocity ( 0 );
00233 if ( wheel_acceleration_ > 0 ) {
00234 double diff_speed = current_speed - target_speed;
00235 if ( fabs ( diff_speed ) < wheel_speed_tolerance_ ) {
00236 applied_speed = target_speed;
00237 } else if ( diff_speed < target_speed ) {
00238 applied_speed = current_speed + wheel_acceleration_ * dt;
00239 } else {
00240 applied_speed = current_speed - wheel_deceleration_ * dt;
00241 }
00242 }
00243 #if GAZEBO_MAJOR_VERSION > 2
00244 joint_wheel_actuated_->SetParam ( "vel", 0, applied_speed );
00245 #else
00246 joint_wheel_actuated_->SetVelocity ( 0, applied_speed );
00247 #endif
00248
00249 double current_angle = joint_steering_->GetAngle ( 0 ).Radian();
00250 if(target_angle > +M_PI / 2.0) target_angle = +M_PI / 2.0;
00251 if(target_angle < -M_PI / 2.0) target_angle = -M_PI / 2.0;
00252 if ( steering_speed_ > 0 ) {
00253 double diff_angle = current_angle - target_angle;
00254 if ( fabs ( diff_angle ) < steering_angle_tolerance_ ) {
00255 applied_steering_speed = 0;
00256 } else if ( diff_angle < target_speed ) {
00257 applied_steering_speed = steering_speed_;
00258 } else {
00259 applied_steering_speed = -steering_speed_;
00260 }
00261 #if GAZEBO_MAJOR_VERSION > 2
00262 joint_steering_->SetParam ( "vel", 0, applied_steering_speed );
00263 #else
00264 joint_steering_->SetVelocity ( 0, applied_steering_speed );
00265 #endif
00266 }else {
00267 #if GAZEBO_MAJOR_VERSION >= 4
00268 joint_steering_->SetPosition ( 0, applied_angle );
00269 #else
00270 joint_steering_->SetAngle ( 0, math::Angle ( applied_angle ) );
00271 #endif
00272 }
00273
00274
00275
00276 }
00277
00278
00279 void GazeboRosTricycleDrive::FiniChild()
00280 {
00281 alive_ = false;
00282 queue_.clear();
00283 queue_.disable();
00284 gazebo_ros_->node()->shutdown();
00285 callback_queue_thread_.join();
00286 }
00287
00288 void GazeboRosTricycleDrive::cmdVelCallback ( const geometry_msgs::Twist::ConstPtr& cmd_msg )
00289 {
00290 boost::mutex::scoped_lock scoped_lock ( lock );
00291 cmd_.speed = cmd_msg->linear.x;
00292 cmd_.angle = cmd_msg->angular.z;
00293 }
00294
00295 void GazeboRosTricycleDrive::QueueThread()
00296 {
00297 static const double timeout = 0.01;
00298
00299 while ( alive_ && gazebo_ros_->node()->ok() ) {
00300 queue_.callAvailable ( ros::WallDuration ( timeout ) );
00301 }
00302 }
00303
00304 void GazeboRosTricycleDrive::UpdateOdometryEncoder()
00305 {
00306 double vl = joint_wheel_encoder_left_->GetVelocity ( 0 );
00307 double vr = joint_wheel_encoder_right_->GetVelocity ( 0 );
00308 common::Time current_time = parent->GetWorld()->GetSimTime();
00309 double seconds_since_last_update = ( current_time - last_odom_update_ ).Double();
00310 last_odom_update_ = current_time;
00311
00312 double b = separation_encoder_wheel_;
00313
00314
00315 double sl = vl * ( diameter_encoder_wheel_ / 2.0 ) * seconds_since_last_update;
00316 double sr = vr * ( diameter_encoder_wheel_ / 2.0 ) * seconds_since_last_update;
00317 double theta = ( sl - sr ) /b;
00318
00319
00320 double dx = ( sl + sr ) /2.0 * cos ( pose_encoder_.theta + ( sl - sr ) / ( 2.0*b ) );
00321 double dy = ( sl + sr ) /2.0 * sin ( pose_encoder_.theta + ( sl - sr ) / ( 2.0*b ) );
00322 double dtheta = ( sl - sr ) /b;
00323
00324 pose_encoder_.x += dx;
00325 pose_encoder_.y += dy;
00326 pose_encoder_.theta += dtheta;
00327
00328 double w = dtheta/seconds_since_last_update;
00329 double v = sqrt ( dx*dx+dy*dy ) /seconds_since_last_update;
00330
00331 tf::Quaternion qt;
00332 tf::Vector3 vt;
00333 qt.setRPY ( 0,0,pose_encoder_.theta );
00334 vt = tf::Vector3 ( pose_encoder_.x, pose_encoder_.y, 0 );
00335
00336 odom_.pose.pose.position.x = vt.x();
00337 odom_.pose.pose.position.y = vt.y();
00338 odom_.pose.pose.position.z = vt.z();
00339
00340 odom_.pose.pose.orientation.x = qt.x();
00341 odom_.pose.pose.orientation.y = qt.y();
00342 odom_.pose.pose.orientation.z = qt.z();
00343 odom_.pose.pose.orientation.w = qt.w();
00344
00345 odom_.twist.twist.angular.z = w;
00346 odom_.twist.twist.linear.x = dx/seconds_since_last_update;
00347 odom_.twist.twist.linear.y = dy/seconds_since_last_update;
00348 }
00349
00350 void GazeboRosTricycleDrive::publishOdometry ( double step_time )
00351 {
00352
00353 ros::Time current_time = ros::Time::now();
00354 std::string odom_frame = gazebo_ros_->resolveTF ( odometry_frame_ );
00355 std::string base_footprint_frame = gazebo_ros_->resolveTF ( robot_base_frame_ );
00356
00357 tf::Quaternion qt;
00358 tf::Vector3 vt;
00359
00360 if ( odom_source_ == ENCODER ) {
00361
00362 qt = tf::Quaternion ( odom_.pose.pose.orientation.x, odom_.pose.pose.orientation.y, odom_.pose.pose.orientation.z, odom_.pose.pose.orientation.w );
00363 vt = tf::Vector3 ( odom_.pose.pose.position.x, odom_.pose.pose.position.y, odom_.pose.pose.position.z );
00364
00365 }
00366 if ( odom_source_ == WORLD ) {
00367
00368 math::Pose pose = parent->GetWorldPose();
00369 qt = tf::Quaternion ( pose.rot.x, pose.rot.y, pose.rot.z, pose.rot.w );
00370 vt = tf::Vector3 ( pose.pos.x, pose.pos.y, pose.pos.z );
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
00382 math::Vector3 linear;
00383 linear = parent->GetWorldLinearVel();
00384 odom_.twist.twist.angular.z = parent->GetWorldAngularVel().z;
00385
00386
00387 float yaw = pose.rot.GetYaw();
00388 odom_.twist.twist.linear.x = cosf ( yaw ) * linear.x + sinf ( yaw ) * linear.y;
00389 odom_.twist.twist.linear.y = cosf ( yaw ) * linear.y - sinf ( yaw ) * linear.x;
00390 }
00391
00392 tf::Transform base_footprint_to_odom ( qt, vt );
00393 transform_broadcaster_->sendTransform (
00394 tf::StampedTransform ( base_footprint_to_odom, current_time,
00395 odom_frame, base_footprint_frame ) );
00396
00397
00398
00399 odom_.pose.covariance[0] = 0.00001;
00400 odom_.pose.covariance[7] = 0.00001;
00401 odom_.pose.covariance[14] = 1000000000000.0;
00402 odom_.pose.covariance[21] = 1000000000000.0;
00403 odom_.pose.covariance[28] = 1000000000000.0;
00404 odom_.pose.covariance[35] = 0.001;
00405
00406
00407
00408 odom_.header.stamp = current_time;
00409 odom_.header.frame_id = odom_frame;
00410 odom_.child_frame_id = base_footprint_frame;
00411
00412 odometry_publisher_.publish ( odom_ );
00413 }
00414
00415 GZ_REGISTER_MODEL_PLUGIN ( GazeboRosTricycleDrive )
00416 }
00417