00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00033 #include "odometry.h"
00034 #include <sensor_msgs/Imu.h>
00035 #include "geometry_msgs/Vector3Stamped.h"
00036 #include "geometry_msgs/QuaternionStamped.h"
00037 #include "geometry_msgs/Pose.h"
00038 #include <sensor_msgs/JointState.h>
00039 
00040 #include "geometry_msgs/Pose.h"
00041 #include "geometry_msgs/Quaternion.h"
00042 #include "tf/transform_datatypes.h"
00043 
00044 
00045 #include <stdio.h>
00046 #include <fstream>
00047 #include <iostream>
00048 
00049 
00050 #define PFLN {printf("%s %d\n",__FILE__, __LINE__);}
00051 bool new_status_message;
00052 atlascar_base::AtlascarStatus base_status;
00053 atlascar_base::AtlascarVelocityStatus base_velocity;
00054 bool message_receive=false;
00055 bool bool_init=true;
00056 ros::Time t_i, t_i_1;
00057 int contador_=0,contador_1=0;
00058 
00059 void VelocityMessageHandler(const atlascar_base::AtlascarVelocityStatus& msg)
00060 {
00061         base_velocity=msg;
00062        new_status_message=true;
00063        if(bool_init)
00064        {
00065               t_i_1=msg.header.stamp;
00066               t_i=msg.header.stamp;
00067               bool_init=false;
00068        }else
00069        {
00070               t_i_1=t_i;
00071               t_i=msg.header.stamp;
00072       }
00073 }
00074 void StatusMessageHandler(const atlascar_base::AtlascarStatus& msg)
00075 {
00076        base_status=msg;
00077 }
00078 
00079 int main(int argc, char** argv)
00080 {
00081        ros::init(argc, argv, "atlascar_odometry");
00082        ros::NodeHandle n;
00083        ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("/vhc/odometry", 50);
00084 
00085        tf::TransformBroadcaster odom_broadcaster;
00086 
00087 
00088        Subscriber subscribeStatusMessages = n.subscribe ("/vhc/plc/status", 1, StatusMessageHandler);
00089        Subscriber subscribeVelocityStatusMessages = n.subscribe ("/vhc/velocity/status", 1, VelocityMessageHandler);
00090 
00091 
00092        double x = 0.0;
00093        double y = 0.0;
00094        double yaw = 0.0;
00095 
00096        double vx = 0.0;
00097        double vy = 0.0;
00098        double vth = 0.0;
00099 
00100        double vl,phi;
00101        double l;
00102 
00103        n.param("wheel_base",l,DEFAULT_WHEEL_BASE);
00104        
00105        new_status_message=false;
00106 
00107        ros::Rate r(20.0);
00108 
00109        ROS_INFO("Starting to spin ...");
00110 
00111        
00112        non_holonomic_ekfilter filter;
00113 
00114        Vector z_i(2);
00115        Vector u(0);
00116        filter.SetWheelBase(l);
00117 
00118        nav_msgs::Odometry odom;
00119 
00120            double phi_tmp=0;
00121            
00122        while(n.ok())
00123        {
00124               spinOnce();   
00125               r.sleep();
00126 
00127               if(!new_status_message)
00128                      continue;
00129 
00130               new_status_message=false;
00131               message_receive=false;
00132 
00133               
00134               vl=base_velocity.velocity;
00135               phi=base_status.steering_wheel;
00136 
00137               
00138               if (phi ==0)
00139                      phi=phi_tmp;
00140               else
00141                      phi_tmp=phi;   
00142               
00143               
00144           phi= phi +0.28801; 
00145 
00146                 if (phi <=0)
00147                 {
00148                         phi = phi*0.766;
00149                         phi=phi*-1;
00150                 }
00151                 else if (phi>0)
00152                 {
00153                         phi= phi*0.770;
00154                         phi=phi*-1;
00155                 }
00156                 
00157                 double w=1.27;
00158                 double instant_radious=fabs(l/tan(phi));
00159                 double v_corrected;
00160                 if(phi>=0)
00161                          v_corrected=vl*(instant_radious/(instant_radious-w/2));
00162                 else    
00163                         
00164                          v_corrected=vl*(instant_radious/(instant_radious+w/2));
00165               
00166               z_i(1)=v_corrected;
00167               z_i(2)=phi;
00168 
00169 
00170 
00171               
00172               double dt = (t_i - t_i_1).toSec();
00173               double delta_x;
00174               double delta_y;
00175               double delta_yaw;
00176 
00177              
00178                 delta_x=cos(yaw)*cos(phi)*v_corrected*dt;
00179                 delta_y=sin(yaw)*cos(phi)*v_corrected*dt;
00180                 
00181                 delta_yaw=sin(phi)*v_corrected*dt/l;
00182 
00183               
00184               x += delta_x;
00185               y += delta_y;
00186               yaw += delta_yaw;
00187 
00188 
00189               
00190               filter.SetTimeInterval(dt);
00191               filter.step(u,z_i);
00192 
00193               Vector x_estimated=filter.getX();
00194               Matrix covariance_matrix =filter.calculateP();
00195               
00196 
00197               
00198               geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(x_estimated(3));
00199 
00200 
00201 
00202 
00203 
00204 
00205 
00206 
00207 
00208 
00209 
00210 
00211 
00212                               
00213 
00214               
00215               
00216 
00217 
00218               
00219               nav_msgs::Odometry odom;
00220               odom.header.stamp =t_i;
00221               odom.header.frame_id = "/world";
00222 
00223               
00224               odom.pose.pose.position.x = x_estimated(1);
00225               odom.pose.pose.position.y = x_estimated(2);
00226               odom.pose.pose.position.z = 0.0;
00227               odom.pose.pose.orientation = odom_quat;
00228               odom.pose.covariance[0]=covariance_matrix(1,1);
00229               odom.pose.covariance[7]=covariance_matrix(2,2);
00230               odom.pose.covariance[35]=covariance_matrix(3,3);
00231               
00232               
00233               
00234               odom.child_frame_id = "/atc/vehicle/rear_axis";
00235               odom.twist.twist.linear.x = vx;
00236               odom.twist.twist.linear.y = vy;
00237               odom.twist.twist.angular.z = vth;
00238 
00239 
00240               
00241               odom_pub.publish(odom);
00242               
00243               
00244               
00245               
00246               
00247 
00248 
00249 
00250 
00251 
00252 
00253 
00254 
00255 
00256 
00257 
00258 
00259 
00260 
00261 
00262 
00263 
00264 
00265 
00266 
00267 
00268 
00269 
00270 
00271        }
00272 }