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 ackermann_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
00050 bool update(double front_wheel_angular_pos, double front_wheel_angular_vel,
00051 double rear_wheel_angular_pos, double rear_wheel_angular_vel,
00052 double front_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
00093 double getLinear() const
00094 {
00095 return linear_;
00096 }
00097
00102 double getAngular() const
00103 {
00104 return angular_;
00105 }
00106
00114 void setWheelParams(double track, double front_wheel_radius, double rear_wheel_radius, double wheel_base);
00115
00120 void setVelocityRollingWindowSize(size_t velocity_rolling_window_size);
00121
00122 private:
00123
00125 typedef bacc::accumulator_set<double, bacc::stats<bacc::tag::rolling_mean> > RollingMeanAcc;
00126 typedef bacc::tag::rolling_window RollingWindow;
00127
00133 void integrateRungeKutta2(double linear, double angular);
00134
00140 void integrateExact(double linear, double angular);
00141
00145 void resetAccumulators();
00146
00148 ros::Time timestamp_, last_update_timestamp_;
00149
00151 double x_;
00152 double y_;
00153 double heading_;
00154
00156 double linear_;
00157 double angular_;
00158
00160 double track_;
00161 double front_wheel_radius_, rear_wheel_radius_;
00162 double wheel_base_;
00163
00165 double left_wheel_old_pos_;
00166 double right_wheel_old_pos_;
00167 double wheel_old_pos_;
00168
00170 size_t velocity_rolling_window_size_;
00171 RollingMeanAcc linear_acc_;
00172 RollingMeanAcc angular_acc_;
00173 };
00174 }
00175
00176 #endif