odometry.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: Enrique Fernández
00037  */
00038 
00039 #include <diff_drive_controller/odometry.h>
00040 
00041 #include <angles/angles.h>
00042 #include <boost/bind.hpp>
00043 
00044 namespace diff_drive_controller
00045 {
00046   namespace bacc = boost::accumulators;
00047 
00048   Odometry::Odometry(size_t velocity_rolling_window_size)
00049   : timestamp_(0.0),
00050     x_(0.0),
00051     y_(0.0),
00052     heading_(0.0),
00053     wheel_separation_(0.0),
00054     wheel_radius_(0.0),
00055     left_wheel_old_pos_(0.0),
00056     right_wheel_old_pos_(0.0),
00057     linear_acc_(RollingWindow::window_size = velocity_rolling_window_size),
00058     angular_acc_(RollingWindow::window_size = velocity_rolling_window_size),
00059     integrate_fun_(boost::bind(&Odometry::integrateExact, this, _1, _2))
00060   {
00061   }
00062 
00063   bool Odometry::update(double left_pos, double right_pos, const ros::Time &time)
00064   {
00066     const double left_wheel_cur_pos  = left_pos  * wheel_radius_;
00067     const double right_wheel_cur_pos = right_pos * wheel_radius_;
00068 
00070     const double left_wheel_est_vel  = left_wheel_cur_pos  - left_wheel_old_pos_;
00071     const double right_wheel_est_vel = right_wheel_cur_pos - right_wheel_old_pos_;
00072 
00074     left_wheel_old_pos_  = left_wheel_cur_pos;
00075     right_wheel_old_pos_ = right_wheel_cur_pos;
00076 
00078     const double linear  = (right_wheel_est_vel + left_wheel_est_vel) * 0.5 ;
00079     const double angular = (right_wheel_est_vel - left_wheel_est_vel) / wheel_separation_;
00080 
00082     integrate_fun_(linear, angular);
00083 
00085     const double dt = (time - timestamp_).toSec();
00086     if(dt < 0.0001)
00087       return false; // Interval too small to integrate with
00088 
00089     timestamp_ = time;
00090 
00092     linear_acc_(linear/dt);
00093     angular_acc_(angular/dt);
00094 
00095     return true;
00096   }
00097 
00098   double Odometry::getLinearEstimated() const
00099   {
00100     return bacc::rolling_mean(linear_acc_);
00101   }
00102 
00103   double Odometry::getAngularEstimated() const
00104   {
00105     return bacc::rolling_mean(angular_acc_);
00106   }
00107 
00108   void Odometry::setWheelParams(double wheel_separation, double wheel_radius)
00109   {
00110     wheel_separation_ = wheel_separation;
00111     wheel_radius_     = wheel_radius;
00112   }
00113 
00114   void Odometry::integrateRungeKutta2(double linear, double angular)
00115   {
00116     double direction = heading_ + angular*0.5;
00117 
00119     x_       += linear * cos(direction);
00120     y_       += linear * sin(direction);
00121     heading_ += angular;
00122 
00124     heading_ = angles::normalize_angle(heading_);
00125   }
00126 
00132   void Odometry::integrateExact(double linear, double angular)
00133   {
00134     if(fabs(angular) < 10e-3)
00135       integrateRungeKutta2(linear, angular);
00136     else
00137     {
00139       const double thetaOld = heading_;
00140       const double r = linear/angular;
00141       heading_ += angular;
00142       x_ +=  r * (sin(heading_) - sin(thetaOld));
00143       y_ += -r * (cos(heading_) - cos(thetaOld));
00144     }
00145   }
00146 
00147 } // namespace diff_drive_controller


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