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 <cmath>
00040 
00041 #include <tf/transform_datatypes.h>
00042 
00043 #include <urdf_parser/urdf_parser.h>
00044 
00045 #include <boost/assign.hpp>
00046 
00047 #include <diff_drive_controller/diff_drive_controller.h>
00048 
00049 static double euclideanOfVectors(const urdf::Vector3& vec1, const urdf::Vector3& vec2)
00050 {
00051   return std::sqrt(std::pow(vec1.x-vec2.x,2) +
00052                    std::pow(vec1.y-vec2.y,2) +
00053                    std::pow(vec1.z-vec2.z,2));
00054 }
00055 
00056 /*
00057  * \brief Check if the link is modeled as a cylinder
00058  * \param link Link
00059  * \return true if the link is modeled as a Cylinder; false otherwise
00060  */
00061 static bool isCylinder(const boost::shared_ptr<const urdf::Link>& link)
00062 {
00063   if (!link)
00064   {
00065     ROS_ERROR("Link == NULL.");
00066     return false;
00067   }
00068 
00069   if (!link->collision)
00070   {
00071     ROS_ERROR_STREAM("Link " << link->name << " does not have collision description. Add collision description for link to urdf.");
00072     return false;
00073   }
00074 
00075   if (!link->collision->geometry)
00076   {
00077     ROS_ERROR_STREAM("Link " << link->name << " does not have collision geometry description. Add collision geometry description for link to urdf.");
00078     return false;
00079   }
00080 
00081   if (link->collision->geometry->type != urdf::Geometry::CYLINDER)
00082   {
00083     ROS_ERROR_STREAM("Link " << link->name << " does not have cylinder geometry");
00084     return false;
00085   }
00086 
00087   return true;
00088 }
00089 
00090 /*
00091  * \brief Get the wheel radius
00092  * \param [in]  wheel_link   Wheel link
00093  * \param [out] wheel_radius Wheel radius [m]
00094  * \return true if the wheel radius was found; false otherwise
00095  */
00096 static bool getWheelRadius(const boost::shared_ptr<const urdf::Link>& wheel_link, double& wheel_radius)
00097 {
00098   if (!isCylinder(wheel_link))
00099   {
00100     ROS_ERROR_STREAM("Wheel link " << wheel_link->name << " is NOT modeled as a cylinder!");
00101     return false;
00102   }
00103 
00104   wheel_radius = (static_cast<urdf::Cylinder*>(wheel_link->collision->geometry.get()))->radius;
00105   return true;
00106 }
00107 
00108 namespace diff_drive_controller{
00109 
00110   DiffDriveController::DiffDriveController()
00111     : open_loop_(false)
00112     , command_struct_()
00113     , wheel_separation_(0.0)
00114     , wheel_radius_(0.0)
00115     , wheel_separation_multiplier_(1.0)
00116     , wheel_radius_multiplier_(1.0)
00117     , cmd_vel_timeout_(0.5)
00118     , allow_multiple_cmd_vel_publishers_(true)
00119     , base_frame_id_("base_link")
00120     , odom_frame_id_("odom")
00121     , enable_odom_tf_(true)
00122     , wheel_joints_size_(0)
00123     , publish_cmd_(false)
00124   {
00125   }
00126 
00127   bool DiffDriveController::init(hardware_interface::VelocityJointInterface* hw,
00128             ros::NodeHandle& root_nh,
00129             ros::NodeHandle &controller_nh)
00130   {
00131     const std::string complete_ns = controller_nh.getNamespace();
00132     std::size_t id = complete_ns.find_last_of("/");
00133     name_ = complete_ns.substr(id + 1);
00134 
00135     // Get joint names from the parameter server
00136     std::vector<std::string> left_wheel_names, right_wheel_names;
00137     if (!getWheelNames(controller_nh, "left_wheel", left_wheel_names) or
00138         !getWheelNames(controller_nh, "right_wheel", right_wheel_names))
00139     {
00140       return false;
00141     }
00142 
00143     if (left_wheel_names.size() != right_wheel_names.size())
00144     {
00145       ROS_ERROR_STREAM_NAMED(name_,
00146           "#left wheels (" << left_wheel_names.size() << ") != " <<
00147           "#right wheels (" << right_wheel_names.size() << ").");
00148       return false;
00149     }
00150     else
00151     {
00152       wheel_joints_size_ = left_wheel_names.size();
00153 
00154       left_wheel_joints_.resize(wheel_joints_size_);
00155       right_wheel_joints_.resize(wheel_joints_size_);
00156     }
00157 
00158     // Odometry related:
00159     double publish_rate;
00160     controller_nh.param("publish_rate", publish_rate, 50.0);
00161     ROS_INFO_STREAM_NAMED(name_, "Controller state will be published at "
00162                           << publish_rate << "Hz.");
00163     publish_period_ = ros::Duration(1.0 / publish_rate);
00164 
00165     controller_nh.param("open_loop", open_loop_, open_loop_);
00166 
00167     controller_nh.param("wheel_separation_multiplier", wheel_separation_multiplier_, wheel_separation_multiplier_);
00168     ROS_INFO_STREAM_NAMED(name_, "Wheel separation will be multiplied by "
00169                           << wheel_separation_multiplier_ << ".");
00170 
00171     controller_nh.param("wheel_radius_multiplier", wheel_radius_multiplier_, wheel_radius_multiplier_);
00172     ROS_INFO_STREAM_NAMED(name_, "Wheel radius will be multiplied by "
00173                           << wheel_radius_multiplier_ << ".");
00174 
00175     int velocity_rolling_window_size = 10;
00176     controller_nh.param("velocity_rolling_window_size", velocity_rolling_window_size, velocity_rolling_window_size);
00177     ROS_INFO_STREAM_NAMED(name_, "Velocity rolling window size of "
00178                           << velocity_rolling_window_size << ".");
00179 
00180     odometry_.setVelocityRollingWindowSize(velocity_rolling_window_size);
00181 
00182     // Twist command related:
00183     controller_nh.param("cmd_vel_timeout", cmd_vel_timeout_, cmd_vel_timeout_);
00184     ROS_INFO_STREAM_NAMED(name_, "Velocity commands will be considered old if they are older than "
00185                           << cmd_vel_timeout_ << "s.");
00186 
00187     controller_nh.param("allow_multiple_cmd_vel_publishers", allow_multiple_cmd_vel_publishers_, allow_multiple_cmd_vel_publishers_);
00188     ROS_INFO_STREAM_NAMED(name_, "Allow mutiple cmd_vel publishers is "
00189                           << (allow_multiple_cmd_vel_publishers_?"enabled":"disabled"));
00190 
00191     controller_nh.param("base_frame_id", base_frame_id_, base_frame_id_);
00192     ROS_INFO_STREAM_NAMED(name_, "Base frame_id set to " << base_frame_id_);
00193 
00194     controller_nh.param("odom_frame_id", odom_frame_id_, odom_frame_id_);
00195     ROS_INFO_STREAM_NAMED(name_, "Odometry frame_id set to " << odom_frame_id_);
00196 
00197     controller_nh.param("enable_odom_tf", enable_odom_tf_, enable_odom_tf_);
00198     ROS_INFO_STREAM_NAMED(name_, "Publishing to tf is " << (enable_odom_tf_?"enabled":"disabled"));
00199 
00200     // Velocity and acceleration limits:
00201     controller_nh.param("linear/x/has_velocity_limits"    , limiter_lin_.has_velocity_limits    , limiter_lin_.has_velocity_limits    );
00202     controller_nh.param("linear/x/has_acceleration_limits", limiter_lin_.has_acceleration_limits, limiter_lin_.has_acceleration_limits);
00203     controller_nh.param("linear/x/has_jerk_limits"        , limiter_lin_.has_jerk_limits        , limiter_lin_.has_jerk_limits        );
00204     controller_nh.param("linear/x/max_velocity"           , limiter_lin_.max_velocity           ,  limiter_lin_.max_velocity          );
00205     controller_nh.param("linear/x/min_velocity"           , limiter_lin_.min_velocity           , -limiter_lin_.max_velocity          );
00206     controller_nh.param("linear/x/max_acceleration"       , limiter_lin_.max_acceleration       ,  limiter_lin_.max_acceleration      );
00207     controller_nh.param("linear/x/min_acceleration"       , limiter_lin_.min_acceleration       , -limiter_lin_.max_acceleration      );
00208     controller_nh.param("linear/x/max_jerk"               , limiter_lin_.max_jerk               ,  limiter_lin_.max_jerk              );
00209     controller_nh.param("linear/x/min_jerk"               , limiter_lin_.min_jerk               , -limiter_lin_.max_jerk              );
00210 
00211     controller_nh.param("angular/z/has_velocity_limits"    , limiter_ang_.has_velocity_limits    , limiter_ang_.has_velocity_limits    );
00212     controller_nh.param("angular/z/has_acceleration_limits", limiter_ang_.has_acceleration_limits, limiter_ang_.has_acceleration_limits);
00213     controller_nh.param("angular/z/has_jerk_limits"        , limiter_ang_.has_jerk_limits        , limiter_ang_.has_jerk_limits        );
00214     controller_nh.param("angular/z/max_velocity"           , limiter_ang_.max_velocity           ,  limiter_ang_.max_velocity          );
00215     controller_nh.param("angular/z/min_velocity"           , limiter_ang_.min_velocity           , -limiter_ang_.max_velocity          );
00216     controller_nh.param("angular/z/max_acceleration"       , limiter_ang_.max_acceleration       ,  limiter_ang_.max_acceleration      );
00217     controller_nh.param("angular/z/min_acceleration"       , limiter_ang_.min_acceleration       , -limiter_ang_.max_acceleration      );
00218     controller_nh.param("angular/z/max_jerk"               , limiter_ang_.max_jerk               ,  limiter_ang_.max_jerk              );
00219     controller_nh.param("angular/z/min_jerk"               , limiter_ang_.min_jerk               , -limiter_ang_.max_jerk              );
00220 
00221     // Publish limited velocity:
00222     controller_nh.param("publish_cmd", publish_cmd_, publish_cmd_);
00223 
00224     // If either parameter is not available, we need to look up the value in the URDF
00225     bool lookup_wheel_separation = !controller_nh.getParam("wheel_separation", wheel_separation_);
00226     bool lookup_wheel_radius = !controller_nh.getParam("wheel_radius", wheel_radius_);
00227 
00228     if (!setOdomParamsFromUrdf(root_nh,
00229                               left_wheel_names[0],
00230                               right_wheel_names[0],
00231                               lookup_wheel_separation,
00232                               lookup_wheel_radius))
00233     {
00234       return false;
00235     }
00236 
00237     // Regardless of how we got the separation and radius, use them
00238     // to set the odometry parameters
00239     const double ws = wheel_separation_multiplier_ * wheel_separation_;
00240     const double wr = wheel_radius_multiplier_     * wheel_radius_;
00241     odometry_.setWheelParams(ws, wr);
00242     ROS_INFO_STREAM_NAMED(name_,
00243                           "Odometry params : wheel separation " << ws
00244                           << ", wheel radius " << wr);
00245 
00246     setOdomPubFields(root_nh, controller_nh);
00247 
00248     if (publish_cmd_)
00249     {
00250       cmd_vel_pub_.reset(new realtime_tools::RealtimePublisher<geometry_msgs::TwistStamped>(controller_nh, "cmd_vel_out", 100));
00251     }
00252 
00253     // Get the joint object to use in the realtime loop
00254     for (int i = 0; i < wheel_joints_size_; ++i)
00255     {
00256       ROS_INFO_STREAM_NAMED(name_,
00257                             "Adding left wheel with joint name: " << left_wheel_names[i]
00258                             << " and right wheel with joint name: " << right_wheel_names[i]);
00259       left_wheel_joints_[i] = hw->getHandle(left_wheel_names[i]);  // throws on failure
00260       right_wheel_joints_[i] = hw->getHandle(right_wheel_names[i]);  // throws on failure
00261     }
00262 
00263     sub_command_ = controller_nh.subscribe("cmd_vel", 1, &DiffDriveController::cmdVelCallback, this);
00264 
00265     return true;
00266   }
00267 
00268   void DiffDriveController::update(const ros::Time& time, const ros::Duration& period)
00269   {
00270     // COMPUTE AND PUBLISH ODOMETRY
00271     if (open_loop_)
00272     {
00273       odometry_.updateOpenLoop(last0_cmd_.lin, last0_cmd_.ang, time);
00274     }
00275     else
00276     {
00277       double left_pos  = 0.0;
00278       double right_pos = 0.0;
00279       for (size_t i = 0; i < wheel_joints_size_; ++i)
00280       {
00281         const double lp = left_wheel_joints_[i].getPosition();
00282         const double rp = right_wheel_joints_[i].getPosition();
00283         if (std::isnan(lp) || std::isnan(rp))
00284           return;
00285 
00286         left_pos  += lp;
00287         right_pos += rp;
00288       }
00289       left_pos  /= wheel_joints_size_;
00290       right_pos /= wheel_joints_size_;
00291 
00292       // Estimate linear and angular velocity using joint information
00293       odometry_.update(left_pos, right_pos, time);
00294     }
00295 
00296     // Publish odometry message
00297     if (last_state_publish_time_ + publish_period_ < time)
00298     {
00299       last_state_publish_time_ += publish_period_;
00300       // Compute and store orientation info
00301       const geometry_msgs::Quaternion orientation(
00302             tf::createQuaternionMsgFromYaw(odometry_.getHeading()));
00303 
00304       // Populate odom message and publish
00305       if (odom_pub_->trylock())
00306       {
00307         odom_pub_->msg_.header.stamp = time;
00308         odom_pub_->msg_.pose.pose.position.x = odometry_.getX();
00309         odom_pub_->msg_.pose.pose.position.y = odometry_.getY();
00310         odom_pub_->msg_.pose.pose.orientation = orientation;
00311         odom_pub_->msg_.twist.twist.linear.x  = odometry_.getLinear();
00312         odom_pub_->msg_.twist.twist.angular.z = odometry_.getAngular();
00313         odom_pub_->unlockAndPublish();
00314       }
00315 
00316       // Publish tf /odom frame
00317       if (enable_odom_tf_ && tf_odom_pub_->trylock())
00318       {
00319         geometry_msgs::TransformStamped& odom_frame = tf_odom_pub_->msg_.transforms[0];
00320         odom_frame.header.stamp = time;
00321         odom_frame.transform.translation.x = odometry_.getX();
00322         odom_frame.transform.translation.y = odometry_.getY();
00323         odom_frame.transform.rotation = orientation;
00324         tf_odom_pub_->unlockAndPublish();
00325       }
00326     }
00327 
00328     // MOVE ROBOT
00329     // Retreive current velocity command and time step:
00330     Commands curr_cmd = *(command_.readFromRT());
00331     const double dt = (time - curr_cmd.stamp).toSec();
00332 
00333     // Brake if cmd_vel has timeout:
00334     if (dt > cmd_vel_timeout_)
00335     {
00336       curr_cmd.lin = 0.0;
00337       curr_cmd.ang = 0.0;
00338     }
00339 
00340     // Limit velocities and accelerations:
00341     const double cmd_dt(period.toSec());
00342 
00343     limiter_lin_.limit(curr_cmd.lin, last0_cmd_.lin, last1_cmd_.lin, cmd_dt);
00344     limiter_ang_.limit(curr_cmd.ang, last0_cmd_.ang, last1_cmd_.ang, cmd_dt);
00345 
00346     last1_cmd_ = last0_cmd_;
00347     last0_cmd_ = curr_cmd;
00348 
00349     // Publish limited velocity:
00350     if (publish_cmd_ && cmd_vel_pub_ && cmd_vel_pub_->trylock())
00351     {
00352       cmd_vel_pub_->msg_.header.stamp = time;
00353       cmd_vel_pub_->msg_.twist.linear.x = curr_cmd.lin;
00354       cmd_vel_pub_->msg_.twist.angular.z = curr_cmd.ang;
00355       cmd_vel_pub_->unlockAndPublish();
00356     }
00357 
00358     // Apply multipliers:
00359     const double ws = wheel_separation_multiplier_ * wheel_separation_;
00360     const double wr = wheel_radius_multiplier_     * wheel_radius_;
00361 
00362     // Compute wheels velocities:
00363     const double vel_left  = (curr_cmd.lin - curr_cmd.ang * ws / 2.0)/wr;
00364     const double vel_right = (curr_cmd.lin + curr_cmd.ang * ws / 2.0)/wr;
00365 
00366     // Set wheels velocities:
00367     for (size_t i = 0; i < wheel_joints_size_; ++i)
00368     {
00369       left_wheel_joints_[i].setCommand(vel_left);
00370       right_wheel_joints_[i].setCommand(vel_right);
00371     }
00372   }
00373 
00374   void DiffDriveController::starting(const ros::Time& time)
00375   {
00376     brake();
00377 
00378     // Register starting time used to keep fixed rate
00379     last_state_publish_time_ = time;
00380 
00381     odometry_.init(time);
00382   }
00383 
00384   void DiffDriveController::stopping(const ros::Time& /*time*/)
00385   {
00386     brake();
00387   }
00388 
00389   void DiffDriveController::brake()
00390   {
00391     const double vel = 0.0;
00392     for (size_t i = 0; i < wheel_joints_size_; ++i)
00393     {
00394       left_wheel_joints_[i].setCommand(vel);
00395       right_wheel_joints_[i].setCommand(vel);
00396     }
00397   }
00398 
00399   void DiffDriveController::cmdVelCallback(const geometry_msgs::Twist& command)
00400   {
00401     if (isRunning())
00402     {
00403       // check that we don't have multiple publishers on the command topic
00404       if (!allow_multiple_cmd_vel_publishers_ && sub_command_.getNumPublishers() > 1)
00405       {
00406         ROS_ERROR_STREAM_THROTTLE_NAMED(1.0, name_, "Detected " << sub_command_.getNumPublishers()
00407             << " publishers. Only 1 publisher is allowed. Going to brake.");
00408         brake();
00409         return;
00410       }
00411 
00412       command_struct_.ang   = command.angular.z;
00413       command_struct_.lin   = command.linear.x;
00414       command_struct_.stamp = ros::Time::now();
00415       command_.writeFromNonRT (command_struct_);
00416       ROS_DEBUG_STREAM_NAMED(name_,
00417                              "Added values to command. "
00418                              << "Ang: "   << command_struct_.ang << ", "
00419                              << "Lin: "   << command_struct_.lin << ", "
00420                              << "Stamp: " << command_struct_.stamp);
00421     }
00422     else
00423     {
00424       ROS_ERROR_NAMED(name_, "Can't accept new commands. Controller is not running.");
00425     }
00426   }
00427 
00428   bool DiffDriveController::getWheelNames(ros::NodeHandle& controller_nh,
00429                               const std::string& wheel_param,
00430                               std::vector<std::string>& wheel_names)
00431   {
00432       XmlRpc::XmlRpcValue wheel_list;
00433       if (!controller_nh.getParam(wheel_param, wheel_list))
00434       {
00435         ROS_ERROR_STREAM_NAMED(name_,
00436             "Couldn't retrieve wheel param '" << wheel_param << "'.");
00437         return false;
00438       }
00439 
00440       if (wheel_list.getType() == XmlRpc::XmlRpcValue::TypeArray)
00441       {
00442         if (wheel_list.size() == 0)
00443         {
00444           ROS_ERROR_STREAM_NAMED(name_,
00445               "Wheel param '" << wheel_param << "' is an empty list");
00446           return false;
00447         }
00448 
00449         for (int i = 0; i < wheel_list.size(); ++i)
00450         {
00451           if (wheel_list[i].getType() != XmlRpc::XmlRpcValue::TypeString)
00452           {
00453             ROS_ERROR_STREAM_NAMED(name_,
00454                 "Wheel param '" << wheel_param << "' #" << i <<
00455                 " isn't a string.");
00456             return false;
00457           }
00458         }
00459 
00460         wheel_names.resize(wheel_list.size());
00461         for (int i = 0; i < wheel_list.size(); ++i)
00462         {
00463           wheel_names[i] = static_cast<std::string>(wheel_list[i]);
00464         }
00465       }
00466       else if (wheel_list.getType() == XmlRpc::XmlRpcValue::TypeString)
00467       {
00468         wheel_names.push_back(wheel_list);
00469       }
00470       else
00471       {
00472         ROS_ERROR_STREAM_NAMED(name_,
00473             "Wheel param '" << wheel_param <<
00474             "' is neither a list of strings nor a string.");
00475         return false;
00476       }
00477 
00478       return true;
00479   }
00480 
00481   bool DiffDriveController::setOdomParamsFromUrdf(ros::NodeHandle& root_nh,
00482                              const std::string& left_wheel_name,
00483                              const std::string& right_wheel_name,
00484                              bool lookup_wheel_separation,
00485                              bool lookup_wheel_radius)
00486   {
00487     if (!(lookup_wheel_separation || lookup_wheel_radius))
00488     {
00489       // Short-circuit in case we don't need to look up anything, so we don't have to parse the URDF
00490       return true;
00491     }
00492 
00493     // Parse robot description
00494     const std::string model_param_name = "robot_description";
00495     bool res = root_nh.hasParam(model_param_name);
00496     std::string robot_model_str="";
00497     if (!res || !root_nh.getParam(model_param_name,robot_model_str))
00498     {
00499       ROS_ERROR_NAMED(name_, "Robot descripion couldn't be retrieved from param server.");
00500       return false;
00501     }
00502 
00503     boost::shared_ptr<urdf::ModelInterface> model(urdf::parseURDF(robot_model_str));
00504 
00505     boost::shared_ptr<const urdf::Joint> left_wheel_joint(model->getJoint(left_wheel_name));
00506     boost::shared_ptr<const urdf::Joint> right_wheel_joint(model->getJoint(right_wheel_name));
00507 
00508     if (lookup_wheel_separation)
00509     {
00510       // Get wheel separation
00511       if (!left_wheel_joint)
00512       {
00513         ROS_ERROR_STREAM_NAMED(name_, left_wheel_name
00514                                << " couldn't be retrieved from model description");
00515         return false;
00516       }
00517 
00518       if (!right_wheel_joint)
00519       {
00520         ROS_ERROR_STREAM_NAMED(name_, right_wheel_name
00521                                << " couldn't be retrieved from model description");
00522         return false;
00523       }
00524 
00525       ROS_INFO_STREAM("left wheel to origin: " << left_wheel_joint->parent_to_joint_origin_transform.position.x << ","
00526                       << left_wheel_joint->parent_to_joint_origin_transform.position.y << ", "
00527                       << left_wheel_joint->parent_to_joint_origin_transform.position.z);
00528       ROS_INFO_STREAM("right wheel to origin: " << right_wheel_joint->parent_to_joint_origin_transform.position.x << ","
00529                       << right_wheel_joint->parent_to_joint_origin_transform.position.y << ", "
00530                       << right_wheel_joint->parent_to_joint_origin_transform.position.z);
00531 
00532       wheel_separation_ = euclideanOfVectors(left_wheel_joint->parent_to_joint_origin_transform.position,
00533                                              right_wheel_joint->parent_to_joint_origin_transform.position);
00534 
00535     }
00536 
00537     if (lookup_wheel_radius)
00538     {
00539       // Get wheel radius
00540       if (!getWheelRadius(model->getLink(left_wheel_joint->child_link_name), wheel_radius_))
00541       {
00542         ROS_ERROR_STREAM_NAMED(name_, "Couldn't retrieve " << left_wheel_name << " wheel radius");
00543         return false;
00544       }
00545     }
00546 
00547     return true;
00548   }
00549 
00550   void DiffDriveController::setOdomPubFields(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh)
00551   {
00552     // Get and check params for covariances
00553     XmlRpc::XmlRpcValue pose_cov_list;
00554     controller_nh.getParam("pose_covariance_diagonal", pose_cov_list);
00555     ROS_ASSERT(pose_cov_list.getType() == XmlRpc::XmlRpcValue::TypeArray);
00556     ROS_ASSERT(pose_cov_list.size() == 6);
00557     for (int i = 0; i < pose_cov_list.size(); ++i)
00558       ROS_ASSERT(pose_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00559 
00560     XmlRpc::XmlRpcValue twist_cov_list;
00561     controller_nh.getParam("twist_covariance_diagonal", twist_cov_list);
00562     ROS_ASSERT(twist_cov_list.getType() == XmlRpc::XmlRpcValue::TypeArray);
00563     ROS_ASSERT(twist_cov_list.size() == 6);
00564     for (int i = 0; i < twist_cov_list.size(); ++i)
00565       ROS_ASSERT(twist_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00566 
00567     // Setup odometry realtime publisher + odom message constant fields
00568     odom_pub_.reset(new realtime_tools::RealtimePublisher<nav_msgs::Odometry>(controller_nh, "odom", 100));
00569     odom_pub_->msg_.header.frame_id = odom_frame_id_;
00570     odom_pub_->msg_.child_frame_id = base_frame_id_;
00571     odom_pub_->msg_.pose.pose.position.z = 0;
00572     odom_pub_->msg_.pose.covariance = boost::assign::list_of
00573         (static_cast<double>(pose_cov_list[0])) (0)  (0)  (0)  (0)  (0)
00574         (0)  (static_cast<double>(pose_cov_list[1])) (0)  (0)  (0)  (0)
00575         (0)  (0)  (static_cast<double>(pose_cov_list[2])) (0)  (0)  (0)
00576         (0)  (0)  (0)  (static_cast<double>(pose_cov_list[3])) (0)  (0)
00577         (0)  (0)  (0)  (0)  (static_cast<double>(pose_cov_list[4])) (0)
00578         (0)  (0)  (0)  (0)  (0)  (static_cast<double>(pose_cov_list[5]));
00579     odom_pub_->msg_.twist.twist.linear.y  = 0;
00580     odom_pub_->msg_.twist.twist.linear.z  = 0;
00581     odom_pub_->msg_.twist.twist.angular.x = 0;
00582     odom_pub_->msg_.twist.twist.angular.y = 0;
00583     odom_pub_->msg_.twist.covariance = boost::assign::list_of
00584         (static_cast<double>(twist_cov_list[0])) (0)  (0)  (0)  (0)  (0)
00585         (0)  (static_cast<double>(twist_cov_list[1])) (0)  (0)  (0)  (0)
00586         (0)  (0)  (static_cast<double>(twist_cov_list[2])) (0)  (0)  (0)
00587         (0)  (0)  (0)  (static_cast<double>(twist_cov_list[3])) (0)  (0)
00588         (0)  (0)  (0)  (0)  (static_cast<double>(twist_cov_list[4])) (0)
00589         (0)  (0)  (0)  (0)  (0)  (static_cast<double>(twist_cov_list[5]));
00590     tf_odom_pub_.reset(new realtime_tools::RealtimePublisher<tf::tfMessage>(root_nh, "/tf", 100));
00591     tf_odom_pub_->msg_.transforms.resize(1);
00592     tf_odom_pub_->msg_.transforms[0].transform.translation.z = 0.0;
00593     tf_odom_pub_->msg_.transforms[0].child_frame_id = base_frame_id_;
00594     tf_odom_pub_->msg_.transforms[0].header.frame_id = odom_frame_id_;
00595   }
00596 
00597 } // namespace diff_drive_controller


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Thu Jun 6 2019 18:58:48