steered_wheel_base_controller.cpp
Go to the documentation of this file.
00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 
00039 
00040 
00041 
00042 
00043 
00044 
00045 
00046 
00047 
00048 
00049 
00050 
00051 
00052 
00053 
00054 
00055 
00056 
00057 
00058 
00059 
00060 
00061 
00062 
00063 
00064 
00065 
00066 
00067 
00068 
00069 
00070 
00071 
00072 
00073 
00074 
00075 
00076 
00077 
00078 
00079 
00080 
00081 
00082 
00083 
00084 
00085 
00086 
00087 
00088 
00089 
00090 
00091 
00092 
00093 
00094 
00095 
00096 
00097 
00098 
00099 
00100 
00101 
00102 
00103 
00104 
00105 
00106 
00107 
00108 
00109 
00110 
00111 
00112 
00113 
00114 
00115 
00116 
00117 
00118 
00119 
00120 
00121 
00122 
00123 
00124 
00125 
00126 
00127 
00128 
00129 
00130 
00131 
00132 
00133 
00134 
00135 
00136 
00137 
00138 
00139 
00140 
00141 
00142 
00143 
00144 
00145 //
00146 // Copyright (c) 2013-2015 Wunderkammer Laboratory
00147 //
00148 // Licensed under the Apache License, Version 2.0 (the "License");
00149 // you may not use this file except in compliance with the License.
00150 // You may obtain a copy of the License at
00151 //
00152 //   http://www.apache.org/licenses/LICENSE-2.0
00153 //
00154 // Unless required by applicable law or agreed to in writing, software
00155 // distributed under the License is distributed on an "AS IS" BASIS,
00156 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00157 // See the License for the specific language governing permissions and
00158 // limitations under the License.
00159 
00160 #include <algorithm>
00161 #include <exception>
00162 #include <set>
00163 #include <stdexcept>
00164 #include <string>
00165 #include <vector>
00166 
00167 #include <angles/angles.h>
00168 
00169 #include <boost/foreach.hpp>
00170 #include <boost/math/special_functions/sign.hpp>
00171 #include <boost/shared_ptr.hpp>
00172 
00173 #include <control_toolbox/pid.h>
00174 #include <controller_interface/controller_base.h>
00175 
00176 #include <Eigen/Core>
00177 #include <Eigen/Geometry>
00178 #include <Eigen/SVD>
00179 
00180 #include <geometry_msgs/Twist.h>
00181 #include <hardware_interface/joint_command_interface.h>
00182 
00183 #include <kdl/chainfksolverpos_recursive.hpp>
00184 #include <kdl_parser/kdl_parser.hpp>
00185 
00186 #include <nav_msgs/Odometry.h>
00187 #include <pluginlib/class_list_macros.h>
00188 #include <realtime_tools/realtime_publisher.h>
00189 
00190 #include <tf/tfMessage.h>
00191 #include <tf/transform_datatypes.h>
00192 
00193 #include <urdf/model.h>
00194 
00195 using std::runtime_error;
00196 using std::set;
00197 using std::string;
00198 
00199 using boost::math::sign;
00200 using boost::shared_ptr;
00201 
00202 using Eigen::Affine2d;
00203 using Eigen::Matrix2d;
00204 using Eigen::Vector2d;
00205 
00206 using geometry_msgs::TwistConstPtr;
00207 
00208 using hardware_interface::JointHandle;
00209 using hardware_interface::RobotHW;
00210 
00211 using hardware_interface::EffortJointInterface;
00212 using hardware_interface::PositionJointInterface;
00213 using hardware_interface::VelocityJointInterface;
00214 
00215 using realtime_tools::RealtimeBuffer;
00216 using realtime_tools::RealtimePublisher;
00217 
00218 using ros::Duration;
00219 using ros::NodeHandle;
00220 using ros::Time;
00221 
00222 using XmlRpc::XmlRpcValue;
00223 
00224 namespace
00225 {
00226 
00227 void addClaimedResources(hardware_interface::HardwareInterface *const hw_iface,
00228                          set<string>& claimed_resources)
00229 {
00230   if (hw_iface == NULL)
00231     return;
00232   const set<string> claims = hw_iface->getClaims();
00233   claimed_resources.insert(claims.begin(), claims.end());
00234   hw_iface->clearClaims();
00235 }
00236 
00237 double clamp(const double val, const double min_val, const double max_val)
00238 {
00239   return std::min(std::max(val, min_val), max_val);
00240 }
00241 
00242 double hermite(const double t)
00243 {
00244   if (t <= 0)
00245     return 0;
00246   if (t >= 1)
00247     return 1;
00248   return (-2 * t + 3) * t * t;  // -2t**3 + 3t**2
00249 }
00250 
00251 class Joint
00252 {
00253 public:
00254   virtual ~Joint() {}
00255   virtual void init() = 0;
00256   virtual void stop() = 0;
00257 
00258   bool isValidPos(const double pos) const;
00259   double getPos() const {return handle_.getPosition();}
00260   virtual void setPos(const double pos, const Duration& period) {}
00261 
00262   virtual void setVel(const double vel, const Duration& period) = 0;
00263 
00264 protected:
00265   Joint(const JointHandle& handle,
00266         const shared_ptr<const urdf::Joint> urdf_joint);
00267 
00268   JointHandle handle_;
00269   const bool is_continuous_;
00270   const double lower_limit_, upper_limit_;  // Unit: radian
00271 };
00272 
00273 // Position-controlled joint
00274 class PosJoint : public Joint
00275 {
00276 public:
00277   PosJoint(const JointHandle& handle,
00278            const shared_ptr<const urdf::Joint> urdf_joint) :
00279     Joint(handle, urdf_joint) {}
00280 
00281   virtual void init();
00282   virtual void stop();
00283   virtual void setPos(const double pos, const Duration& period);
00284   virtual void setVel(const double vel, const Duration& period);
00285 
00286 private:
00287   double pos_;
00288 };
00289 
00290 // Velocity-controlled joint. VelJoint is used for axles only.
00291 class VelJoint : public Joint
00292 {
00293 public:
00294   VelJoint(const JointHandle& handle,
00295            const shared_ptr<const urdf::Joint> urdf_joint) :
00296     Joint(handle, urdf_joint) {}
00297 
00298   virtual void init() {stop();}
00299   virtual void stop();
00300   virtual void setVel(const double vel, const Duration& period);
00301 };
00302 
00303 // An object of class PIDJoint is a joint controlled by a PID controller.
00304 class PIDJoint : public Joint
00305 {
00306 public:
00307   PIDJoint(const JointHandle& handle,
00308            const shared_ptr<const urdf::Joint> urdf_joint,
00309            const NodeHandle& ctrlr_nh);
00310 
00311   virtual void init();
00312   virtual void stop();
00313   virtual void setPos(const double pos, const Duration& period);
00314   virtual void setVel(const double vel, const Duration& period);
00315 
00316 private:
00317   const int type_;  // URDF joint type
00318   control_toolbox::Pid pid_ctrlr_;
00319 };
00320 
00321 // An object of class Wheel is a steered wheel.
00322 class Wheel
00323 {
00324 public:
00325   Wheel(const KDL::Tree& tree,
00326         const string& base_link, const string& steer_link,
00327         const shared_ptr<Joint> steer_joint,
00328         const shared_ptr<Joint> axle_joint,
00329         const double circ);
00330 
00331   const Vector2d& pos() const {return pos_;}
00332   Vector2d getDeltaPos();
00333 
00334   void initJoints();
00335   void stop() const;
00336   double ctrlSteering(const Duration& period, const double hermite_scale,
00337                       const double hermite_offset);
00338   double ctrlSteering(const double theta_desired, const Duration& period,
00339                       const double hermite_scale, const double hermite_offset);
00340   void ctrlAxle(const double lin_speed, const Duration& period) const;
00341 
00342 private:
00343   void initPos(const KDL::Tree& tree, const string& base_link);
00344 
00345   string steer_link_; // Steering link
00346   Vector2d pos_;      // Wheel's position in the base link's frame
00347 
00348   shared_ptr<Joint> steer_joint_;   // Steering joint
00349   shared_ptr<Joint> axle_joint_;
00350   double theta_steer_;              // Steering joint position
00351   double last_theta_steer_desired_; // Last desired steering joint position
00352   double last_theta_axle_;          // Last axle joint position
00353 
00354   double radius_;         // Unit: meter.
00355   double inv_radius_;     // Inverse of radius_
00356   double axle_vel_gain_;  // Axle velocity gain
00357 };
00358 
00359 Joint::Joint(const JointHandle& handle,
00360              const shared_ptr<const urdf::Joint> urdf_joint) :
00361   handle_(handle), is_continuous_(urdf_joint->type == urdf::Joint::CONTINUOUS),
00362   lower_limit_(urdf_joint->limits->lower),
00363   upper_limit_(urdf_joint->limits->upper)
00364 {
00365   // Do nothing.
00366 }
00367 
00368 bool Joint::isValidPos(const double pos) const
00369 {
00370   if (is_continuous_)
00371     return true;
00372   return pos >= lower_limit_ && pos <= upper_limit_;
00373 }
00374 
00375 // Initialize this joint.
00376 void PosJoint::init()
00377 {
00378   pos_ = getPos();
00379   stop();
00380 }
00381 
00382 // Stop this joint's motion.
00383 void PosJoint::stop()
00384 {
00385   handle_.setCommand(getPos());
00386 }
00387 
00388 // Specify this joint's position.
00389 void PosJoint::setPos(const double pos, const Duration& /* period */)
00390 {
00391   pos_ = pos;
00392   handle_.setCommand(pos_);
00393 }
00394 
00395 // Specify this joint's velocity.
00396 void PosJoint::setVel(const double vel, const Duration& period)
00397 {
00398   pos_ += vel * period.toSec();
00399   handle_.setCommand(pos_);
00400 }
00401 
00402 // Stop this joint's motion.
00403 void VelJoint::stop()
00404 {
00405   handle_.setCommand(0);
00406 }
00407 
00408 // Specify this joint's velocity.
00409 void VelJoint::setVel(const double vel, const Duration& /* period */)
00410 {
00411   handle_.setCommand(vel);
00412 }
00413 
00414 PIDJoint::PIDJoint(const JointHandle& handle,
00415                    const shared_ptr<const urdf::Joint> urdf_joint,
00416                    const NodeHandle& ctrlr_nh) :
00417   Joint(handle, urdf_joint), type_(urdf_joint->type)
00418 {
00419   const NodeHandle nh(ctrlr_nh, "pid_gains/" + handle.getName());
00420   if (!pid_ctrlr_.init(nh))
00421   {
00422     throw runtime_error("No PID gain values for \"" + handle.getName() +
00423                         "\" were found.");
00424   }
00425 }
00426 
00427 // Initialize this joint.
00428 void PIDJoint::init()
00429 {
00430   pid_ctrlr_.reset();
00431   stop();
00432 }
00433 
00434 // Stop this joint's motion.
00435 void PIDJoint::stop()
00436 {
00437   // The command passed to setCommand() might be an effort value or a
00438   // velocity. In either case, the correct command to pass here is zero.
00439   handle_.setCommand(0);
00440 }
00441 
00442 // Specify this joint's position.
00443 void PIDJoint::setPos(const double pos, const Duration& period)
00444 {
00445   const double curr_pos = getPos();
00446 
00447   double error;
00448   switch (type_)
00449   {
00450     case urdf::Joint::REVOLUTE:
00451       angles::shortest_angular_distance_with_limits(curr_pos, pos,
00452                                                     lower_limit_, upper_limit_,
00453                                                     error);
00454       break;
00455     case urdf::Joint::CONTINUOUS:
00456       error = angles::shortest_angular_distance(curr_pos, pos);
00457       break;
00458     default:
00459       error = pos - curr_pos;
00460       break;
00461   }
00462 
00463   handle_.setCommand(pid_ctrlr_.computeCommand(error, period));
00464 }
00465 
00466 // Specify this joint's velocity.
00467 void PIDJoint::setVel(const double vel, const Duration& period)
00468 {
00469   const double error = vel - handle_.getVelocity();
00470   handle_.setCommand(pid_ctrlr_.computeCommand(error, period));
00471 }
00472 
00473 Wheel::Wheel(const KDL::Tree& tree,
00474              const string& base_link, const string& steer_link,
00475              const shared_ptr<Joint> steer_joint,
00476              const shared_ptr<Joint> axle_joint,
00477              const double circ)
00478 {
00479   steer_link_ = steer_link;
00480   initPos(tree, base_link);
00481 
00482   steer_joint_ = steer_joint;
00483   axle_joint_ = axle_joint;
00484   theta_steer_ = steer_joint_->getPos();
00485   last_theta_steer_desired_ = theta_steer_;
00486   last_theta_axle_ = axle_joint_->getPos();
00487 
00488   radius_ = circ / (2 * M_PI);
00489   inv_radius_ = 1 / radius_;
00490   axle_vel_gain_ = 0;
00491 }
00492 
00493 // Return the difference between this wheel's current position and its
00494 // position when getDeltaPos() was last called. The returned vector is defined
00495 // in the base link's frame.
00496 Vector2d Wheel::getDeltaPos()
00497 {
00498   const double theta_axle = axle_joint_->getPos();
00499   const double delta_theta_axle = theta_axle - last_theta_axle_;
00500   last_theta_axle_ = theta_axle;
00501   const double vec_mag = delta_theta_axle * radius_;
00502   return Vector2d(cos(theta_steer_), sin(theta_steer_)) * vec_mag;
00503 }
00504 
00505 // Initialize this wheel's steering and axle joints.
00506 void Wheel::initJoints()
00507 {
00508   steer_joint_->init();
00509   axle_joint_->init();
00510 }
00511 
00512 // Stop this wheel's motion.
00513 void Wheel::stop() const
00514 {
00515   steer_joint_->stop();
00516   axle_joint_->stop();
00517 }
00518 
00519 // Maintain the position of this wheel's steering joint. Return a linear speed
00520 // gain value based on the difference between the desired steering angle and
00521 // the actual steering angle.
00522 double Wheel::ctrlSteering(const Duration& period, const double hermite_scale,
00523                            const double hermite_offset)
00524 {
00525   return ctrlSteering(last_theta_steer_desired_, period, hermite_scale,
00526                       hermite_offset);
00527 }
00528 
00529 // Control this wheel's steering joint. theta_desired range: [-pi, pi].
00530 // Return a linear speed gain value based on the difference between the
00531 // desired steering angle and the actual steering angle.
00532 double Wheel::ctrlSteering(const double theta_desired, const Duration& period,
00533                            const double hermite_scale,
00534                            const double hermite_offset)
00535 {
00536   last_theta_steer_desired_ = theta_desired;
00537 
00538   // Find the minimum rotation that will align the wheel with theta_desired.
00539   theta_steer_ = steer_joint_->getPos();
00540   const double theta_diff = fabs(theta_desired - theta_steer_);
00541   double theta;
00542   if (theta_diff > M_PI_2)
00543   {
00544     theta = theta_desired - copysign(M_PI, theta_desired);
00545     axle_vel_gain_ = -1;
00546   }
00547   else
00548   {
00549     theta = theta_desired;
00550     axle_vel_gain_ = 1;
00551   }
00552 
00553   // Keep theta within its valid range.
00554   if (!steer_joint_->isValidPos(theta))
00555   {
00556     theta -= copysign(M_PI, theta);
00557     axle_vel_gain_ = -axle_vel_gain_;
00558   }
00559 
00560   steer_joint_->setPos(theta, period);
00561   return 1 - hermite(hermite_scale * (fabs(theta - theta_steer_) -
00562                                       hermite_offset));
00563 }
00564 
00565 // Control this wheel's axle joint.
00566 void Wheel::ctrlAxle(const double lin_speed, const Duration& period) const
00567 {
00568   const double ang_vel = axle_vel_gain_ * inv_radius_ * lin_speed;
00569   axle_joint_->setVel(ang_vel, period);
00570 }
00571 
00572 // Initialize pos_.
00573 void Wheel::initPos(const KDL::Tree& tree, const string& base_link)
00574 {
00575   KDL::Chain chain;
00576   if (!tree.getChain(base_link, steer_link_, chain))
00577   {
00578     throw runtime_error("No kinematic chain was found from \"" + base_link +
00579                         "\" to \"" + steer_link_ + "\".");
00580   }
00581 
00582   const unsigned int num_joints = chain.getNrOfJoints();
00583   KDL::JntArray joint_positions(num_joints);
00584   for (unsigned int i = 0; i < num_joints; i++)
00585     joint_positions(i) = 0;
00586 
00587   KDL::ChainFkSolverPos_recursive solver(chain);
00588   KDL::Frame frame;
00589   if (solver.JntToCart(joint_positions, frame) < 0)
00590   {
00591     throw runtime_error("The position of steering link \"" + steer_link_ +
00592                         "\" in base link frame \"" + base_link +
00593                         "\" was not found.");
00594   }
00595   pos_ = Vector2d(frame.p.x(), frame.p.y());
00596 }
00597 
00598 // Create an object of class Joint that corresponds to the URDF joint specified
00599 // by joint_name.
00600 shared_ptr<Joint> getJoint(const string& joint_name, const bool is_steer_joint,
00601                            const NodeHandle& ctrlr_nh,
00602                            const urdf::Model& urdf_model,
00603                            EffortJointInterface *const eff_joint_iface,
00604                            PositionJointInterface *const pos_joint_iface,
00605                            VelocityJointInterface *const vel_joint_iface)
00606 {
00607   if (eff_joint_iface != NULL)
00608   {
00609     JointHandle handle;
00610     bool handle_found;
00611     try
00612     {
00613       handle = eff_joint_iface->getHandle(joint_name);
00614       handle_found = true;
00615     }
00616     catch (...)
00617     {
00618       handle_found = false;
00619     }
00620 
00621     if (handle_found)
00622     {
00623       const shared_ptr<const urdf::Joint> urdf_joint =
00624         urdf_model.getJoint(joint_name);
00625       if (urdf_joint == NULL)
00626       {
00627         throw runtime_error("\"" + joint_name +
00628                             "\" was not found in the URDF data.");
00629       }
00630 
00631       shared_ptr<Joint> joint(new PIDJoint(handle, urdf_joint, ctrlr_nh));
00632       return joint;
00633     }
00634   }
00635 
00636   if (pos_joint_iface != NULL)
00637   {
00638     JointHandle handle;
00639     bool handle_found;
00640     try
00641     {
00642       handle = pos_joint_iface->getHandle(joint_name);
00643       handle_found = true;
00644     }
00645     catch (...)
00646     {
00647       handle_found = false;
00648     }
00649 
00650     if (handle_found)
00651     {
00652       const shared_ptr<const urdf::Joint> urdf_joint =
00653         urdf_model.getJoint(joint_name);
00654       if (urdf_joint == NULL)
00655       {
00656         throw runtime_error("\"" + joint_name +
00657                             "\" was not found in the URDF data.");
00658       }
00659 
00660       shared_ptr<Joint> joint(new PosJoint(handle, urdf_joint));
00661       return joint;
00662     }
00663   }
00664 
00665   if (vel_joint_iface != NULL)
00666   {
00667     JointHandle handle;
00668     bool handle_found;
00669     try
00670     {
00671       handle = vel_joint_iface->getHandle(joint_name);
00672       handle_found = true;
00673     }
00674     catch (...)
00675     {
00676       handle_found = false;
00677     }
00678 
00679     if (handle_found)
00680     {
00681       const shared_ptr<const urdf::Joint> urdf_joint =
00682         urdf_model.getJoint(joint_name);
00683       if (urdf_joint == NULL)
00684       {
00685         throw runtime_error("\"" + joint_name +
00686                             "\" was not found in the URDF data.");
00687       }
00688 
00689       if (is_steer_joint)
00690       {
00691         shared_ptr<Joint> joint(new PIDJoint(handle, urdf_joint, ctrlr_nh));
00692         return joint;
00693       }
00694       shared_ptr<Joint> joint(new VelJoint(handle, urdf_joint));
00695       return joint;
00696     }
00697   }
00698 
00699   throw runtime_error("No handle for \"" + joint_name + "\" was found.");
00700 }
00701 
00702 } // namespace
00703 
00704 namespace steered_wheel_base_controller
00705 {
00706 
00707 // Steered-wheel base controller
00708 class SteeredWheelBaseController : public controller_interface::ControllerBase
00709 {
00710 public:
00711   SteeredWheelBaseController();
00712 
00713   // These are not real-time safe.
00714   virtual bool initRequest(RobotHW *const robot_hw,
00715                            NodeHandle& root_nh, NodeHandle& ctrlr_nh,
00716                            set<string>& claimed_resources);
00717   virtual string getHardwareInterfaceType() const;
00718 
00719   // These are real-time safe.
00720   virtual void starting(const Time& time);
00721   virtual void update(const Time& time, const Duration& period);
00722   virtual void stopping(const Time& time);
00723 
00724 private:
00725   struct VelCmd     // Velocity command
00726   {
00727     double x_vel;   // X velocity component. Unit: m/s.
00728     double y_vel;   // Y velocity component. Unit: m/s.
00729     double yaw_vel; // Yaw velocity. Unit: rad/s.
00730 
00731     // last_vel_cmd_time is the time at which the most recent velocity command
00732     // was received.
00733     Time last_vel_cmd_time;
00734   };
00735 
00736   static const string DEF_ROBOT_DESC_NAME;
00737   static const string DEF_BASE_LINK;
00738   static const double DEF_CMD_VEL_TIMEOUT;
00739 
00740   static const double DEF_LIN_SPEED_LIMIT;
00741   static const double DEF_LIN_ACCEL_LIMIT;
00742   static const double DEF_LIN_DECEL_LIMIT;
00743 
00744   static const double DEF_YAW_SPEED_LIMIT;
00745   static const double DEF_YAW_ACCEL_LIMIT;
00746   static const double DEF_YAW_DECEL_LIMIT;
00747 
00748   static const double DEF_FULL_AXLE_SPEED_ANG;
00749   static const double DEF_ZERO_AXLE_SPEED_ANG;
00750 
00751   static const double DEF_WHEEL_DIA_SCALE;
00752 
00753   static const double DEF_ODOM_PUB_FREQ;
00754   static const bool DEF_PUB_ODOM_TO_BASE;
00755   static const string DEF_ODOM_FRAME;
00756   static const string DEF_BASE_FRAME;
00757   static const double DEF_INIT_X;
00758   static const double DEF_INIT_Y;
00759   static const double DEF_INIT_YAW;
00760   static const double DEF_SD;
00761 
00762   static const Vector2d X_DIR;
00763 
00764   void init(EffortJointInterface *const eff_joint_iface,
00765             PositionJointInterface *const pos_joint_iface,
00766             VelocityJointInterface *const vel_joint_iface,
00767             NodeHandle& ctrlr_nh);
00768   void velCmdCB(const TwistConstPtr& vel_cmd);
00769 
00770   Vector2d enforceLinLimits(const Vector2d& desired_vel,
00771                             const double delta_t, const double inv_delta_t);
00772   double enforceYawLimits(const double desired_vel,
00773                           const double delta_t, const double inv_delta_t);
00774   void ctrlWheels(const Vector2d& lin_vel, const double yaw_vel,
00775                   const Duration& period);
00776   void compOdometry(const Time& time, const double inv_delta_t);
00777 
00778   std::vector<Wheel> wheels_;
00779 
00780   // Linear motion limits
00781   bool has_lin_speed_limit_;
00782   double lin_speed_limit_;
00783   bool has_lin_accel_limit_;
00784   double lin_accel_limit_;
00785   bool has_lin_decel_limit_;
00786   double lin_decel_limit_;
00787 
00788   // Yaw limits
00789   bool has_yaw_speed_limit_;
00790   double yaw_speed_limit_;
00791   bool has_yaw_accel_limit_;
00792   double yaw_accel_limit_;
00793   bool has_yaw_decel_limit_;
00794   double yaw_decel_limit_;
00795 
00796   double hermite_scale_, hermite_offset_;
00797 
00798   Vector2d last_lin_vel_; // Last linear velocity. Unit: m/s.
00799   double last_yaw_vel_;   // Last yaw velocity. Unit: rad/s.
00800 
00801   // Velocity command member variables
00802   VelCmd vel_cmd_;
00803   RealtimeBuffer<VelCmd> vel_cmd_buf_;
00804   bool vel_cmd_timeout_enabled_;
00805   Duration vel_cmd_timeout_;
00806   ros::Subscriber vel_cmd_sub_;
00807 
00808   // Odometry
00809   bool comp_odom_;              // Compute odometry
00810   bool pub_odom_to_base_;       // Publish the odometry to base frame transform
00811   Duration odom_pub_period_;    // Odometry publishing period
00812   Affine2d init_odom_to_base_;  // Initial odometry to base frame transform
00813   Affine2d odom_to_base_;       // Odometry to base frame transform
00814   Affine2d odom_rigid_transf_;
00815   // wheel_pos_ contains the positions of the wheel's steering axles.
00816   // The positions are relative to the centroid of the steering axle positions
00817   // in the base link's frame. neg_wheel_centroid is the negative version of
00818   // that centroid.
00819   Eigen::Matrix2Xd wheel_pos_;
00820   Vector2d neg_wheel_centroid_;
00821   Eigen::MatrixX2d new_wheel_pos_;
00822   RealtimePublisher<nav_msgs::Odometry> odom_pub_;
00823   RealtimePublisher<tf::tfMessage> odom_tf_pub_;
00824   Time last_odom_pub_time_, last_odom_tf_pub_time_;
00825 };
00826 
00827 const string SteeredWheelBaseController::DEF_ROBOT_DESC_NAME =
00828   "robot_description";
00829 const string SteeredWheelBaseController::DEF_BASE_LINK = "base_link";
00830 const double SteeredWheelBaseController::DEF_CMD_VEL_TIMEOUT = 0.5;
00831 
00832 const double SteeredWheelBaseController::DEF_LIN_SPEED_LIMIT = 1;
00833 const double SteeredWheelBaseController::DEF_LIN_ACCEL_LIMIT = 1;
00834 const double SteeredWheelBaseController::DEF_LIN_DECEL_LIMIT = -1;
00835 
00836 const double SteeredWheelBaseController::DEF_YAW_SPEED_LIMIT = 1;
00837 const double SteeredWheelBaseController::DEF_YAW_ACCEL_LIMIT = 1;
00838 const double SteeredWheelBaseController::DEF_YAW_DECEL_LIMIT = -1;
00839 
00840 const double SteeredWheelBaseController::DEF_FULL_AXLE_SPEED_ANG = 0.7854;
00841 const double SteeredWheelBaseController::DEF_ZERO_AXLE_SPEED_ANG = 1.5708;
00842 
00843 const double SteeredWheelBaseController::DEF_WHEEL_DIA_SCALE = 1;
00844 
00845 const double SteeredWheelBaseController::DEF_ODOM_PUB_FREQ = 30;
00846 const bool SteeredWheelBaseController::DEF_PUB_ODOM_TO_BASE = true;
00847 const string SteeredWheelBaseController::DEF_ODOM_FRAME = "odom";
00848 const string SteeredWheelBaseController::DEF_BASE_FRAME = "base_link";
00849 const double SteeredWheelBaseController::DEF_INIT_X = 0;
00850 const double SteeredWheelBaseController::DEF_INIT_Y = 0;
00851 const double SteeredWheelBaseController::DEF_INIT_YAW = 0;
00852 const double SteeredWheelBaseController::DEF_SD = 0;
00853 
00854 // X direction
00855 const Vector2d SteeredWheelBaseController::X_DIR = Vector2d::UnitX();
00856 
00857 SteeredWheelBaseController::SteeredWheelBaseController()
00858 {
00859   state_ = CONSTRUCTED;
00860 }
00861 
00862 bool SteeredWheelBaseController::initRequest(RobotHW *const robot_hw,
00863                                              NodeHandle& /* root_nh */,
00864                                              NodeHandle& ctrlr_nh,
00865                                              set<string>& claimed_resources)
00866 {
00867   if (state_ != CONSTRUCTED)
00868   {
00869     ROS_ERROR("The steered-wheel base controller could not be created.");
00870     return false;
00871   }
00872 
00873   EffortJointInterface *const eff_joint_iface =
00874     robot_hw->get<EffortJointInterface>();
00875   PositionJointInterface *const pos_joint_iface =
00876     robot_hw->get<PositionJointInterface>();
00877   VelocityJointInterface *const vel_joint_iface =
00878     robot_hw->get<VelocityJointInterface>();
00879 
00880   if (eff_joint_iface != NULL)
00881     eff_joint_iface->clearClaims();
00882   if (pos_joint_iface != NULL)
00883     pos_joint_iface->clearClaims();
00884   if (vel_joint_iface != NULL)
00885     vel_joint_iface->clearClaims();
00886 
00887   try
00888   {
00889     init(eff_joint_iface, pos_joint_iface, vel_joint_iface, ctrlr_nh);
00890   }
00891   catch (const std::exception& ex)
00892   {
00893     ROS_ERROR_STREAM(ex.what());
00894     return false;
00895   }
00896 
00897   claimed_resources.clear();
00898   addClaimedResources(eff_joint_iface, claimed_resources);
00899   addClaimedResources(pos_joint_iface, claimed_resources);
00900   addClaimedResources(vel_joint_iface, claimed_resources);
00901 
00902   state_ = INITIALIZED;
00903   return true;
00904 }
00905 
00906 string SteeredWheelBaseController::getHardwareInterfaceType() const
00907 {
00908   return "";
00909 }
00910 
00911 void SteeredWheelBaseController::starting(const Time& time)
00912 {
00913   BOOST_FOREACH(Wheel& wheel, wheels_)
00914     wheel.initJoints();
00915 
00916   last_lin_vel_ = Vector2d(0, 0);
00917   last_yaw_vel_ = 0;
00918 
00919   if (comp_odom_)
00920   {
00921     last_odom_pub_time_ = time;
00922     last_odom_tf_pub_time_ = time;
00923   }
00924 
00925   vel_cmd_.x_vel = 0;
00926   vel_cmd_.y_vel = 0;
00927   vel_cmd_.yaw_vel = 0;
00928   vel_cmd_.last_vel_cmd_time = time;
00929   vel_cmd_buf_.initRT(vel_cmd_);
00930 }
00931 
00932 void SteeredWheelBaseController::update(const Time& time,
00933                                         const Duration& period)
00934 {
00935   const double delta_t = period.toSec();
00936   if (delta_t <= 0)
00937     return;
00938 
00939   vel_cmd_ = *(vel_cmd_buf_.readFromRT());
00940   Vector2d desired_lin_vel;
00941   double desired_yaw_vel;
00942   if (!vel_cmd_timeout_enabled_ ||
00943       time - vel_cmd_.last_vel_cmd_time <= vel_cmd_timeout_)
00944   {
00945     desired_lin_vel = Vector2d(vel_cmd_.x_vel, vel_cmd_.y_vel);
00946     desired_yaw_vel = vel_cmd_.yaw_vel;
00947   }
00948   else
00949   {
00950     // Too much time has elapsed since the last velocity command was received.
00951     // Stop the robot.
00952     desired_lin_vel.setZero();
00953     desired_yaw_vel = 0;
00954   }
00955   const double inv_delta_t = 1 / delta_t;
00956 
00957   const Vector2d lin_vel = enforceLinLimits(desired_lin_vel,
00958                                             delta_t, inv_delta_t);
00959   const double yaw_vel = enforceYawLimits(desired_yaw_vel,
00960                                           delta_t, inv_delta_t);
00961   ctrlWheels(lin_vel, yaw_vel, period);
00962   if (comp_odom_)
00963     compOdometry(time, inv_delta_t);
00964 }
00965 
00966 void SteeredWheelBaseController::stopping(const Time& time)
00967 {
00968   BOOST_FOREACH(Wheel& wheel, wheels_)
00969     wheel.stop();
00970 }
00971 
00972 // Initialize this steered-wheel base controller.
00973 void SteeredWheelBaseController::
00974 init(EffortJointInterface *const eff_joint_iface,
00975      PositionJointInterface *const pos_joint_iface,
00976      VelocityJointInterface *const vel_joint_iface,
00977      NodeHandle& ctrlr_nh)
00978 {
00979   string robot_desc_name;
00980   ctrlr_nh.param("robot_description_name", robot_desc_name,
00981                  DEF_ROBOT_DESC_NAME);
00982   urdf::Model urdf_model;
00983   if (!urdf_model.initParam(robot_desc_name))
00984     throw runtime_error("The URDF data was not found.");
00985   KDL::Tree model_tree;
00986   if (!kdl_parser::treeFromUrdfModel(urdf_model, model_tree))
00987     throw runtime_error("The kinematic tree could not be created.");
00988 
00989   string base_link;
00990   ctrlr_nh.param("base_link", base_link, DEF_BASE_LINK);
00991   double timeout;
00992   ctrlr_nh.param("cmd_vel_timeout", timeout, DEF_CMD_VEL_TIMEOUT);
00993   vel_cmd_timeout_enabled_ = timeout > 0;
00994   if (vel_cmd_timeout_enabled_)
00995     vel_cmd_timeout_.fromSec(timeout);
00996 
00997   ctrlr_nh.param("linear_speed_limit", lin_speed_limit_, DEF_LIN_SPEED_LIMIT);
00998   has_lin_speed_limit_ = lin_speed_limit_ >= 0;
00999   ctrlr_nh.param("linear_acceleration_limit", lin_accel_limit_,
01000                  DEF_LIN_ACCEL_LIMIT);
01001   has_lin_accel_limit_ = lin_accel_limit_ >= 0;
01002   // For safety, a valid deceleration limit must be greater than zero.
01003   ctrlr_nh.param("linear_deceleration_limit", lin_decel_limit_,
01004                  DEF_LIN_DECEL_LIMIT);
01005   has_lin_decel_limit_ = lin_decel_limit_ > 0;
01006 
01007   ctrlr_nh.param("yaw_speed_limit", yaw_speed_limit_, DEF_YAW_SPEED_LIMIT);
01008   has_yaw_speed_limit_ = yaw_speed_limit_ >= 0;
01009   ctrlr_nh.param("yaw_acceleration_limit", yaw_accel_limit_,
01010                  DEF_YAW_ACCEL_LIMIT);
01011   has_yaw_accel_limit_ = yaw_accel_limit_ >= 0;
01012   // For safety, a valid deceleration limit must be greater than zero.
01013   ctrlr_nh.param("yaw_deceleration_limit", yaw_decel_limit_,
01014                  DEF_YAW_DECEL_LIMIT);
01015   has_yaw_decel_limit_ = yaw_decel_limit_ > 0;
01016 
01017   ctrlr_nh.param("full_axle_speed_angle", hermite_offset_,
01018                  DEF_FULL_AXLE_SPEED_ANG);
01019   if (hermite_offset_ < 0 || hermite_offset_ > M_PI)
01020     throw runtime_error("full_axle_speed_angle must be in the range [0, pi].");
01021   double zero_axle_speed_ang;
01022   ctrlr_nh.param("zero_axle_speed_angle", zero_axle_speed_ang,
01023                  DEF_ZERO_AXLE_SPEED_ANG);
01024   if (zero_axle_speed_ang < 0 || zero_axle_speed_ang > M_PI)
01025     throw runtime_error("zero_axle_speed_angle must be in the range [0, pi].");
01026   if (hermite_offset_ >= zero_axle_speed_ang)
01027   {
01028     throw runtime_error("full_axle_speed_angle must be less than "
01029                         "zero_axle_speed_angle.");
01030   }
01031   hermite_scale_ = 1 / (zero_axle_speed_ang - hermite_offset_);
01032 
01033   // Wheels
01034 
01035   XmlRpcValue wheel_param_list;
01036   if (!ctrlr_nh.getParam("wheels", wheel_param_list))
01037     throw runtime_error("No wheels were specified.");
01038   if (wheel_param_list.getType() != XmlRpcValue::TypeArray)
01039     throw runtime_error("The specified list of wheels is invalid.");
01040   if (wheel_param_list.size() < 2)
01041     throw runtime_error("At least two wheels must be specified.");
01042 
01043   double wheel_dia_scale;
01044   ctrlr_nh.param("wheel_diameter_scale", wheel_dia_scale, DEF_WHEEL_DIA_SCALE);
01045   if (wheel_dia_scale <= 0)
01046   {
01047     throw runtime_error("The specified wheel diameter scale is less than or "
01048                         "equal to zero.");
01049   }
01050 
01051   for (int i = 0; i < wheel_param_list.size(); i++)
01052   {
01053     XmlRpcValue& wheel_params = wheel_param_list[i];
01054     if (wheel_params.getType() != XmlRpcValue::TypeStruct)
01055       throw runtime_error("The specified list of wheels is invalid.");
01056 
01057     if (!wheel_params.hasMember("steering_joint"))
01058       throw runtime_error("A steering joint was not specified.");
01059     XmlRpcValue& xml_steer_joint = wheel_params["steering_joint"];
01060     if (!xml_steer_joint.valid() ||
01061         xml_steer_joint.getType() != XmlRpcValue::TypeString)
01062     {
01063       throw runtime_error("An invalid steering joint was specified.");
01064     }
01065     const string steer_joint_name = xml_steer_joint;
01066     const shared_ptr<const urdf::Joint> steer_joint =
01067       urdf_model.getJoint(steer_joint_name);
01068     if (steer_joint == NULL)
01069     {
01070       throw runtime_error("Steering joint \"" + steer_joint_name +
01071                           "\" was not found in the URDF data.");
01072     }
01073     const string steer_link = steer_joint->child_link_name;
01074 
01075     if (!wheel_params.hasMember("axle_joint"))
01076       throw runtime_error("An axle joint was not specified.");
01077     XmlRpcValue& xml_axle_joint = wheel_params["axle_joint"];
01078     if (!xml_axle_joint.valid() ||
01079         xml_axle_joint.getType() != XmlRpcValue::TypeString)
01080     {
01081       throw runtime_error("An invalid axle joint was specified.");
01082     }
01083     const string axle_joint_name = xml_axle_joint;
01084 
01085     if (!wheel_params.hasMember("diameter"))
01086       throw runtime_error("A wheel diameter was not specified.");
01087     XmlRpcValue& xml_dia = wheel_params["diameter"];
01088     if (!xml_dia.valid())
01089       throw runtime_error("An invalid wheel diameter was specified.");
01090     double dia;
01091     switch (xml_dia.getType())
01092     {
01093       case XmlRpcValue::TypeInt:
01094         {
01095           const int tmp = xml_dia;
01096           dia = tmp;
01097         }
01098         break;
01099       case XmlRpcValue::TypeDouble:
01100         dia = xml_dia;
01101         break;
01102       default:
01103         throw runtime_error("An invalid wheel diameter was specified.");
01104     }
01105     if (dia <= 0)
01106     {
01107       throw runtime_error("A specified wheel diameter is less than or "
01108                           "equal to zero.");
01109     }
01110     // Circumference
01111     const double circ = (2 * M_PI) * (wheel_dia_scale * dia) / 2;
01112 
01113     wheels_.push_back(Wheel(model_tree, base_link, steer_link,
01114                             getJoint(steer_joint_name, true,
01115                                      ctrlr_nh, urdf_model,
01116                                      eff_joint_iface, pos_joint_iface,
01117                                      vel_joint_iface),
01118                             getJoint(axle_joint_name, false,
01119                                      ctrlr_nh, urdf_model,
01120                                      eff_joint_iface, pos_joint_iface,
01121                                      vel_joint_iface), circ));
01122   }
01123 
01124   // Odometry
01125   double odom_pub_freq;
01126   ctrlr_nh.param("odometry_publishing_frequency", odom_pub_freq,
01127                  DEF_ODOM_PUB_FREQ);
01128   comp_odom_ = odom_pub_freq > 0;
01129   if (comp_odom_)
01130   {
01131     odom_pub_period_ = Duration(1 / odom_pub_freq);
01132     ctrlr_nh.param("publish_odometry_to_base_transform", pub_odom_to_base_,
01133                    DEF_PUB_ODOM_TO_BASE);
01134 
01135     double init_x, init_y, init_yaw;
01136     ctrlr_nh.param("initial_x", init_x, DEF_INIT_X);
01137     ctrlr_nh.param("initial_y", init_y, DEF_INIT_Y);
01138     ctrlr_nh.param("initial_yaw", init_yaw, DEF_INIT_YAW);
01139     double x_sd, y_sd, yaw_sd;
01140     ctrlr_nh.param("x_sd", x_sd, DEF_SD);
01141     ctrlr_nh.param("y_sd", y_sd, DEF_SD);
01142     ctrlr_nh.param("yaw_sd", yaw_sd, DEF_SD);
01143     double x_speed_sd, y_speed_sd, yaw_speed_sd;
01144     ctrlr_nh.param("x_speed_sd", x_speed_sd, DEF_SD);
01145     ctrlr_nh.param("y_speed_sd", y_speed_sd, DEF_SD);
01146     ctrlr_nh.param("yaw_speed_sd", yaw_speed_sd, DEF_SD);
01147 
01148     init_odom_to_base_.setIdentity();
01149     init_odom_to_base_.rotate(clamp(init_yaw, -M_PI, M_PI));
01150     init_odom_to_base_.translation() = Vector2d(init_x, init_y);
01151     odom_to_base_ = init_odom_to_base_;
01152     odom_rigid_transf_.setIdentity();
01153 
01154     wheel_pos_.resize(2, wheels_.size());
01155     for (size_t col = 0; col < wheels_.size(); col++)
01156       wheel_pos_.col(col) = wheels_[col].pos();
01157     const Vector2d centroid = wheel_pos_.rowwise().mean();
01158     wheel_pos_.colwise() -= centroid;
01159     neg_wheel_centroid_ = -centroid;
01160     new_wheel_pos_.resize(wheels_.size(), 2);
01161 
01162     string odom_frame, base_frame;
01163     ctrlr_nh.param("odometry_frame", odom_frame, DEF_ODOM_FRAME);
01164     ctrlr_nh.param("base_frame", base_frame, DEF_BASE_FRAME);
01165 
01166     odom_pub_.msg_.header.frame_id = odom_frame;
01167     odom_pub_.msg_.child_frame_id = base_frame;
01168 
01169     odom_pub_.msg_.pose.pose.position.z = 0;
01170 
01171     odom_pub_.msg_.pose.covariance.assign(0);
01172     odom_pub_.msg_.pose.covariance[0] = x_sd * x_sd;
01173     odom_pub_.msg_.pose.covariance[7] = y_sd * y_sd;
01174     odom_pub_.msg_.pose.covariance[35] = yaw_sd * yaw_sd;
01175 
01176     odom_pub_.msg_.twist.twist.linear.z = 0;
01177     odom_pub_.msg_.twist.twist.angular.x = 0;
01178     odom_pub_.msg_.twist.twist.angular.y = 0;
01179 
01180     odom_pub_.msg_.twist.covariance.assign(0);
01181     odom_pub_.msg_.twist.covariance[0] = x_speed_sd * x_speed_sd;
01182     odom_pub_.msg_.twist.covariance[7] = y_speed_sd * y_speed_sd;
01183     odom_pub_.msg_.twist.covariance[35] = yaw_speed_sd * yaw_speed_sd;
01184 
01185     odom_pub_.init(ctrlr_nh, "odom", 1);
01186 
01187     if (pub_odom_to_base_)
01188     {
01189       odom_tf_pub_.msg_.transforms.resize(1);
01190       geometry_msgs::TransformStamped& odom_tf_trans =
01191         odom_tf_pub_.msg_.transforms[0];
01192       odom_tf_trans.header.frame_id = odom_pub_.msg_.header.frame_id;
01193       odom_tf_trans.child_frame_id = odom_pub_.msg_.child_frame_id;
01194       odom_tf_trans.transform.translation.z = 0;
01195       odom_tf_pub_.init(ctrlr_nh, "/tf", 1);
01196     }
01197   }
01198 
01199   vel_cmd_sub_ = ctrlr_nh.subscribe("cmd_vel", 1,
01200                                     &SteeredWheelBaseController::velCmdCB,
01201                                     this);
01202 }
01203 
01204 // Velocity command callback
01205 void SteeredWheelBaseController::velCmdCB(const TwistConstPtr& vel_cmd)
01206 {
01207   vel_cmd_.x_vel = vel_cmd->linear.x;
01208   vel_cmd_.y_vel = vel_cmd->linear.y;
01209   vel_cmd_.yaw_vel = vel_cmd->angular.z;
01210   vel_cmd_.last_vel_cmd_time = Time::now();
01211   vel_cmd_buf_.writeFromNonRT(vel_cmd_);
01212 }
01213 
01214 // Enforce linear motion limits.
01215 Vector2d SteeredWheelBaseController::
01216 enforceLinLimits(const Vector2d& desired_vel,
01217                  const double delta_t, const double inv_delta_t)
01218 {
01219   Vector2d vel = desired_vel;
01220   if (has_lin_speed_limit_)
01221   {
01222     const double vel_mag = vel.norm();
01223     if (vel_mag > lin_speed_limit_)
01224       vel = (vel / vel_mag) * lin_speed_limit_;
01225   }
01226 
01227   Vector2d accel = (vel - last_lin_vel_) * inv_delta_t;
01228 
01229   if (accel.dot(last_lin_vel_) >= 0)
01230   {
01231     // Acceleration
01232 
01233     if (has_lin_accel_limit_)
01234     {
01235       const double accel_mag = accel.norm();
01236       if (accel_mag > lin_accel_limit_)
01237       {
01238         accel = (accel / accel_mag) * lin_accel_limit_;
01239         vel = last_lin_vel_ + accel * delta_t;
01240       }
01241     }
01242   }
01243   else
01244   {
01245     // Deceleration
01246 
01247     if (has_lin_decel_limit_)
01248     {
01249       const double accel_mag = accel.norm();
01250       if (accel_mag > lin_decel_limit_)
01251       {
01252         accel = (accel / accel_mag) * lin_decel_limit_;
01253         vel = last_lin_vel_ + accel * delta_t;
01254       }
01255     }
01256     if (vel.dot(last_lin_vel_) < 0)
01257       vel = Vector2d(0, 0);
01258   }
01259 
01260   last_lin_vel_ = vel;
01261   return vel;
01262 }
01263 
01264 double SteeredWheelBaseController::enforceYawLimits(const double desired_vel,
01265                                                     const double delta_t,
01266                                                     const double inv_delta_t)
01267 {
01268   double vel = desired_vel;
01269   if (has_yaw_speed_limit_)
01270     vel = clamp(vel, -yaw_speed_limit_, yaw_speed_limit_);
01271 
01272   double accel = (vel - last_yaw_vel_) * inv_delta_t;
01273 
01274   const double accel_sign = sign(accel);
01275   const double last_yaw_vel_sign = sign(last_yaw_vel_);
01276   if (accel_sign == last_yaw_vel_sign || last_yaw_vel_sign == 0)
01277   {
01278     // Acceleration
01279 
01280     if (has_yaw_accel_limit_ && fabs(accel) > yaw_accel_limit_)
01281     {
01282       accel = accel_sign * yaw_accel_limit_;
01283       vel = last_yaw_vel_ + accel * delta_t;
01284     }
01285   }
01286   else
01287   {
01288     // Deceleration
01289 
01290     if (has_yaw_decel_limit_ && fabs(accel) > yaw_decel_limit_)
01291     {
01292       accel = accel_sign * yaw_decel_limit_;
01293       vel = last_yaw_vel_ + accel * delta_t;
01294     }
01295     if (sign(vel) != last_yaw_vel_sign)
01296       vel = 0;
01297   }
01298 
01299   last_yaw_vel_ = vel;
01300   return vel;
01301 }
01302 
01303 // Control the wheels.
01304 void SteeredWheelBaseController::ctrlWheels(const Vector2d& lin_vel,
01305                                             const double yaw_vel,
01306                                             const Duration& period)
01307 {
01308   const double lin_speed = lin_vel.norm();
01309 
01310   if (yaw_vel == 0)
01311   {
01312     if (lin_speed > 0)
01313     {
01314       // Point the wheels in the same direction.
01315 
01316       const Vector2d dir = lin_vel / lin_speed;
01317       const double theta =
01318         copysign(acos(dir.dot(SteeredWheelBaseController::X_DIR)), dir.y());
01319 
01320       double min_speed_gain = 1;
01321       BOOST_FOREACH(Wheel& wheel, wheels_)
01322       {
01323         const double speed_gain =
01324           wheel.ctrlSteering(theta, period, hermite_scale_, hermite_offset_);
01325         if (speed_gain < min_speed_gain)
01326           min_speed_gain = speed_gain;
01327       }
01328       const double lin_speed_2 = min_speed_gain * lin_speed;
01329       BOOST_FOREACH(Wheel& wheel, wheels_)
01330       {
01331         wheel.ctrlAxle(lin_speed_2, period);
01332       }
01333     }
01334     else
01335     {
01336       // Stop wheel rotation.
01337       BOOST_FOREACH(Wheel& wheel, wheels_)
01338       {
01339         wheel.ctrlSteering(period, hermite_scale_, hermite_offset_);
01340         wheel.ctrlAxle(0, period);
01341       }
01342     }
01343   }
01344   else  // The yaw velocity is nonzero.
01345   {
01346     // Align the wheels so that they are tangent to circles centered
01347     // at "center".
01348 
01349     Vector2d center;
01350     if (lin_speed > 0)
01351     {
01352       const Vector2d dir = lin_vel / lin_speed;
01353       center = Vector2d(-dir.y(), dir.x()) * lin_speed / yaw_vel;
01354     }
01355     else
01356     {
01357       center.setZero();
01358     }
01359 
01360     std::vector<double> radii;
01361     double min_speed_gain = 1;
01362     BOOST_FOREACH(Wheel& wheel, wheels_)
01363     {
01364       Vector2d vec = wheel.pos();
01365       vec -= center;
01366       const double radius = vec.norm();
01367       radii.push_back(radius);
01368       double theta;
01369       if (radius > 0)
01370       {
01371         vec /= radius;
01372         theta =
01373           copysign(acos(vec.dot(SteeredWheelBaseController::X_DIR)), vec.y()) +
01374           M_PI_2;
01375       }
01376       else
01377       {
01378         theta = 0;
01379       }
01380                         
01381       const double speed_gain =
01382         wheel.ctrlSteering(theta, period, hermite_scale_, hermite_offset_);
01383       if (speed_gain < min_speed_gain)
01384         min_speed_gain = speed_gain;
01385     }
01386 
01387     const double lin_speed_gain = min_speed_gain * yaw_vel;
01388     size_t i = 0;
01389     BOOST_FOREACH(Wheel& wheel, wheels_)
01390     {
01391       wheel.ctrlAxle(lin_speed_gain * radii[i++], period);
01392     }
01393   }
01394 }
01395 
01396 // Compute odometry.
01397 void SteeredWheelBaseController::compOdometry(const Time& time,
01398                                               const double inv_delta_t)
01399 {
01400   // Compute the rigid transform from wheel_pos_ to new_wheel_pos_.
01401 
01402   for (size_t row = 0; row < wheels_.size(); row++)
01403     new_wheel_pos_.row(row) = wheels_[row].pos() + wheels_[row].getDeltaPos();
01404   const Eigen::RowVector2d new_wheel_centroid =
01405     new_wheel_pos_.colwise().mean();
01406   new_wheel_pos_.rowwise() -= new_wheel_centroid;
01407 
01408   const Matrix2d h = wheel_pos_ * new_wheel_pos_;
01409   const Eigen::JacobiSVD<Matrix2d> svd(h, Eigen::ComputeFullU |
01410                                        Eigen::ComputeFullV);
01411   Matrix2d rot = svd.matrixV() * svd.matrixU().transpose();
01412   if (rot.determinant() < 0)
01413     rot.col(1) *= -1;
01414 
01415   odom_rigid_transf_.matrix().block(0, 0, 2, 2) = rot;
01416   odom_rigid_transf_.translation() =
01417     rot * neg_wheel_centroid_ + new_wheel_centroid.transpose();
01418   odom_to_base_ = odom_to_base_ * odom_rigid_transf_;
01419 
01420   const double odom_x = odom_to_base_.translation().x();
01421   const double odom_y = odom_to_base_.translation().y();
01422   const double odom_yaw = atan2(odom_to_base_(1, 0), odom_to_base_(0, 0));
01423 
01424   // Publish the odometry.
01425 
01426   geometry_msgs::Quaternion orientation;
01427   bool orientation_comped = false;
01428 
01429   // tf
01430   if (pub_odom_to_base_ && time - last_odom_tf_pub_time_ >= odom_pub_period_ &&
01431       odom_tf_pub_.trylock())
01432   {
01433     orientation = tf::createQuaternionMsgFromYaw(odom_yaw);
01434     orientation_comped = true;
01435 
01436     geometry_msgs::TransformStamped& odom_tf_trans =
01437       odom_tf_pub_.msg_.transforms[0];
01438     odom_tf_trans.header.stamp = time;
01439     odom_tf_trans.transform.translation.x = odom_x;
01440     odom_tf_trans.transform.translation.y = odom_y;
01441     odom_tf_trans.transform.rotation = orientation;
01442 
01443     odom_tf_pub_.unlockAndPublish();
01444     last_odom_tf_pub_time_ = time;
01445   }
01446 
01447   // odom
01448   if (time - last_odom_pub_time_ >= odom_pub_period_ && odom_pub_.trylock())
01449   {
01450     if (!orientation_comped)
01451       orientation = tf::createQuaternionMsgFromYaw(odom_yaw);
01452 
01453     odom_pub_.msg_.header.stamp = time;
01454     odom_pub_.msg_.pose.pose.position.x = odom_x;
01455     odom_pub_.msg_.pose.pose.position.y = odom_y;
01456     odom_pub_.msg_.pose.pose.orientation = orientation;
01457 
01458     odom_pub_.msg_.twist.twist.linear.x =
01459       odom_rigid_transf_.translation().x() * inv_delta_t;
01460     odom_pub_.msg_.twist.twist.linear.y =
01461       odom_rigid_transf_.translation().y() * inv_delta_t;
01462     odom_pub_.msg_.twist.twist.angular.z =
01463       atan2(odom_rigid_transf_(1, 0), odom_rigid_transf_(0, 0)) * inv_delta_t;
01464 
01465     odom_pub_.unlockAndPublish();
01466     last_odom_pub_time_ = time;
01467   }
01468 }
01469 
01470 } // namespace steered_wheel_base_controller
01471 
01472 PLUGINLIB_EXPORT_CLASS(steered_wheel_base_controller::\
01473 SteeredWheelBaseController, controller_interface::ControllerBase)


steered_wheel_base_controller
Author(s): Jim Rothrock
autogenerated on Wed Sep 2 2015 11:47:12