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: Luca Marchionni
00037  * Author: Bence Magyar
00038  * Author: Enrique Fernández
00039  * Author: Paul Mathieu
00040  */
00041 
00042 #include <mecanum_drive_controller/odometry.h>
00043 
00044 #include <tf/transform_datatypes.h>
00045 
00046 #include <boost/bind.hpp>
00047 
00048 namespace mecanum_drive_controller
00049 {
00050 
00051 namespace bacc = boost::accumulators;
00052 
00054 Odometry::Odometry(size_t velocity_rolling_window_size)
00055 : timestamp_(0.0)
00056 , x_(0.0)
00057 , y_(0.0)
00058 , heading_(0.0)
00059 , linearX_(0.0)
00060 , linearY_(0.0)
00061 , angular_(0.0)
00062 , wheels_k_(0.0)
00063 , wheels_radius_(0.0)
00064 , velocity_rolling_window_size_(velocity_rolling_window_size)
00065 , linearX_acc_(RollingWindow::window_size = velocity_rolling_window_size)
00066 , linearY_acc_(RollingWindow::window_size = velocity_rolling_window_size)
00067 , angular_acc_(RollingWindow::window_size = velocity_rolling_window_size)
00068 , integrate_fun_(boost::bind(&Odometry::integrateExact, this, _1, _2, _3))
00069 {
00070 }
00071 
00073 void Odometry::init(const ros::Time& time)
00074 {
00075   // Reset accumulators:
00076   linearX_acc_ = RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_);
00077   linearY_acc_ = RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_);
00078   angular_acc_ = RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_);
00079 
00080   // Reset timestamp:
00081   timestamp_ = time;
00082 }
00083 
00085 bool Odometry::update(double wheel0_vel, double wheel1_vel, double wheel2_vel, double wheel3_vel, const ros::Time &time)
00086 {
00088   const double dt = (time - timestamp_).toSec();
00089   if (dt < 0.0001)
00090     return false; // Interval too small to integrate with
00091 
00092   timestamp_ = time;
00093 
00099   linearX_ = 0.25 * wheels_radius_              * ( wheel0_vel + wheel1_vel + wheel2_vel + wheel3_vel);
00100   linearY_ = 0.25 * wheels_radius_              * (-wheel0_vel + wheel1_vel - wheel2_vel + wheel3_vel);
00101   angular_ = 0.25 * wheels_radius_  / wheels_k_ * (-wheel0_vel - wheel1_vel + wheel2_vel + wheel3_vel);
00102 
00104   integrate_fun_(linearX_ * dt, linearY_ * dt, angular_ * dt);
00105 
00106   return true;
00107 }
00108 
00110 void Odometry::updateOpenLoop(double linearX, double linearY, double angular, const ros::Time &time)
00111 {
00113   linearX_ = linearX;
00114   linearY_ = linearY;
00115   angular_ = angular;
00116 
00118   const double dt = (time - timestamp_).toSec();
00119   timestamp_ = time;
00120   integrate_fun_(linearX * dt, linearY * dt, angular * dt);
00121 }
00122 
00124 void Odometry::setWheelsParams(double wheels_k, double wheels_radius)
00125 {
00126   wheels_k_ = wheels_k;
00127 
00128   wheels_radius_ = wheels_radius;
00129 }
00130 
00132 void Odometry::integrateExact(double linearX, double linearY, double angular)
00133 {
00135   heading_ += angular;
00136 
00139   tf::Matrix3x3 R_m_odom = tf::Matrix3x3(tf::createQuaternionFromYaw(heading_));
00140   tf::Vector3 vel_inOdom = R_m_odom * tf::Vector3(linearX, linearY, 0.0);
00141 
00143   x_ += vel_inOdom.x();
00144   y_ += vel_inOdom.y();
00145 }
00146 
00147 } // namespace mecanum_drive_controller


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