diff_drive_controller.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, PAL Robotics, S.L.
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 PAL Robotics nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /*
00036  * Author: Bence Magyar
00037  */
00038 
00039 #include <tf/transform_datatypes.h>
00040 
00041 #include <urdf_parser/urdf_parser.h>
00042 
00043 #include <boost/assign.hpp>
00044 
00045 #include <diff_drive_controller/diff_drive_controller.h>
00046 
00047 static double euclideanOfVectors(const urdf::Vector3& vec1, const urdf::Vector3& vec2)
00048 {
00049   return std::sqrt(std::pow(vec1.x-vec2.x,2) +
00050                    std::pow(vec1.y-vec2.y,2) +
00051                    std::pow(vec1.z-vec2.z,2));
00052 }
00053 
00054 /*
00055  * \brief Check if the link is modeled as a cylinder
00056  * \param link Link
00057  * \return true if the link is modeled as a Cylinder; false otherwise
00058  */
00059 static bool isCylinder(const boost::shared_ptr<const urdf::Link>& link)
00060 {
00061   if(!link)
00062   {
00063     ROS_ERROR("Link == NULL.");
00064     return false;
00065   }
00066 
00067   if(!link->collision)
00068   {
00069     ROS_ERROR_STREAM("Link " << link->name << " does not have collision description. Add collision description for link to urdf.");
00070     return false;
00071   }
00072 
00073   if(!link->collision->geometry)
00074   {
00075     ROS_ERROR_STREAM("Link " << link->name << " does not have collision geometry description. Add collision geometry description for link to urdf.");
00076     return false;
00077   }
00078 
00079   if(link->collision->geometry->type != urdf::Geometry::CYLINDER)
00080   {
00081     ROS_ERROR_STREAM("Link " << link->name << " does not have cylinder geometry");
00082     return false;
00083   }
00084 
00085   return true;
00086 }
00087 
00088 /*
00089  * \brief Get the wheel radius
00090  * \param [in]  wheel_link   Wheel link
00091  * \param [out] wheel_radius Wheel radius [m]
00092  * \return true if the wheel radius was found; false otherwise
00093  */
00094 static bool getWheelRadius(const boost::shared_ptr<const urdf::Link>& wheel_link, double& wheel_radius)
00095 {
00096   if(!isCylinder(wheel_link))
00097   {
00098     ROS_ERROR_STREAM("Wheel link " << wheel_link->name << " is NOT modeled as a cylinder!");
00099     return false;
00100   }
00101 
00102   wheel_radius = (static_cast<urdf::Cylinder*>(wheel_link->collision->geometry.get()))->radius;
00103   return true;
00104 }
00105 
00106 namespace diff_drive_controller{
00107 
00108   DiffDriveController::DiffDriveController()
00109     : command_struct_()
00110     , wheel_separation_(0.0)
00111     , wheel_radius_(0.0)
00112     , wheel_separation_multiplier_(1.0)
00113     , wheel_radius_multiplier_(1.0)
00114     , cmd_vel_timeout_(0.5)
00115     , base_frame_id_("base_link")
00116   {
00117   }
00118 
00119   bool DiffDriveController::init(hardware_interface::VelocityJointInterface* hw,
00120             ros::NodeHandle& root_nh,
00121             ros::NodeHandle &controller_nh)
00122   {
00123     const std::string complete_ns = controller_nh.getNamespace();
00124     std::size_t id = complete_ns.find_last_of("/");
00125     name_ = complete_ns.substr(id + 1);
00126     // Get joint names from the parameter server
00127     std::string left_wheel_name, right_wheel_name;
00128 
00129     bool res = controller_nh.hasParam("left_wheel");
00130     if(!res || !controller_nh.getParam("left_wheel", left_wheel_name))
00131     {
00132       ROS_ERROR_NAMED(name_, "Couldn't retrieve left wheel name from param server.");
00133       return false;
00134     }
00135     res = controller_nh.hasParam("right_wheel");
00136     if(!res || !controller_nh.getParam("right_wheel", right_wheel_name))
00137     {
00138       ROS_ERROR_NAMED(name_, "Couldn't retrieve right wheel name from param server.");
00139       return false;
00140     }
00141 
00142     double publish_rate;
00143     controller_nh.param("publish_rate", publish_rate, 50.0);
00144     ROS_INFO_STREAM_NAMED(name_, "Controller state will be published at "
00145                           << publish_rate << "Hz.");
00146     publish_period_ = ros::Duration(1.0 / publish_rate);
00147 
00148     controller_nh.param("wheel_separation_multiplier", wheel_separation_multiplier_, wheel_separation_multiplier_);
00149     ROS_INFO_STREAM_NAMED(name_, "Wheel separation will be multiplied by "
00150                           << wheel_separation_multiplier_ << ".");
00151 
00152     controller_nh.param("wheel_radius_multiplier", wheel_radius_multiplier_, wheel_radius_multiplier_);
00153     ROS_INFO_STREAM_NAMED(name_, "Wheel radius will be multiplied by "
00154                           << wheel_radius_multiplier_ << ".");
00155 
00156     controller_nh.param("cmd_vel_timeout", cmd_vel_timeout_, cmd_vel_timeout_);
00157     ROS_INFO_STREAM_NAMED(name_, "Velocity commands will be considered old if they are older than "
00158                           << cmd_vel_timeout_ << "s.");
00159 
00160     controller_nh.param("base_frame_id", base_frame_id_, base_frame_id_);
00161     ROS_INFO_STREAM_NAMED(name_, "Base frame_id set to " << base_frame_id_);
00162 
00163     // Velocity and acceleration limits:
00164     controller_nh.param("linear/x/has_velocity_limits"    , limiter_lin_.has_velocity_limits    , limiter_lin_.has_velocity_limits    );
00165     controller_nh.param("linear/x/has_acceleration_limits", limiter_lin_.has_acceleration_limits, limiter_lin_.has_acceleration_limits);
00166     controller_nh.param("linear/x/max_velocity"           , limiter_lin_.max_velocity           ,  limiter_lin_.max_velocity          );
00167     controller_nh.param("linear/x/min_velocity"           , limiter_lin_.min_velocity           , -limiter_lin_.max_velocity          );
00168     controller_nh.param("linear/x/max_acceleration"       , limiter_lin_.max_acceleration       ,  limiter_lin_.max_acceleration      );
00169     controller_nh.param("linear/x/min_acceleration"       , limiter_lin_.min_acceleration       , -limiter_lin_.max_acceleration      );
00170 
00171     controller_nh.param("angular/z/has_velocity_limits"    , limiter_ang_.has_velocity_limits    , limiter_ang_.has_velocity_limits    );
00172     controller_nh.param("angular/z/has_acceleration_limits", limiter_ang_.has_acceleration_limits, limiter_ang_.has_acceleration_limits);
00173     controller_nh.param("angular/z/max_velocity"           , limiter_ang_.max_velocity           ,  limiter_ang_.max_velocity          );
00174     controller_nh.param("angular/z/min_velocity"           , limiter_ang_.min_velocity           , -limiter_ang_.max_velocity          );
00175     controller_nh.param("angular/z/max_acceleration"       , limiter_ang_.max_acceleration       ,  limiter_ang_.max_acceleration      );
00176     controller_nh.param("angular/z/min_acceleration"       , limiter_ang_.min_acceleration       , -limiter_ang_.max_acceleration      );
00177 
00178     if(!setOdomParamsFromUrdf(root_nh, left_wheel_name, right_wheel_name))
00179       return false;
00180 
00181     setOdomPubFields(root_nh, controller_nh);
00182 
00183     // Get the joint object to use in the realtime loop
00184     ROS_INFO_STREAM_NAMED(name_,
00185                           "Adding left wheel with joint name: " << left_wheel_name
00186                           << " and right wheel with joint name: " << right_wheel_name);
00187     left_wheel_joint_ = hw->getHandle(left_wheel_name);  // throws on failure
00188     right_wheel_joint_ = hw->getHandle(right_wheel_name);  // throws on failure
00189 
00190     sub_command_ = controller_nh.subscribe("cmd_vel", 1, &DiffDriveController::cmdVelCallback, this);
00191 
00192     return true;
00193   }
00194 
00195   void DiffDriveController::update(const ros::Time& time, const ros::Duration& period)
00196   {
00197     // COMPUTE AND PUBLISH ODOMETRY
00198     // Estimate linear and angular velocity using joint information
00199     odometry_.update(left_wheel_joint_.getPosition(), right_wheel_joint_.getPosition(), time);
00200 
00201     // Publish odometry message
00202     if(last_state_publish_time_ + publish_period_ < time)
00203     {
00204       last_state_publish_time_ += publish_period_;
00205       // Compute and store orientation info
00206       const geometry_msgs::Quaternion orientation(
00207             tf::createQuaternionMsgFromYaw(odometry_.getHeading()));
00208 
00209       // Populate odom message and publish
00210       if(odom_pub_->trylock())
00211       {
00212         odom_pub_->msg_.header.stamp = time;
00213         odom_pub_->msg_.pose.pose.position.x = odometry_.getX();
00214         odom_pub_->msg_.pose.pose.position.y = odometry_.getY();
00215         odom_pub_->msg_.pose.pose.orientation = orientation;
00216         odom_pub_->msg_.twist.twist.linear.x  = odometry_.getLinearEstimated();
00217         odom_pub_->msg_.twist.twist.angular.z = odometry_.getAngularEstimated();
00218         odom_pub_->unlockAndPublish();
00219       }
00220 
00221       // Publish tf /odom frame
00222       if(tf_odom_pub_->trylock())
00223       {
00224         odom_frame_.header.stamp = time;
00225         odom_frame_.transform.translation.x = odometry_.getX();
00226         odom_frame_.transform.translation.y = odometry_.getY();
00227         odom_frame_.transform.rotation = orientation;
00228         tf_odom_pub_->msg_.transforms[0] = odom_frame_;
00229         tf_odom_pub_->unlockAndPublish();
00230       }
00231     }
00232 
00233     // MOVE ROBOT
00234     // Retreive current velocity command and time step:
00235     Commands curr_cmd = *(command_.readFromRT());
00236     const double dt = (time - curr_cmd.stamp).toSec();
00237 
00238     // Brake if cmd_vel has timeout:
00239     if (dt > cmd_vel_timeout_)
00240     {
00241       curr_cmd.lin = 0.0;
00242       curr_cmd.ang = 0.0;
00243     }
00244 
00245     // Limit velocities and accelerations:
00246     double cmd_dt = period.toSec();
00247     limiter_lin_.limit(curr_cmd.lin, last_cmd_.lin, cmd_dt);
00248     limiter_ang_.limit(curr_cmd.ang, last_cmd_.ang, cmd_dt);
00249     last_cmd_ = curr_cmd;
00250 
00251     // Apply multipliers:
00252     const double ws = wheel_separation_multiplier_ * wheel_separation_;
00253     const double wr = wheel_radius_multiplier_     * wheel_radius_;
00254 
00255     // Compute wheels velocities:
00256     const double vel_left  = (curr_cmd.lin - curr_cmd.ang * ws / 2.0)/wr;
00257     const double vel_right = (curr_cmd.lin + curr_cmd.ang * ws / 2.0)/wr;
00258 
00259     // Set wheels velocities:
00260     left_wheel_joint_.setCommand(vel_left);
00261     right_wheel_joint_.setCommand(vel_right);
00262   }
00263 
00264   void DiffDriveController::starting(const ros::Time& time)
00265   {
00266     brake();
00267 
00268     // Register starting time used to keep fixed rate
00269     last_state_publish_time_ = time;
00270   }
00271 
00272   void DiffDriveController::stopping(const ros::Time& time)
00273   {
00274     brake();
00275   }
00276 
00277   void DiffDriveController::brake()
00278   {
00279     const double vel = 0.0;
00280     left_wheel_joint_.setCommand(vel);
00281     right_wheel_joint_.setCommand(vel);
00282   }
00283 
00284   void DiffDriveController::cmdVelCallback(const geometry_msgs::Twist& command)
00285   {
00286     if(isRunning())
00287     {
00288       command_struct_.ang   = command.angular.z;
00289       command_struct_.lin   = command.linear.x;
00290       command_struct_.stamp = ros::Time::now();
00291       command_.writeFromNonRT (command_struct_);
00292       ROS_DEBUG_STREAM_NAMED(name_,
00293                              "Added values to command. "
00294                              << "Ang: "   << command_struct_.ang << ", "
00295                              << "Lin: "   << command_struct_.lin << ", "
00296                              << "Stamp: " << command_struct_.stamp);
00297     }
00298     else
00299     {
00300       ROS_ERROR_NAMED(name_, "Can't accept new commands. Controller is not running.");
00301     }
00302   }
00303 
00304   bool DiffDriveController::setOdomParamsFromUrdf(ros::NodeHandle& root_nh,
00305                              const std::string& left_wheel_name,
00306                              const std::string& right_wheel_name)
00307   {
00308     // Parse robot description
00309     const std::string model_param_name = "robot_description";
00310     bool res = root_nh.hasParam(model_param_name);
00311     std::string robot_model_str="";
00312     if(!res || !root_nh.getParam(model_param_name,robot_model_str))
00313     {
00314       ROS_ERROR_NAMED(name_, "Robot descripion couldn't be retrieved from param server.");
00315       return false;
00316     }
00317 
00318     boost::shared_ptr<urdf::ModelInterface> model(urdf::parseURDF(robot_model_str));
00319 
00320     // Get wheel separation
00321     boost::shared_ptr<const urdf::Joint> left_wheel_joint(model->getJoint(left_wheel_name));
00322     if(!left_wheel_joint)
00323     {
00324       ROS_ERROR_STREAM_NAMED(name_, left_wheel_name
00325                              << " couldn't be retrieved from model description");
00326       return false;
00327     }
00328     boost::shared_ptr<const urdf::Joint> right_wheel_joint(model->getJoint(right_wheel_name));
00329     if(!right_wheel_joint)
00330     {
00331       ROS_ERROR_STREAM_NAMED(name_, right_wheel_name
00332                              << " couldn't be retrieved from model description");
00333       return false;
00334     }
00335 
00336     ROS_INFO_STREAM("left wheel to origin: " << left_wheel_joint->parent_to_joint_origin_transform.position.x << ","
00337                     << left_wheel_joint->parent_to_joint_origin_transform.position.y << ", "
00338                     << left_wheel_joint->parent_to_joint_origin_transform.position.z);
00339     ROS_INFO_STREAM("right wheel to origin: " << right_wheel_joint->parent_to_joint_origin_transform.position.x << ","
00340                     << right_wheel_joint->parent_to_joint_origin_transform.position.y << ", "
00341                     << right_wheel_joint->parent_to_joint_origin_transform.position.z);
00342 
00343     wheel_separation_ = euclideanOfVectors(left_wheel_joint->parent_to_joint_origin_transform.position,
00344                                            right_wheel_joint->parent_to_joint_origin_transform.position);
00345 
00346     // Get wheel radius
00347     if(!getWheelRadius(model->getLink(left_wheel_joint->child_link_name), wheel_radius_))
00348     {
00349       ROS_ERROR_STREAM_NAMED(name_, "Couldn't retrieve " << left_wheel_name << " wheel radius");
00350       return false;
00351     }
00352 
00353     // Set wheel params for the odometry computation
00354     const double ws = wheel_separation_multiplier_ * wheel_separation_;
00355     const double wr = wheel_radius_multiplier_     * wheel_radius_;
00356     odometry_.setWheelParams(ws, wr);
00357     ROS_INFO_STREAM_NAMED(name_,
00358                           "Odometry params : wheel separation " << ws
00359                           << ", wheel radius " << wr);
00360     return true;
00361   }
00362 
00363   void DiffDriveController::setOdomPubFields(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh)
00364   {
00365     // Get and check params for covariances
00366     XmlRpc::XmlRpcValue pose_cov_list;
00367     controller_nh.getParam("pose_covariance_diagonal", pose_cov_list);
00368     ROS_ASSERT(pose_cov_list.getType() == XmlRpc::XmlRpcValue::TypeArray);
00369     ROS_ASSERT(pose_cov_list.size() == 6);
00370     for (int i = 0; i < pose_cov_list.size(); ++i)
00371       ROS_ASSERT(pose_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00372 
00373     XmlRpc::XmlRpcValue twist_cov_list;
00374     controller_nh.getParam("twist_covariance_diagonal", twist_cov_list);
00375     ROS_ASSERT(twist_cov_list.getType() == XmlRpc::XmlRpcValue::TypeArray);
00376     ROS_ASSERT(twist_cov_list.size() == 6);
00377     for (int i = 0; i < twist_cov_list.size(); ++i)
00378       ROS_ASSERT(twist_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00379 
00380     // Setup odometry realtime publisher + odom message constant fields
00381     odom_pub_.reset(new realtime_tools::RealtimePublisher<nav_msgs::Odometry>(controller_nh, "odom", 100));
00382     odom_pub_->msg_.header.frame_id = "odom";
00383     odom_pub_->msg_.child_frame_id = base_frame_id_;
00384     odom_pub_->msg_.pose.pose.position.z = 0;
00385     odom_pub_->msg_.pose.covariance = boost::assign::list_of
00386         (static_cast<double>(pose_cov_list[0])) (0)   (0)  (0)  (0)  (0)
00387         (0) (static_cast<double>(pose_cov_list[1]))  (0)  (0)  (0)  (0)
00388         (0)   (0)  (static_cast<double>(pose_cov_list[2])) (0)  (0)  (0)
00389         (0)   (0)   (0) (static_cast<double>(pose_cov_list[3])) (0)  (0)
00390         (0)   (0)   (0)  (0) (static_cast<double>(pose_cov_list[4])) (0)
00391         (0)   (0)   (0)  (0)  (0)  (static_cast<double>(pose_cov_list[5]));
00392     odom_pub_->msg_.twist.twist.linear.y  = 0;
00393     odom_pub_->msg_.twist.twist.linear.z  = 0;
00394     odom_pub_->msg_.twist.twist.angular.x = 0;
00395     odom_pub_->msg_.twist.twist.angular.y = 0;
00396     odom_pub_->msg_.twist.covariance = boost::assign::list_of
00397         (static_cast<double>(twist_cov_list[0])) (0)   (0)  (0)  (0)  (0)
00398         (0) (static_cast<double>(twist_cov_list[1]))  (0)  (0)  (0)  (0)
00399         (0)   (0)  (static_cast<double>(twist_cov_list[2])) (0)  (0)  (0)
00400         (0)   (0)   (0) (static_cast<double>(twist_cov_list[3])) (0)  (0)
00401         (0)   (0)   (0)  (0) (static_cast<double>(twist_cov_list[4])) (0)
00402         (0)   (0)   (0)  (0)  (0)  (static_cast<double>(twist_cov_list[5]));
00403     tf_odom_pub_.reset(new realtime_tools::RealtimePublisher<tf::tfMessage>(root_nh, "/tf", 100));
00404     tf_odom_pub_->msg_.transforms.resize(1);
00405     odom_frame_.transform.translation.z = 0.0;
00406     odom_frame_.child_frame_id = base_frame_id_;
00407     odom_frame_.header.frame_id = "odom";
00408   }
00409 
00410 } // namespace diff_drive_controller


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Fri Aug 28 2015 12:36:51