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 <jackal_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     , enable_odom_tf_(true)
00117     , wheel_joints_size_(0)
00118   {
00119   }
00120 
00121   bool DiffDriveController::init(hardware_interface::VelocityJointInterface* hw,
00122             ros::NodeHandle& root_nh,
00123             ros::NodeHandle &controller_nh)
00124   {
00125     const std::string complete_ns = controller_nh.getNamespace();
00126     std::size_t id = complete_ns.find_last_of("/");
00127     name_ = complete_ns.substr(id + 1);
00128 
00129     // Get joint names from the parameter server
00130     std::vector<std::string> left_wheel_names, right_wheel_names;
00131     if (!getWheelNames(controller_nh, "left_wheel", left_wheel_names))
00132     {
00133       ROS_ERROR_NAMED(name_, "Couldn't retrieve left wheel names from the param server.");
00134       return false;
00135     }
00136     if (!getWheelNames(controller_nh, "right_wheel", right_wheel_names))
00137     {
00138       ROS_ERROR_NAMED(name_, "Couldn't retrieve right wheel names from the param server.");
00139       return false;
00140     }
00141 
00142     if (left_wheel_names.empty())
00143     {
00144       ROS_ERROR_NAMED(name_, "No left wheels.");
00145       return false;
00146     }
00147 
00148     if (right_wheel_names.empty())
00149     {
00150       ROS_ERROR_NAMED(name_, "No right wheels.");
00151       return false;
00152     }
00153 
00154     if (left_wheel_names.size() != right_wheel_names.size())
00155     {
00156       ROS_ERROR_STREAM_NAMED(name_,
00157           "#left wheels (" << left_wheel_names.size() << ") != " <<
00158           "#right wheels (" << right_wheel_names.size() << ").");
00159       return false;
00160     }
00161     else
00162     {
00163       wheel_joints_size_ = left_wheel_names.size();
00164     }
00165 
00166     // Odometry related:
00167     double publish_rate;
00168     controller_nh.param("publish_rate", publish_rate, 50.0);
00169     ROS_INFO_STREAM_NAMED(name_, "Controller state will be published at "
00170                           << publish_rate << "Hz.");
00171     publish_period_ = ros::Duration(1.0 / publish_rate);
00172 
00173     controller_nh.param("wheel_separation_multiplier", wheel_separation_multiplier_, wheel_separation_multiplier_);
00174     ROS_INFO_STREAM_NAMED(name_, "Wheel separation will be multiplied by "
00175                           << wheel_separation_multiplier_ << ".");
00176 
00177     controller_nh.param("wheel_radius_multiplier", wheel_radius_multiplier_, wheel_radius_multiplier_);
00178     ROS_INFO_STREAM_NAMED(name_, "Wheel radius will be multiplied by "
00179                           << wheel_radius_multiplier_ << ".");
00180 
00181     controller_nh.param("cmd_vel_timeout", cmd_vel_timeout_, cmd_vel_timeout_);
00182     ROS_INFO_STREAM_NAMED(name_, "Velocity commands will be considered old if they are older than "
00183                           << cmd_vel_timeout_ << "s.");
00184 
00185     controller_nh.param("base_frame_id", base_frame_id_, base_frame_id_);
00186     ROS_INFO_STREAM_NAMED(name_, "Base frame_id set to " << base_frame_id_);
00187 
00188     controller_nh.param("enable_odom_tf", enable_odom_tf_, enable_odom_tf_);
00189     ROS_INFO_STREAM_NAMED(name_, "Publishing to tf is " << (enable_odom_tf_?"enabled":"disabled"));
00190 
00191     // Velocity and acceleration limits:
00192     controller_nh.param("linear/x/has_velocity_limits"    , limiter_lin_.has_velocity_limits    , limiter_lin_.has_velocity_limits    );
00193     controller_nh.param("linear/x/has_acceleration_limits", limiter_lin_.has_acceleration_limits, limiter_lin_.has_acceleration_limits);
00194     controller_nh.param("linear/x/max_velocity"           , limiter_lin_.max_velocity           ,  limiter_lin_.max_velocity          );
00195     controller_nh.param("linear/x/min_velocity"           , limiter_lin_.min_velocity           , -limiter_lin_.max_velocity          );
00196     controller_nh.param("linear/x/max_acceleration"       , limiter_lin_.max_acceleration       ,  limiter_lin_.max_acceleration      );
00197     controller_nh.param("linear/x/min_acceleration"       , limiter_lin_.min_acceleration       , -limiter_lin_.max_acceleration      );
00198 
00199     controller_nh.param("angular/z/has_velocity_limits"    , limiter_ang_.has_velocity_limits    , limiter_ang_.has_velocity_limits    );
00200     controller_nh.param("angular/z/has_acceleration_limits", limiter_ang_.has_acceleration_limits, limiter_ang_.has_acceleration_limits);
00201     controller_nh.param("angular/z/max_velocity"           , limiter_ang_.max_velocity           ,  limiter_ang_.max_velocity          );
00202     controller_nh.param("angular/z/min_velocity"           , limiter_ang_.min_velocity           , -limiter_ang_.max_velocity          );
00203     controller_nh.param("angular/z/max_acceleration"       , limiter_ang_.max_acceleration       ,  limiter_ang_.max_acceleration      );
00204     controller_nh.param("angular/z/min_acceleration"       , limiter_ang_.min_acceleration       , -limiter_ang_.max_acceleration      );
00205 
00206     if (!setOdomParamsFromUrdf(root_nh, left_wheel_names[0], right_wheel_names[0]))
00207       return false;
00208 
00209     setOdomPubFields(root_nh, controller_nh);
00210 
00211     // Get the joint object to use in the realtime loop
00212     left_wheel_joints_.resize(left_wheel_names.size());
00213     right_wheel_joints_.resize(right_wheel_names.size());
00214     for (int i = 0; i < left_wheel_names.size(); ++i)
00215     {
00216       ROS_INFO_STREAM_NAMED(name_,
00217                             "Adding left wheel with joint name: " << left_wheel_names[i]
00218                             << " and right wheel with joint name: " << right_wheel_names[i]);
00219       left_wheel_joints_[i] = hw->getHandle(left_wheel_names[i]);  // throws on failure
00220       right_wheel_joints_[i] = hw->getHandle(right_wheel_names[i]);  // throws on failure
00221     }
00222 
00223     sub_command_ = controller_nh.subscribe("cmd_vel", 1, &DiffDriveController::cmdVelCallback, this);
00224 
00225     return true;
00226   }
00227 
00228   void DiffDriveController::update(const ros::Time& time, const ros::Duration& period)
00229   {
00230     // Compute and publish odometry
00231     double left_pos  = 0.0;
00232     double right_pos = 0.0;
00233     for (size_t i = 0; i < wheel_joints_size_; ++i)
00234     {
00235       const double lp = left_wheel_joints_[i].getPosition();
00236       const double rp = right_wheel_joints_[i].getPosition();
00237       if (std::isnan(lp) || std::isnan(rp))
00238         return;
00239 
00240       left_pos  += lp;
00241       right_pos += rp;
00242     }
00243     left_pos  /= wheel_joints_size_;
00244     right_pos /= wheel_joints_size_;
00245 
00246     // Estimate linear and angular velocity using joint information
00247     odometry_.update(left_pos, right_pos, time);
00248 
00249     // Publish odometry message
00250     if (last_state_publish_time_ + publish_period_ < time)
00251     {
00252       last_state_publish_time_ += publish_period_;
00253       // Compute and store orientation info
00254       const geometry_msgs::Quaternion orientation(
00255             tf::createQuaternionMsgFromYaw(odometry_.getHeading()));
00256 
00257       // Populate odom message and publish
00258       if(odom_pub_->trylock())
00259       {
00260         odom_pub_->msg_.header.stamp = time;
00261         odom_pub_->msg_.pose.pose.position.x = odometry_.getX();
00262         odom_pub_->msg_.pose.pose.position.y = odometry_.getY();
00263         odom_pub_->msg_.pose.pose.orientation = orientation;
00264         odom_pub_->msg_.twist.twist.linear.x  = odometry_.getLinearEstimated();
00265         odom_pub_->msg_.twist.twist.angular.z = odometry_.getAngularEstimated();
00266         odom_pub_->unlockAndPublish();
00267       }
00268 
00269       // Publish tf /odom frame
00270       if (enable_odom_tf_ && tf_odom_pub_->trylock())
00271       {
00272         odom_frame_.header.stamp = time;
00273         odom_frame_.transform.translation.x = odometry_.getX();
00274         odom_frame_.transform.translation.y = odometry_.getY();
00275         odom_frame_.transform.rotation = orientation;
00276         tf_odom_pub_->msg_.transforms[0] = odom_frame_;
00277         tf_odom_pub_->unlockAndPublish();
00278       }
00279     }
00280 
00281     // MOVE ROBOT
00282     // Retreive current velocity command and time step:
00283     Commands curr_cmd = *(command_.readFromRT());
00284     const double dt = (time - curr_cmd.stamp).toSec();
00285 
00286     // Brake if cmd_vel has timeout:
00287     if (dt > cmd_vel_timeout_)
00288     {
00289       curr_cmd.lin = 0.0;
00290       curr_cmd.ang = 0.0;
00291     }
00292 
00293     // Limit velocities and accelerations:
00294     double cmd_dt = period.toSec();
00295     limiter_lin_.limit(curr_cmd.lin, last_cmd_.lin, cmd_dt);
00296     limiter_ang_.limit(curr_cmd.ang, last_cmd_.ang, cmd_dt);
00297     last_cmd_ = curr_cmd;
00298 
00299     // Apply multipliers:
00300     const double ws = wheel_separation_multiplier_ * wheel_separation_;
00301     const double wr = wheel_radius_multiplier_     * wheel_radius_;
00302 
00303     // Compute wheels velocities:
00304     const double vel_left  = (curr_cmd.lin - curr_cmd.ang * ws / 2.0)/wr;
00305     const double vel_right = (curr_cmd.lin + curr_cmd.ang * ws / 2.0)/wr;
00306 
00307     // Set wheels velocities:
00308     for (size_t i = 0; i < wheel_joints_size_; ++i)
00309     {
00310       left_wheel_joints_[i].setCommand(vel_left);
00311       right_wheel_joints_[i].setCommand(vel_right);
00312     }
00313   }
00314 
00315   void DiffDriveController::starting(const ros::Time& time)
00316   {
00317     brake();
00318 
00319     // Register starting time used to keep fixed rate
00320     last_state_publish_time_ = time;
00321   }
00322 
00323   void DiffDriveController::stopping(const ros::Time& time)
00324   {
00325     brake();
00326   }
00327 
00328   void DiffDriveController::brake()
00329   {
00330     const double vel = 0.0;
00331     for (size_t i = 0; i < wheel_joints_size_; ++i)
00332     {
00333       left_wheel_joints_[i].setCommand(vel);
00334       right_wheel_joints_[i].setCommand(vel);
00335     }
00336   }
00337 
00338   void DiffDriveController::cmdVelCallback(const geometry_msgs::Twist& command)
00339   {
00340     if(isRunning())
00341     {
00342       command_struct_.ang   = command.angular.z;
00343       command_struct_.lin   = command.linear.x;
00344       command_struct_.stamp = ros::Time::now();
00345       command_.writeFromNonRT (command_struct_);
00346       ROS_DEBUG_STREAM_NAMED(name_,
00347                              "Added values to command. "
00348                              << "Ang: "   << command_struct_.ang << ", "
00349                              << "Lin: "   << command_struct_.lin << ", "
00350                              << "Stamp: " << command_struct_.stamp);
00351     }
00352     else
00353     {
00354       ROS_ERROR_NAMED(name_, "Can't accept new commands. Controller is not running.");
00355     }
00356   }
00357 
00358   bool DiffDriveController::getWheelNames(ros::NodeHandle& controller_nh,
00359                               const std::string& wheel_param,
00360                               std::vector<std::string>& wheel_names)
00361   {
00362       XmlRpc::XmlRpcValue wheel_list;
00363       if (!controller_nh.getParam(wheel_param, wheel_list))
00364       {
00365         return false;
00366       }
00367 
00368       if (wheel_list.getType() == XmlRpc::XmlRpcValue::TypeArray)
00369       {
00370         for (int i = 0; i < wheel_list.size(); ++i)
00371         {
00372           if (wheel_list[i].getType() != XmlRpc::XmlRpcValue::TypeString)
00373           {
00374             ROS_ERROR_STREAM_NAMED(name_,
00375                 "Wheel name #" << i << " isn't a string.");
00376             return false;
00377           }
00378         }
00379 
00380         wheel_names.resize(wheel_list.size());
00381         for (int i = 0; i < wheel_list.size(); ++i)
00382         {
00383           wheel_names[i] = static_cast<std::string>(wheel_list[i]);
00384         }
00385       }
00386       else if (wheel_list.getType() == XmlRpc::XmlRpcValue::TypeString)
00387       {
00388         wheel_names.push_back(wheel_list);
00389       }
00390       else
00391       {
00392         ROS_ERROR_STREAM_NAMED(name_,
00393             "Wheel param '" << wheel_param <<
00394             "' is neither a list of strings nor a string.");
00395         return false;
00396       }
00397 
00398       return true;
00399   }
00400 
00401   bool DiffDriveController::setOdomParamsFromUrdf(ros::NodeHandle& root_nh,
00402                              const std::string& left_wheel_name,
00403                              const std::string& right_wheel_name)
00404   {
00405     // Parse robot description
00406     const std::string model_param_name = "robot_description";
00407     bool res = root_nh.hasParam(model_param_name);
00408     std::string robot_model_str="";
00409     if(!res || !root_nh.getParam(model_param_name,robot_model_str))
00410     {
00411       ROS_ERROR_NAMED(name_, "Robot descripion couldn't be retrieved from param server.");
00412       return false;
00413     }
00414 
00415     boost::shared_ptr<urdf::ModelInterface> model(urdf::parseURDF(robot_model_str));
00416 
00417     // Get wheel separation
00418     boost::shared_ptr<const urdf::Joint> left_wheel_joint(model->getJoint(left_wheel_name));
00419     if(!left_wheel_joint)
00420     {
00421       ROS_ERROR_STREAM_NAMED(name_, left_wheel_name
00422                              << " couldn't be retrieved from model description");
00423       return false;
00424     }
00425     boost::shared_ptr<const urdf::Joint> right_wheel_joint(model->getJoint(right_wheel_name));
00426     if(!right_wheel_joint)
00427     {
00428       ROS_ERROR_STREAM_NAMED(name_, right_wheel_name
00429                              << " couldn't be retrieved from model description");
00430       return false;
00431     }
00432 
00433     ROS_INFO_STREAM("left wheel to origin: " << left_wheel_joint->parent_to_joint_origin_transform.position.x << ","
00434                     << left_wheel_joint->parent_to_joint_origin_transform.position.y << ", "
00435                     << left_wheel_joint->parent_to_joint_origin_transform.position.z);
00436     ROS_INFO_STREAM("right wheel to origin: " << right_wheel_joint->parent_to_joint_origin_transform.position.x << ","
00437                     << right_wheel_joint->parent_to_joint_origin_transform.position.y << ", "
00438                     << right_wheel_joint->parent_to_joint_origin_transform.position.z);
00439 
00440     wheel_separation_ = euclideanOfVectors(left_wheel_joint->parent_to_joint_origin_transform.position,
00441                                            right_wheel_joint->parent_to_joint_origin_transform.position);
00442 
00443     // Get wheel radius
00444     if(!getWheelRadius(model->getLink(left_wheel_joint->child_link_name), wheel_radius_))
00445     {
00446       ROS_ERROR_STREAM_NAMED(name_, "Couldn't retrieve " << left_wheel_name << " wheel radius");
00447       return false;
00448     }
00449 
00450     // Set wheel params for the odometry computation
00451     const double ws = wheel_separation_multiplier_ * wheel_separation_;
00452     const double wr = wheel_radius_multiplier_     * wheel_radius_;
00453     odometry_.setWheelParams(ws, wr);
00454     ROS_INFO_STREAM_NAMED(name_,
00455                           "Odometry params : wheel separation " << ws
00456                           << ", wheel radius " << wr);
00457     return true;
00458   }
00459 
00460   void DiffDriveController::setOdomPubFields(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh)
00461   {
00462     // Get and check params for covariances
00463     XmlRpc::XmlRpcValue pose_cov_list;
00464     controller_nh.getParam("pose_covariance_diagonal", pose_cov_list);
00465     ROS_ASSERT(pose_cov_list.getType() == XmlRpc::XmlRpcValue::TypeArray);
00466     ROS_ASSERT(pose_cov_list.size() == 6);
00467     for (int i = 0; i < pose_cov_list.size(); ++i)
00468       ROS_ASSERT(pose_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00469 
00470     XmlRpc::XmlRpcValue twist_cov_list;
00471     controller_nh.getParam("twist_covariance_diagonal", twist_cov_list);
00472     ROS_ASSERT(twist_cov_list.getType() == XmlRpc::XmlRpcValue::TypeArray);
00473     ROS_ASSERT(twist_cov_list.size() == 6);
00474     for (int i = 0; i < twist_cov_list.size(); ++i)
00475       ROS_ASSERT(twist_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00476 
00477     // Setup odometry realtime publisher + odom message constant fields
00478     odom_pub_.reset(new realtime_tools::RealtimePublisher<nav_msgs::Odometry>(controller_nh, "odom", 100));
00479     odom_pub_->msg_.header.frame_id = "odom";
00480     odom_pub_->msg_.child_frame_id = base_frame_id_;
00481     odom_pub_->msg_.pose.pose.position.z = 0;
00482     odom_pub_->msg_.pose.covariance = boost::assign::list_of
00483         (static_cast<double>(pose_cov_list[0])) (0)   (0)  (0)  (0)  (0)
00484         (0) (static_cast<double>(pose_cov_list[1]))  (0)  (0)  (0)  (0)
00485         (0)   (0)  (static_cast<double>(pose_cov_list[2])) (0)  (0)  (0)
00486         (0)   (0)   (0) (static_cast<double>(pose_cov_list[3])) (0)  (0)
00487         (0)   (0)   (0)  (0) (static_cast<double>(pose_cov_list[4])) (0)
00488         (0)   (0)   (0)  (0)  (0)  (static_cast<double>(pose_cov_list[5]));
00489     odom_pub_->msg_.twist.twist.linear.y  = 0;
00490     odom_pub_->msg_.twist.twist.linear.z  = 0;
00491     odom_pub_->msg_.twist.twist.angular.x = 0;
00492     odom_pub_->msg_.twist.twist.angular.y = 0;
00493     odom_pub_->msg_.twist.covariance = boost::assign::list_of
00494         (static_cast<double>(twist_cov_list[0])) (0)   (0)  (0)  (0)  (0)
00495         (0) (static_cast<double>(twist_cov_list[1]))  (0)  (0)  (0)  (0)
00496         (0)   (0)  (static_cast<double>(twist_cov_list[2])) (0)  (0)  (0)
00497         (0)   (0)   (0) (static_cast<double>(twist_cov_list[3])) (0)  (0)
00498         (0)   (0)   (0)  (0) (static_cast<double>(twist_cov_list[4])) (0)
00499         (0)   (0)   (0)  (0)  (0)  (static_cast<double>(twist_cov_list[5]));
00500     tf_odom_pub_.reset(new realtime_tools::RealtimePublisher<tf::tfMessage>(root_nh, "/tf", 100));
00501     tf_odom_pub_->msg_.transforms.resize(1);
00502     odom_frame_.transform.translation.z = 0.0;
00503     odom_frame_.child_frame_id = base_frame_id_;
00504     odom_frame_.header.frame_id = "odom";
00505   }
00506 
00507 } // namespace diff_drive_controller


jackal_diff_drive_controller
Author(s): Bence Magyar
autogenerated on Fri Dec 12 2014 23:32:03