mecanum_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 <mecanum_drive_controller/mecanum_drive_controller.h>
00046 
00048 static bool isCylinderOrSphere(const boost::shared_ptr<const urdf::Link>& link)
00049 {
00050   if(!link)
00051   {
00052     ROS_ERROR("Link == NULL.");
00053     return false;
00054   }
00055 
00056   if(!link->collision)
00057   {
00058     ROS_ERROR_STREAM("Link " << link->name << " does not have collision description. Add collision description for link to urdf.");
00059     return false;
00060   }
00061 
00062   if(!link->collision->geometry)
00063   {
00064     ROS_ERROR_STREAM("Link " << link->name << " does not have collision geometry description. Add collision geometry description for link to urdf.");
00065     return false;
00066   }
00067 
00068   if(link->collision->geometry->type != urdf::Geometry::CYLINDER && link->collision->geometry->type != urdf::Geometry::SPHERE)
00069   {
00070     ROS_ERROR_STREAM("Link " << link->name << " does not have cylinder nor sphere geometry");
00071     return false;
00072   }
00073 
00074   return true;
00075 }
00076 
00077 namespace mecanum_drive_controller
00078 {
00079 
00081 MecanumDriveController::MecanumDriveController()
00082   : open_loop_(false)
00083   , command_struct_()
00084   , use_realigned_roller_joints_(false)
00085   , wheels_k_(0.0)
00086   , wheels_radius_(0.0)
00087   , cmd_vel_timeout_(0.5)
00088   , base_frame_id_("base_link")
00089   , enable_odom_tf_(true)
00090   , wheel_joints_size_(0)
00091 {
00092 }
00093 
00094 
00096 bool MecanumDriveController::init(hardware_interface::VelocityJointInterface* hw,
00097           ros::NodeHandle& root_nh,
00098           ros::NodeHandle &controller_nh)
00099 {
00100   const std::string complete_ns = controller_nh.getNamespace();
00101   std::size_t id = complete_ns.find_last_of("/");
00102   name_ = complete_ns.substr(id + 1);
00103 
00104   // Option use_realigned_roller_joints
00105   controller_nh.param("use_realigned_roller_joints", use_realigned_roller_joints_, use_realigned_roller_joints_);
00106   ROS_INFO_STREAM_NAMED(name_, "Use the roller's radius rather than the wheel's: " << use_realigned_roller_joints_ << ".");
00107 
00108   // Get joint names from the parameter server
00109   std::string wheel0_name;
00110   controller_nh.param("front_left_wheel_joint", wheel0_name, wheel0_name);
00111   ROS_INFO_STREAM_NAMED(name_, "Front left wheel joint (wheel0) is : " << wheel0_name);
00112 
00113   std::string wheel1_name;
00114   controller_nh.param("back_left_wheel_joint", wheel1_name, wheel1_name);
00115   ROS_INFO_STREAM_NAMED(name_, "Back left wheel joint (wheel1) is : " << wheel1_name);
00116 
00117   std::string wheel2_name;
00118   controller_nh.param("back_right_wheel_joint", wheel2_name, wheel2_name);
00119   ROS_INFO_STREAM_NAMED(name_, "Back right wheel joint (wheel2) is : " << wheel2_name);
00120 
00121   std::string wheel3_name;
00122   controller_nh.param("front_right_wheel_joint", wheel3_name, wheel3_name);
00123   ROS_INFO_STREAM_NAMED(name_, "Front right wheel joint (wheel3) is : " << wheel3_name);
00124 
00125   // Odometry related:
00126   double publish_rate;
00127   controller_nh.param("publish_rate", publish_rate, 50.0);
00128   ROS_INFO_STREAM_NAMED(name_, "Controller state will be published at "
00129                         << publish_rate << "Hz.");
00130   publish_period_ = ros::Duration(1.0 / publish_rate);
00131 
00132   controller_nh.param("open_loop", open_loop_, open_loop_);
00133 
00134   // Twist command related:
00135   controller_nh.param("cmd_vel_timeout", cmd_vel_timeout_, cmd_vel_timeout_);
00136   ROS_INFO_STREAM_NAMED(name_, "Velocity commands will be considered old if they are older than "
00137                         << cmd_vel_timeout_ << "s.");
00138 
00139   controller_nh.param("base_frame_id", base_frame_id_, base_frame_id_);
00140   ROS_INFO_STREAM_NAMED(name_, "Base frame_id set to " << base_frame_id_);
00141 
00142   controller_nh.param("enable_odom_tf", enable_odom_tf_, enable_odom_tf_);
00143   ROS_INFO_STREAM_NAMED(name_, "Publishing to tf is " << (enable_odom_tf_?"enabled":"disabled"));
00144 
00145   // Velocity and acceleration limits:
00146   controller_nh.param("linear/x/has_velocity_limits"    , limiter_linX_.has_velocity_limits    , limiter_linX_.has_velocity_limits    );
00147   controller_nh.param("linear/x/has_acceleration_limits", limiter_linX_.has_acceleration_limits, limiter_linX_.has_acceleration_limits);
00148   controller_nh.param("linear/x/max_velocity"           , limiter_linX_.max_velocity           ,  limiter_linX_.max_velocity          );
00149   controller_nh.param("linear/x/min_velocity"           , limiter_linX_.min_velocity           , -limiter_linX_.max_velocity          );
00150   controller_nh.param("linear/x/max_acceleration"       , limiter_linX_.max_acceleration       ,  limiter_linX_.max_acceleration      );
00151   controller_nh.param("linear/x/min_acceleration"       , limiter_linX_.min_acceleration       , -limiter_linX_.max_acceleration      );
00152 
00153   controller_nh.param("linear/y/has_velocity_limits"    , limiter_linY_.has_velocity_limits    , limiter_linY_.has_velocity_limits    );
00154   controller_nh.param("linear/y/has_acceleration_limits", limiter_linY_.has_acceleration_limits, limiter_linY_.has_acceleration_limits);
00155   controller_nh.param("linear/y/max_velocity"           , limiter_linY_.max_velocity           ,  limiter_linY_.max_velocity          );
00156   controller_nh.param("linear/y/min_velocity"           , limiter_linY_.min_velocity           , -limiter_linY_.max_velocity          );
00157   controller_nh.param("linear/y/max_acceleration"       , limiter_linY_.max_acceleration       ,  limiter_linY_.max_acceleration      );
00158   controller_nh.param("linear/y/min_acceleration"       , limiter_linY_.min_acceleration       , -limiter_linY_.max_acceleration      );
00159 
00160   controller_nh.param("angular/z/has_velocity_limits"    , limiter_ang_.has_velocity_limits    , limiter_ang_.has_velocity_limits    );
00161   controller_nh.param("angular/z/has_acceleration_limits", limiter_ang_.has_acceleration_limits, limiter_ang_.has_acceleration_limits);
00162   controller_nh.param("angular/z/max_velocity"           , limiter_ang_.max_velocity           ,  limiter_ang_.max_velocity          );
00163   controller_nh.param("angular/z/min_velocity"           , limiter_ang_.min_velocity           , -limiter_ang_.max_velocity          );
00164   controller_nh.param("angular/z/max_acceleration"       , limiter_ang_.max_acceleration       ,  limiter_ang_.max_acceleration      );
00165   controller_nh.param("angular/z/min_acceleration"       , limiter_ang_.min_acceleration       , -limiter_ang_.max_acceleration      );
00166 
00167   // Get the joint objects to use in the realtime loop
00168   wheel0_jointHandle_ = hw->getHandle(wheel0_name);  // throws on failure
00169   wheel1_jointHandle_ = hw->getHandle(wheel1_name);  // throws on failure
00170   wheel2_jointHandle_ = hw->getHandle(wheel2_name);  // throws on failure
00171   wheel3_jointHandle_ = hw->getHandle(wheel3_name);  // throws on failure
00172 
00173   // Pass params through and setup publishers and subscribers
00174   if (!setWheelParamsFromUrdf(root_nh, controller_nh, wheel0_name, wheel1_name, wheel2_name, wheel3_name))
00175     return false;
00176 
00177   setupRtPublishersMsg(root_nh, controller_nh);
00178 
00179   sub_command_ = controller_nh.subscribe("cmd_vel", 1, &MecanumDriveController::cmdVelCallback, this);
00180 
00181   return true;
00182 }
00183 
00184 
00186 void MecanumDriveController::update(const ros::Time& time, const ros::Duration& period)
00187 {
00188   // COMPUTE AND PUBLISH ODOMETRY
00189   if (open_loop_)
00190   {
00191     odometry_.updateOpenLoop(last_cmd_.linX, last_cmd_.linY, last_cmd_.ang, time);
00192   }
00193   else
00194   {
00195     double wheel0_vel = wheel0_jointHandle_.getVelocity();
00196     double wheel1_vel = wheel1_jointHandle_.getVelocity();
00197     double wheel2_vel = wheel2_jointHandle_.getVelocity();
00198     double wheel3_vel = wheel3_jointHandle_.getVelocity();
00199 
00200     if (std::isnan(wheel0_vel) || std::isnan(wheel1_vel) || std::isnan(wheel2_vel) || std::isnan(wheel3_vel))
00201       return;
00202 
00203     // Estimate twist (using joint information) and integrate
00204     odometry_.update(wheel0_vel, wheel1_vel, wheel2_vel, wheel3_vel, time);
00205   }
00206 
00207   // Publish odometry message
00208   if(last_state_publish_time_ + publish_period_ < time)
00209   {
00210     last_state_publish_time_ += publish_period_;
00211     // Compute and store orientation info
00212     const geometry_msgs::Quaternion orientation(
00213           tf::createQuaternionMsgFromYaw(odometry_.getHeading()));
00214 
00215     // Populate odom message and publish
00216     if(odom_pub_->trylock())
00217     {
00218       odom_pub_->msg_.header.stamp = time;
00219       odom_pub_->msg_.pose.pose.position.x = odometry_.getX();
00220       odom_pub_->msg_.pose.pose.position.y = odometry_.getY();
00221       odom_pub_->msg_.pose.pose.orientation = orientation;
00222       odom_pub_->msg_.twist.twist.linear.x  = odometry_.getLinearX();
00223       odom_pub_->msg_.twist.twist.linear.y  = odometry_.getLinearY();
00224       odom_pub_->msg_.twist.twist.angular.z = odometry_.getAngular();
00225       odom_pub_->unlockAndPublish();
00226     }
00227 
00228     // Publish tf /odom frame
00229     if (enable_odom_tf_ && tf_odom_pub_->trylock())
00230     {
00231       geometry_msgs::TransformStamped& odom_frame = tf_odom_pub_->msg_.transforms[0];
00232       odom_frame.header.stamp = time;
00233       odom_frame.transform.translation.x = odometry_.getX();
00234       odom_frame.transform.translation.y = odometry_.getY();
00235       odom_frame.transform.rotation = orientation;
00236       tf_odom_pub_->unlockAndPublish();
00237     }
00238   }
00239 
00240   // MOVE ROBOT
00241   // Retrieve current velocity command and time step:
00242   Commands curr_cmd = *(command_.readFromRT());
00243   const double dt = (time - curr_cmd.stamp).toSec();
00244 
00245   // Brake if cmd_vel has timeout:
00246   if (dt > cmd_vel_timeout_)
00247   {
00248     curr_cmd.linX = 0.0;
00249     curr_cmd.linY = 0.0;
00250     curr_cmd.ang = 0.0;
00251   }
00252 
00253   // Limit velocities and accelerations:
00254   const double cmd_dt(period.toSec());
00255   limiter_linX_.limit(curr_cmd.linX, last_cmd_.linX, cmd_dt);
00256   limiter_linY_.limit(curr_cmd.linY, last_cmd_.linY, cmd_dt);
00257   limiter_ang_.limit(curr_cmd.ang, last_cmd_.ang, cmd_dt);
00258   last_cmd_ = curr_cmd;
00259 
00260   // Compute wheels velocities (this is the actual ik):
00261   // NOTE: the input desired twist (from topic /cmd_vel) is a body twist.
00262   const double w0_vel = 1.0 / wheels_radius_ * (curr_cmd.linX - curr_cmd.linY - wheels_k_ * curr_cmd.ang);
00263   const double w1_vel = 1.0 / wheels_radius_ * (curr_cmd.linX + curr_cmd.linY - wheels_k_ * curr_cmd.ang);
00264   const double w2_vel = 1.0 / wheels_radius_ * (curr_cmd.linX - curr_cmd.linY + wheels_k_ * curr_cmd.ang);
00265   const double w3_vel = 1.0 / wheels_radius_ * (curr_cmd.linX + curr_cmd.linY + wheels_k_ * curr_cmd.ang);
00266 
00267   // Set wheels velocities:
00268   wheel0_jointHandle_.setCommand(w0_vel);
00269   wheel1_jointHandle_.setCommand(w1_vel);
00270   wheel2_jointHandle_.setCommand(w2_vel);
00271   wheel3_jointHandle_.setCommand(w3_vel);
00272 }
00273 
00275 void MecanumDriveController::starting(const ros::Time& time)
00276 {
00277   brake();
00278 
00279   // Register starting time used to keep fixed rate
00280   last_state_publish_time_ = time;
00281 
00282   odometry_.init(time);
00283 }
00284 
00286 void MecanumDriveController::stopping(const ros::Time& time)
00287 {
00288   brake();
00289 }
00290 
00292 void MecanumDriveController::brake()
00293 {
00294   wheel0_jointHandle_.setCommand(0.0);
00295   wheel1_jointHandle_.setCommand(0.0);
00296   wheel2_jointHandle_.setCommand(0.0);
00297   wheel3_jointHandle_.setCommand(0.0);
00298 }
00299 
00301 void MecanumDriveController::cmdVelCallback(const geometry_msgs::Twist& command)
00302 {
00303   if(isRunning())
00304   {
00305     command_struct_.ang   = command.angular.z;
00306     command_struct_.linX  = command.linear.x;
00307     command_struct_.linY  = command.linear.y;
00308     command_struct_.stamp = ros::Time::now();
00309     command_.writeFromNonRT (command_struct_);
00310     ROS_DEBUG_STREAM_NAMED(name_,
00311                            "Added values to command. "
00312                            << "Ang: "   << command_struct_.ang << ", "
00313                            << "Lin: "   << command_struct_.linX << ", "
00314                            << "Lin: "   << command_struct_.linY << ", "
00315                            << "Stamp: " << command_struct_.stamp);
00316   }
00317   else
00318   {
00319     ROS_ERROR_NAMED(name_, "Can't accept new commands. Controller is not running.");
00320   }
00321 }
00322 
00324 bool MecanumDriveController::setWheelParamsFromUrdf(ros::NodeHandle& root_nh,
00325                                                    ros::NodeHandle &controller_nh,
00326                                                    const std::string& wheel0_name,
00327                                                    const std::string& wheel1_name,
00328                                                    const std::string& wheel2_name,
00329                                                    const std::string& wheel3_name)
00330 {
00331   bool has_wheel_separation_x = controller_nh.getParam("wheel_separation_x", wheel_separation_x_);
00332   bool has_wheel_separation_y = controller_nh.getParam("wheel_separation_y", wheel_separation_y_);
00333 
00334   // Check to see if both X and Y separations are overrided.
00335   if (has_wheel_separation_x != has_wheel_separation_y)
00336   {
00337     ROS_ERROR_STREAM_NAMED(name_, "Only one wheel separation overrided");
00338     return false;
00339   }
00340 
00341   bool lookup_wheel_separation = !(has_wheel_separation_x && has_wheel_separation_y);
00342   bool lookup_wheel_radius = !controller_nh.getParam("wheel_radius", wheels_radius_);
00343 
00344   // Avoid URDF requirement if wheel separation and radius already specified
00345   if (lookup_wheel_separation || lookup_wheel_radius)
00346   {
00347     // Parse robot description
00348     const std::string model_param_name = "robot_description";
00349     bool res = root_nh.hasParam(model_param_name);
00350     std::string robot_model_str="";
00351     if(!res || !root_nh.getParam(model_param_name,robot_model_str))
00352     {
00353       ROS_ERROR_NAMED(name_, "Robot descripion couldn't be retrieved from param server.");
00354       return false;
00355     }
00356 
00357     boost::shared_ptr<urdf::ModelInterface> model(urdf::parseURDF(robot_model_str));
00358 
00359     // Get wheels position and compute parameter k_ (used in mecanum wheels IK).
00360     boost::shared_ptr<const urdf::Joint> wheel0_urdfJoint(model->getJoint(wheel0_name));
00361     if(!wheel0_urdfJoint)
00362     {
00363       ROS_ERROR_STREAM_NAMED(name_, wheel0_name
00364                              << " couldn't be retrieved from model description");
00365       return false;
00366     }
00367     boost::shared_ptr<const urdf::Joint> wheel1_urdfJoint(model->getJoint(wheel1_name));
00368     if(!wheel1_urdfJoint)
00369     {
00370       ROS_ERROR_STREAM_NAMED(name_, wheel1_name
00371                              << " couldn't be retrieved from model description");
00372       return false;
00373     }
00374     boost::shared_ptr<const urdf::Joint> wheel2_urdfJoint(model->getJoint(wheel2_name));
00375     if(!wheel2_urdfJoint)
00376     {
00377       ROS_ERROR_STREAM_NAMED(name_, wheel2_name
00378                              << " couldn't be retrieved from model description");
00379       return false;
00380     }
00381     boost::shared_ptr<const urdf::Joint> wheel3_urdfJoint(model->getJoint(wheel3_name));
00382     if(!wheel3_urdfJoint)
00383     {
00384       ROS_ERROR_STREAM_NAMED(name_, wheel3_name
00385                              << " couldn't be retrieved from model description");
00386       return false;
00387     }
00388 
00389     if (lookup_wheel_separation)
00390     {
00391       ROS_INFO_STREAM("wheel0 to origin: "  << wheel0_urdfJoint->parent_to_joint_origin_transform.position.x << ","
00392                                             << wheel0_urdfJoint->parent_to_joint_origin_transform.position.y << ", "
00393                                             << wheel0_urdfJoint->parent_to_joint_origin_transform.position.z);
00394       ROS_INFO_STREAM("wheel1 to origin: "  << wheel1_urdfJoint->parent_to_joint_origin_transform.position.x << ","
00395                                             << wheel1_urdfJoint->parent_to_joint_origin_transform.position.y << ", "
00396                                             << wheel1_urdfJoint->parent_to_joint_origin_transform.position.z);
00397       ROS_INFO_STREAM("wheel2 to origin: "  << wheel2_urdfJoint->parent_to_joint_origin_transform.position.x << ","
00398                                             << wheel2_urdfJoint->parent_to_joint_origin_transform.position.y << ", "
00399                                             << wheel2_urdfJoint->parent_to_joint_origin_transform.position.z);
00400       ROS_INFO_STREAM("wheel3 to origin: "  << wheel3_urdfJoint->parent_to_joint_origin_transform.position.x << ","
00401                                             << wheel3_urdfJoint->parent_to_joint_origin_transform.position.y << ", "
00402                                             << wheel3_urdfJoint->parent_to_joint_origin_transform.position.z);
00403 
00404       double wheel0_x = wheel0_urdfJoint->parent_to_joint_origin_transform.position.x;
00405       double wheel0_y = wheel0_urdfJoint->parent_to_joint_origin_transform.position.y;
00406       double wheel1_x = wheel1_urdfJoint->parent_to_joint_origin_transform.position.x;
00407       double wheel1_y = wheel1_urdfJoint->parent_to_joint_origin_transform.position.y;
00408       double wheel2_x = wheel2_urdfJoint->parent_to_joint_origin_transform.position.x;
00409       double wheel2_y = wheel2_urdfJoint->parent_to_joint_origin_transform.position.y;
00410       double wheel3_x = wheel3_urdfJoint->parent_to_joint_origin_transform.position.x;
00411       double wheel3_y = wheel3_urdfJoint->parent_to_joint_origin_transform.position.y;
00412 
00413       wheels_k_ = (-(-wheel0_x - wheel0_y) - (wheel1_x - wheel1_y) + (-wheel2_x - wheel2_y) + (wheel3_x - wheel3_y))
00414                   / 4.0;
00415     }
00416     else
00417     {
00418       ROS_INFO_STREAM("Wheel seperation in X: " << wheel_separation_x_);
00419       ROS_INFO_STREAM("Wheel seperation in Y: " << wheel_separation_y_);
00420 
00421       // The seperation is the total distance between the wheels in X and Y.
00422 
00423       wheels_k_ = (wheel_separation_x_ + wheel_separation_y_) / 2.0;
00424     }
00425 
00426     if (lookup_wheel_radius)
00427     {
00428       // Get wheels radius
00429       double wheel0_radius = 0.0;
00430       double wheel1_radius = 0.0;
00431       double wheel2_radius = 0.0;
00432       double wheel3_radius = 0.0;
00433 
00434       if (!getWheelRadius(model, model->getLink(wheel0_urdfJoint->child_link_name), wheel0_radius) ||
00435           !getWheelRadius(model, model->getLink(wheel1_urdfJoint->child_link_name), wheel1_radius) ||
00436           !getWheelRadius(model, model->getLink(wheel2_urdfJoint->child_link_name), wheel2_radius) ||
00437           !getWheelRadius(model, model->getLink(wheel3_urdfJoint->child_link_name), wheel3_radius))
00438       {
00439         ROS_ERROR_STREAM_NAMED(name_, "Couldn't retrieve wheels' radius");
00440         return false;
00441       }
00442 
00443       if (abs(wheel0_radius - wheel1_radius) > 1e-3 ||
00444           abs(wheel0_radius - wheel2_radius) > 1e-3 ||
00445           abs(wheel0_radius - wheel3_radius) > 1e-3)
00446       {
00447         ROS_ERROR_STREAM_NAMED(name_, "Wheels radius are not egual");
00448         return false;
00449       }
00450 
00451       wheels_radius_ = wheel0_radius;
00452     }
00453   }
00454 
00455   ROS_INFO_STREAM("Wheel radius: " << wheels_radius_);
00456 
00457   // Set wheel params for the odometry computation
00458   odometry_.setWheelsParams(wheels_k_, wheels_radius_);
00459 
00460   return true;
00461 }
00462 
00464 bool MecanumDriveController::getWheelRadius(const boost::shared_ptr<urdf::ModelInterface> model,
00465                                             const boost::shared_ptr<const urdf::Link>& wheel_link, double& wheel_radius)
00466 {
00467   boost::shared_ptr<const urdf::Link> radius_link = wheel_link;
00468 
00469   if (use_realigned_roller_joints_)
00470   {
00471       // This mode is used when the mecanum wheels are simulated and we use realigned rollers to mimic mecanum wheels.
00472       const boost::shared_ptr<const urdf::Joint>& roller_joint = radius_link->child_joints[0];
00473       if(!roller_joint)
00474       {
00475         ROS_ERROR_STREAM_NAMED(name_, "No roller joint could be retrieved for wheel : " << wheel_link->name <<
00476           ". Are you sure mecanum wheels are simulated using realigned rollers?");
00477         return false;
00478       }
00479 
00480       radius_link = model->getLink(roller_joint->child_link_name);
00481       if(!radius_link)
00482       {
00483         ROS_ERROR_STREAM_NAMED(name_, "No roller link could be retrieved for wheel : " << wheel_link->name <<
00484           ". Are you sure mecanum wheels are simulated using realigned rollers?");
00485         return false;
00486       }
00487   }
00488 
00489   if(!isCylinderOrSphere(radius_link))
00490   {
00491     ROS_ERROR_STREAM("Wheel link " << radius_link->name << " is NOT modeled as a cylinder!");
00492     return false;
00493   }
00494 
00495   if (radius_link->collision->geometry->type == urdf::Geometry::CYLINDER)
00496     wheel_radius = (static_cast<urdf::Cylinder*>(radius_link->collision->geometry.get()))->radius;
00497   else
00498     wheel_radius = (static_cast<urdf::Sphere*>(radius_link->collision->geometry.get()))->radius;
00499 
00500   return true;
00501 }
00502 
00504 void MecanumDriveController::setupRtPublishersMsg(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh)
00505 {
00506   // Get covariance parameters for odometry.
00507   XmlRpc::XmlRpcValue pose_cov_list;
00508   controller_nh.getParam("pose_covariance_diagonal", pose_cov_list);
00509   ROS_ASSERT(pose_cov_list.getType() == XmlRpc::XmlRpcValue::TypeArray);
00510   ROS_ASSERT(pose_cov_list.size() == 6);
00511   for (int i = 0; i < pose_cov_list.size(); ++i)
00512     ROS_ASSERT(pose_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00513 
00514   XmlRpc::XmlRpcValue twist_cov_list;
00515   controller_nh.getParam("twist_covariance_diagonal", twist_cov_list);
00516   ROS_ASSERT(twist_cov_list.getType() == XmlRpc::XmlRpcValue::TypeArray);
00517   ROS_ASSERT(twist_cov_list.size() == 6);
00518   for (int i = 0; i < twist_cov_list.size(); ++i)
00519     ROS_ASSERT(twist_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00520 
00521   // Setup odometry msg.
00522   odom_pub_.reset(new realtime_tools::RealtimePublisher<nav_msgs::Odometry>(controller_nh, "odom", 100));
00523   odom_pub_->msg_.header.frame_id = "odom";
00524   odom_pub_->msg_.child_frame_id = base_frame_id_;
00525   odom_pub_->msg_.pose.pose.position.z = 0;
00526   odom_pub_->msg_.pose.covariance = boost::assign::list_of
00527       (static_cast<double>(pose_cov_list[0])) (0)  (0)  (0)  (0)  (0)
00528       (0)  (static_cast<double>(pose_cov_list[1])) (0)  (0)  (0)  (0)
00529       (0)  (0)  (static_cast<double>(pose_cov_list[2])) (0)  (0)  (0)
00530       (0)  (0)  (0)  (static_cast<double>(pose_cov_list[3])) (0)  (0)
00531       (0)  (0)  (0)  (0)  (static_cast<double>(pose_cov_list[4])) (0)
00532       (0)  (0)  (0)  (0)  (0)  (static_cast<double>(pose_cov_list[5]));
00533   odom_pub_->msg_.twist.twist.linear.y  = 0;
00534   odom_pub_->msg_.twist.twist.linear.z  = 0;
00535   odom_pub_->msg_.twist.twist.angular.x = 0;
00536   odom_pub_->msg_.twist.twist.angular.y = 0;
00537   odom_pub_->msg_.twist.covariance = boost::assign::list_of
00538       (static_cast<double>(twist_cov_list[0])) (0)  (0)  (0)  (0)  (0)
00539       (0)  (static_cast<double>(twist_cov_list[1])) (0)  (0)  (0)  (0)
00540       (0)  (0)  (static_cast<double>(twist_cov_list[2])) (0)  (0)  (0)
00541       (0)  (0)  (0)  (static_cast<double>(twist_cov_list[3])) (0)  (0)
00542       (0)  (0)  (0)  (0)  (static_cast<double>(twist_cov_list[4])) (0)
00543       (0)  (0)  (0)  (0)  (0)  (static_cast<double>(twist_cov_list[5]));
00544 
00545   // Setup tf msg.
00546   tf_odom_pub_.reset(new realtime_tools::RealtimePublisher<tf::tfMessage>(root_nh, "/tf", 100));
00547   tf_odom_pub_->msg_.transforms.resize(1);
00548   tf_odom_pub_->msg_.transforms[0].transform.translation.z = 0.0;
00549   tf_odom_pub_->msg_.transforms[0].child_frame_id = base_frame_id_;
00550   tf_odom_pub_->msg_.transforms[0].header.frame_id = "odom";
00551 }
00552 
00553 } // namespace mecanum_drive_controller


ridgeback_control
Author(s): Mike Purvis
autogenerated on Thu Jun 6 2019 21:19:02