odometry.h
Go to the documentation of this file.
00001 
00002 #ifndef ODOMETRY_H_
00003 #define ODOMETRY_H_
00004 
00005 #include <ros/time.h>
00006 #include <boost/accumulators/accumulators.hpp>
00007 #include <boost/accumulators/statistics/stats.hpp>
00008 #include <boost/accumulators/statistics/rolling_mean.hpp>
00009 #include <boost/function.hpp>
00010 
00011 namespace four_wheel_steering_controller
00012 {
00013   namespace bacc = boost::accumulators;
00014 
00019   class Odometry
00020   {
00021   public:
00022 
00024     typedef boost::function<void(double, double)> IntegrationFunction;
00025 
00032     Odometry(size_t velocity_rolling_window_size = 10);
00033 
00038     void init(const ros::Time &time);
00039 
00051     bool update(const double& fl_speed, const double& fr_speed, const double& rl_speed, const double& rr_speed,
00052                 double front_steering, double rear_steering, const ros::Time &time);
00053 
00060     void updateOpenLoop(double linear, double angular, const ros::Time &time);
00061 
00066     double getHeading() const
00067     {
00068       return heading_;
00069     }
00070 
00075     double getX() const
00076     {
00077       return x_;
00078     }
00079 
00084     double getY() const
00085     {
00086       return y_;
00087     }
00088 
00089 
00094     double getLinear() const
00095     {
00096       return linear_;
00097     }
00098 
00103     double getLinearX() const
00104     {
00105       return linear_x_;
00106     }
00107 
00112     double getLinearY() const
00113     {
00114       return linear_y_;
00115     }
00116 
00121     double getAngular() const
00122     {
00123       return angular_;
00124     }
00125 
00132     void setWheelParams(double track, double wheel_radius, double wheel_base);
00133 
00138     void setVelocityRollingWindowSize(size_t velocity_rolling_window_size);
00139 
00140   private:
00141 
00143     typedef bacc::accumulator_set<double, bacc::stats<bacc::tag::rolling_mean> > RollingMeanAcc;
00144     typedef bacc::tag::rolling_window RollingWindow;
00145 
00152     void integrateXY(double linear_x, double linear_y, double angular);
00153 
00159     void integrateRungeKutta2(double linear, double angular);
00160 
00166     void integrateExact(double linear, double angular);
00167 
00171     void resetAccumulators();
00172 
00174     ros::Time timestamp_, last_update_timestamp_;
00175 
00177     double x_;        //   [m]
00178     double y_;        //   [m]
00179     double heading_;  // [rad]
00180 
00182     double linear_, linear_x_, linear_y_;  //   [m/s]
00183     double angular_; // [rad/s]
00184 
00186     double track_;
00187     double wheel_radius_;
00188     double wheel_base_;
00189 
00191     double wheel_old_pos_;
00192 
00194     size_t velocity_rolling_window_size_;
00195     RollingMeanAcc linear_acc_;
00196     RollingMeanAcc angular_acc_;
00197   };
00198 }
00199 
00200 #endif /* ODOMETRY_H_ */


four_wheel_steering_controller
Author(s): Vincent Rousseau
autogenerated on Sat Jun 8 2019 20:06:24