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 #include <nav_msgs/Odometry.h>
00019
00020 #ifndef COB_ODOMETRY_TRACKER_H
00021 #define COB_ODOMETRY_TRACKER_H
00022
00023 class OdometryTracker{
00024 nav_msgs::Odometry odom_;
00025 double theta_rob_rad_;
00026 public:
00027 OdometryTracker(const std::string &from = "odom", const std::string &to = "base_footprint" , double cov_pose = 0.1, double cov_twist = 0.1) {
00028 odom_.header.frame_id = from;
00029 odom_.child_frame_id = to;
00030 for(int i = 0; i < 6; i++){
00031 odom_.pose.covariance[i*6+i] = cov_pose;
00032 odom_.twist.covariance[6*i+i] = cov_twist;
00033 }
00034
00035
00036
00037
00038 init(ros::Time::now());
00039 }
00040 void init(const ros::Time &now){
00041 theta_rob_rad_ = 0;
00042
00043 odom_.header.stamp = now;
00044
00045 odom_.twist.twist.linear.x = 0;
00046 odom_.twist.twist.linear.y = 0;
00047 odom_.twist.twist.angular.z = 0;
00048
00049 odom_.pose.pose.position.x = 0;
00050 odom_.pose.pose.position.y = 0;
00051 odom_.pose.pose.orientation = tf::createQuaternionMsgFromYaw(theta_rob_rad_);
00052
00053 }
00054 const nav_msgs::Odometry &getOdometry(){
00055 return odom_;
00056 }
00057 void track(const ros::Time &now, double dt, double vel_x, double vel_y, double vel_theta){
00058
00059
00060 if(dt > 0){
00061 odom_.header.stamp = now;
00062
00063 double vel_x_mid = (vel_x+odom_.twist.twist.linear.x)/2.0;
00064 double vel_y_mid = (vel_y+odom_.twist.twist.linear.y)/2.0;
00065
00066 double sin_theta = sin(theta_rob_rad_);
00067 double cos_theta = cos(theta_rob_rad_);
00068 theta_rob_rad_ += vel_theta * dt;
00069
00070 odom_.pose.pose.position.x += (vel_x_mid * cos_theta - vel_y_mid * sin_theta) * dt;
00071 odom_.pose.pose.position.y += (vel_x_mid * sin_theta + vel_y_mid * cos_theta) * dt;
00072 odom_.pose.pose.orientation = tf::createQuaternionMsgFromYaw(theta_rob_rad_);
00073
00074 odom_.twist.twist.linear.x = vel_x;
00075 odom_.twist.twist.linear.y = vel_y;
00076 odom_.twist.twist.angular.z = vel_theta;
00077 }
00078 }
00079 };
00080
00081
00082 #endif