gazebo_ros_tricycle_drive.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, Markus Bader <markus.bader@tuwien.ac.at>
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder nor the names of its
00018  *     contributors may be used to endorse or promote products derived from
00019  *     this software without specific prior written permission.
00020  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031  *  POSSIBILITY OF SUCH DAMAGE.
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 // Destructor
00070 GazeboRosTricycleDrive::~GazeboRosTricycleDrive() {}
00071 
00072 // Load the controller
00073 void GazeboRosTricycleDrive::Load ( physics::ModelPtr _parent, sdf::ElementPtr _sdf )
00074 {
00075     parent = _parent;
00076     gazebo_ros_ = GazeboRosPtr ( new GazeboRos ( _parent, _sdf, "TricycleDrive" ) );
00077     // Make sure the ROS node for Gazebo has already been initialized
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     joint_wheel_actuated_->SetMaxForce ( 0, wheel_torque_ );
00112     joint_steering_->SetMaxForce ( 0, wheel_torque_ );
00113 
00114 
00115     // Initialize update rate stuff
00116     if ( this->update_rate_ > 0.0 ) this->update_period_ = 1.0 / this->update_rate_;
00117     else this->update_period_ = 0.0;
00118     last_actuator_update_ = parent->GetWorld()->GetSimTime();
00119 
00120     // Initialize velocity stuff
00121     alive_ = true;
00122 
00123     if ( this->publishWheelJointState_ ) {
00124         joint_state_publisher_ = gazebo_ros_->node()->advertise<sensor_msgs::JointState> ( "joint_states", 1000 );
00125         ROS_INFO ( "%s: Advertise joint_states!", gazebo_ros_->info() );
00126     }
00127 
00128     transform_broadcaster_ = boost::shared_ptr<tf::TransformBroadcaster> ( new tf::TransformBroadcaster() );
00129 
00130     // ROS: Subscribe to the velocity command topic (usually "cmd_vel")
00131     ROS_INFO ( "%s: Try to subscribe to %s!", gazebo_ros_->info(), command_topic_.c_str() );
00132 
00133     ros::SubscribeOptions so =
00134         ros::SubscribeOptions::create<geometry_msgs::Twist> ( command_topic_, 1,
00135                 boost::bind ( &GazeboRosTricycleDrive::cmdVelCallback, this, _1 ),
00136                 ros::VoidPtr(), &queue_ );
00137 
00138     cmd_vel_subscriber_ = gazebo_ros_->node()->subscribe ( so );
00139     ROS_INFO ( "%s: Subscribe to %s!", gazebo_ros_->info(), command_topic_.c_str() );
00140 
00141     odometry_publisher_ = gazebo_ros_->node()->advertise<nav_msgs::Odometry> ( odometry_topic_, 1 );
00142     ROS_INFO ( "%s: Advertise odom on %s !", gazebo_ros_->info(), odometry_topic_.c_str() );
00143 
00144     // start custom queue for diff drive
00145     this->callback_queue_thread_ = boost::thread ( boost::bind ( &GazeboRosTricycleDrive::QueueThread, this ) );
00146 
00147     // listen to the update event (broadcast every simulation iteration)
00148     this->update_connection_ = event::Events::ConnectWorldUpdateBegin ( boost::bind ( &GazeboRosTricycleDrive::UpdateChild, this ) );
00149 
00150 }
00151 
00152 void GazeboRosTricycleDrive::publishWheelJointState()
00153 {
00154     std::vector<physics::JointPtr> joints;
00155     joints.push_back ( joint_steering_ );
00156     joints.push_back ( joint_wheel_actuated_ );
00157     joints.push_back ( joint_wheel_encoder_left_ );
00158     joints.push_back ( joint_wheel_encoder_right_ );
00159 
00160     ros::Time current_time = ros::Time::now();
00161     joint_state_.header.stamp = current_time;
00162     joint_state_.name.resize ( joints.size() );
00163     joint_state_.position.resize ( joints.size() );
00164     joint_state_.velocity.resize ( joints.size() );
00165     joint_state_.effort.resize ( joints.size() );
00166     for ( std::size_t i = 0; i < joints.size(); i++ ) {
00167         joint_state_.name[i] = joints[i]->GetName();
00168         joint_state_.position[i] = joints[i]->GetAngle ( 0 ).Radian();
00169         joint_state_.velocity[i] = joints[i]->GetVelocity ( 0 );
00170         joint_state_.effort[i] = joints[i]->GetForce ( 0 );
00171     }
00172     joint_state_publisher_.publish ( joint_state_ );
00173 }
00174 
00175 void GazeboRosTricycleDrive::publishWheelTF()
00176 {
00177     ros::Time current_time = ros::Time::now();
00178     std::vector<physics::JointPtr> joints;
00179     joints.push_back ( joint_steering_ );
00180     joints.push_back ( joint_wheel_actuated_ );
00181     joints.push_back ( joint_wheel_encoder_left_ );
00182     joints.push_back ( joint_wheel_encoder_right_ );
00183     for ( std::size_t i = 0; i < joints.size(); i++ ) {
00184         std::string frame = gazebo_ros_->resolveTF ( joints[i]->GetName() );
00185         std::string parent_frame = gazebo_ros_->resolveTF ( joints[i]->GetParent()->GetName() );
00186 
00187         math::Pose pose = joints[i]->GetChild()->GetRelativePose();
00188 
00189         tf::Quaternion qt ( pose.rot.x, pose.rot.y, pose.rot.z, pose.rot.w );
00190         tf::Vector3 vt ( pose.pos.x, pose.pos.y, pose.pos.z );
00191 
00192         tf::Transform transform ( qt, vt );
00193         transform_broadcaster_->sendTransform ( tf::StampedTransform ( transform, current_time, parent_frame, frame ) );
00194     }
00195 
00196 }
00197 // Update the controller
00198 void GazeboRosTricycleDrive::UpdateChild()
00199 {
00200     if ( odom_source_ == ENCODER ) UpdateOdometryEncoder();
00201     common::Time current_time = parent->GetWorld()->GetSimTime();
00202     double seconds_since_last_update = ( current_time - last_actuator_update_ ).Double();
00203     if ( seconds_since_last_update > update_period_ ) {
00204 
00205         publishOdometry ( seconds_since_last_update );
00206         if ( publishWheelTF_ ) publishWheelTF();
00207         if ( publishWheelJointState_ ) publishWheelJointState();
00208 
00209         double target_wheel_roation_speed = cmd_.speed / ( diameter_actuated_wheel_ / 2.0 );
00210         double target_steering_angle = cmd_.angle;
00211 
00212         motorController ( target_wheel_roation_speed, target_steering_angle, seconds_since_last_update );
00213 
00214         //ROS_INFO("v = %f, w = %f !", target_wheel_roation_speed, target_steering_angle);
00215 
00216         last_actuator_update_ += common::Time ( update_period_ );
00217     }
00218 }
00219 
00220 
00221 void GazeboRosTricycleDrive::motorController ( double target_speed, double target_angle, double dt )
00222 {
00223     double applied_speed = target_speed;
00224     double applied_angle = target_angle;
00225     double applied_steering_speed = 0;
00226 
00227     double current_speed = joint_wheel_actuated_->GetVelocity ( 0 );
00228     if ( wheel_acceleration_ > 0 ) {
00229         double diff_speed = current_speed - target_speed;
00230         if ( fabs ( diff_speed ) < wheel_speed_tolerance_ ) {
00231             applied_speed = target_speed;
00232         } else if ( diff_speed < target_speed ) {
00233             applied_speed = current_speed + wheel_acceleration_ * dt;
00234         } else {
00235             applied_speed = current_speed - wheel_deceleration_ * dt;
00236         }
00237     }
00238     joint_wheel_actuated_->SetVelocity ( 0, applied_speed );
00239     
00240     double current_angle = joint_steering_->GetAngle ( 0 ).Radian();
00241     if(target_angle > +M_PI / 2.0) target_angle =  +M_PI / 2.0;
00242     if(target_angle < -M_PI / 2.0) target_angle =  -M_PI / 2.0;
00243     if ( steering_speed_ > 0 ) {
00244         double diff_angle = current_angle - target_angle;
00245         if ( fabs ( diff_angle ) < steering_angle_tolerance_ ) {
00246           applied_steering_speed = 0;
00247         } else if ( diff_angle < target_speed ) {
00248             applied_steering_speed = steering_speed_;
00249         } else {
00250             applied_steering_speed = -steering_speed_;
00251         }
00252       joint_steering_->SetVelocity ( 0, applied_steering_speed );
00253     }else {
00254 #if GAZEBO_MAJOR_VERSION >= 4
00255       joint_steering_->SetPosition ( 0, applied_angle );
00256 #else
00257       joint_steering_->SetAngle ( 0, math::Angle ( applied_angle ) );
00258 #endif
00259     }
00260     //ROS_INFO ( "target: [%3.2f, %3.2f], current: [%3.2f, %3.2f], applied: [%3.2f, %3.2f/%3.2f] !", 
00261     //            target_speed, target_angle, current_speed, current_angle, applied_speed, applied_angle, applied_steering_speed );
00262 
00263 }
00264 
00265 // Finalize the controller
00266 void GazeboRosTricycleDrive::FiniChild()
00267 {
00268     alive_ = false;
00269     queue_.clear();
00270     queue_.disable();
00271     gazebo_ros_->node()->shutdown();
00272     callback_queue_thread_.join();
00273 }
00274 
00275 void GazeboRosTricycleDrive::cmdVelCallback ( const geometry_msgs::Twist::ConstPtr& cmd_msg )
00276 {
00277     boost::mutex::scoped_lock scoped_lock ( lock );
00278     cmd_.speed = cmd_msg->linear.x;
00279     cmd_.angle = cmd_msg->angular.z;
00280 }
00281 
00282 void GazeboRosTricycleDrive::QueueThread()
00283 {
00284     static const double timeout = 0.01;
00285 
00286     while ( alive_ && gazebo_ros_->node()->ok() ) {
00287         queue_.callAvailable ( ros::WallDuration ( timeout ) );
00288     }
00289 }
00290 
00291 void GazeboRosTricycleDrive::UpdateOdometryEncoder()
00292 {
00293     double vl = joint_wheel_encoder_left_->GetVelocity ( 0 );
00294     double vr = joint_wheel_encoder_right_->GetVelocity ( 0 );
00295     common::Time current_time = parent->GetWorld()->GetSimTime();
00296     double seconds_since_last_update = ( current_time - last_odom_update_ ).Double();
00297     last_odom_update_ = current_time;
00298 
00299     double b = separation_encoder_wheel_;
00300 
00301     // Book: Sigwart 2011 Autonompus Mobile Robots page:337
00302     double sl = vl * ( diameter_encoder_wheel_ / 2.0 ) * seconds_since_last_update;
00303     double sr = vr * ( diameter_encoder_wheel_ / 2.0 ) * seconds_since_last_update;
00304     double theta = ( sl - sr ) /b;
00305 
00306 
00307     double dx = ( sl + sr ) /2.0 * cos ( pose_encoder_.theta + ( sl - sr ) / ( 2.0*b ) );
00308     double dy = ( sl + sr ) /2.0 * sin ( pose_encoder_.theta + ( sl - sr ) / ( 2.0*b ) );
00309     double dtheta = ( sl - sr ) /b;
00310 
00311     pose_encoder_.x += dx;
00312     pose_encoder_.y += dy;
00313     pose_encoder_.theta += dtheta;
00314 
00315     double w = dtheta/seconds_since_last_update;
00316     double v = sqrt ( dx*dx+dy*dy ) /seconds_since_last_update;
00317 
00318     tf::Quaternion qt;
00319     tf::Vector3 vt;
00320     qt.setRPY ( 0,0,pose_encoder_.theta );
00321     vt = tf::Vector3 ( pose_encoder_.x, pose_encoder_.y, 0 );
00322 
00323     odom_.pose.pose.position.x = vt.x();
00324     odom_.pose.pose.position.y = vt.y();
00325     odom_.pose.pose.position.z = vt.z();
00326 
00327     odom_.pose.pose.orientation.x = qt.x();
00328     odom_.pose.pose.orientation.y = qt.y();
00329     odom_.pose.pose.orientation.z = qt.z();
00330     odom_.pose.pose.orientation.w = qt.w();
00331 
00332     odom_.twist.twist.angular.z = w;
00333     odom_.twist.twist.linear.x = dx/seconds_since_last_update;
00334     odom_.twist.twist.linear.y = dy/seconds_since_last_update;
00335 }
00336 
00337 void GazeboRosTricycleDrive::publishOdometry ( double step_time )
00338 {
00339 
00340     ros::Time current_time = ros::Time::now();
00341     std::string odom_frame = gazebo_ros_->resolveTF ( odometry_frame_ );
00342     std::string base_footprint_frame = gazebo_ros_->resolveTF ( robot_base_frame_ );
00343 
00344     tf::Quaternion qt;
00345     tf::Vector3 vt;
00346 
00347     if ( odom_source_ == ENCODER ) {
00348         // getting data form encoder integration
00349         qt = tf::Quaternion ( odom_.pose.pose.orientation.x, odom_.pose.pose.orientation.y, odom_.pose.pose.orientation.z, odom_.pose.pose.orientation.w );
00350         vt = tf::Vector3 ( odom_.pose.pose.position.x, odom_.pose.pose.position.y, odom_.pose.pose.position.z );
00351 
00352     }
00353     if ( odom_source_ == WORLD ) {
00354         // getting data form gazebo world
00355         math::Pose pose = parent->GetWorldPose();
00356         qt = tf::Quaternion ( pose.rot.x, pose.rot.y, pose.rot.z, pose.rot.w );
00357         vt = tf::Vector3 ( pose.pos.x, pose.pos.y, pose.pos.z );
00358 
00359         odom_.pose.pose.position.x = vt.x();
00360         odom_.pose.pose.position.y = vt.y();
00361         odom_.pose.pose.position.z = vt.z();
00362 
00363         odom_.pose.pose.orientation.x = qt.x();
00364         odom_.pose.pose.orientation.y = qt.y();
00365         odom_.pose.pose.orientation.z = qt.z();
00366         odom_.pose.pose.orientation.w = qt.w();
00367 
00368         // get velocity in /odom frame
00369         math::Vector3 linear;
00370         linear = parent->GetWorldLinearVel();
00371         odom_.twist.twist.angular.z = parent->GetWorldAngularVel().z;
00372 
00373         // convert velocity to child_frame_id (aka base_footprint)
00374         float yaw = pose.rot.GetYaw();
00375         odom_.twist.twist.linear.x = cosf ( yaw ) * linear.x + sinf ( yaw ) * linear.y;
00376         odom_.twist.twist.linear.y = cosf ( yaw ) * linear.y - sinf ( yaw ) * linear.x;
00377     }
00378 
00379     tf::Transform base_footprint_to_odom ( qt, vt );
00380     transform_broadcaster_->sendTransform (
00381         tf::StampedTransform ( base_footprint_to_odom, current_time,
00382                                odom_frame, base_footprint_frame ) );
00383 
00384 
00385     // set covariance
00386     odom_.pose.covariance[0] = 0.00001;
00387     odom_.pose.covariance[7] = 0.00001;
00388     odom_.pose.covariance[14] = 1000000000000.0;
00389     odom_.pose.covariance[21] = 1000000000000.0;
00390     odom_.pose.covariance[28] = 1000000000000.0;
00391     odom_.pose.covariance[35] = 0.001;
00392 
00393 
00394     // set header
00395     odom_.header.stamp = current_time;
00396     odom_.header.frame_id = odom_frame;
00397     odom_.child_frame_id = base_footprint_frame;
00398 
00399     odometry_publisher_.publish ( odom_ );
00400 }
00401 
00402 GZ_REGISTER_MODEL_PLUGIN ( GazeboRosTricycleDrive )
00403 }
00404 


gazebo_plugins
Author(s): John Hsu
autogenerated on Fri Aug 28 2015 10:47:25