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
00031 #include <sensor_msgs/Imu.h>
00032
00033 #include <tf/transform_listener.h>
00034 #include <nav_msgs/Odometry.h>
00035 #include <stdio.h>
00036 #include <atlascar_base/AtlascarStatus.h>
00037 #include <std_msgs/Float64.h>
00038 #include <atlascar_base/AtlascarVelocityStatus.h>
00039 using namespace std;
00040 using namespace ros;
00041
00042
00043
00044 std_msgs::Float64 acc_norm_imu,tan_msg,cent_msg;
00045
00046 ros::Publisher* p_pitch_pub;
00047 nav_msgs::Odometry odometry_;
00048 sensor_msgs::Imu imu_data;
00049 atlascar_base::AtlascarStatus base_status;
00050 atlascar_base::AtlascarVelocityStatus base_velocity;
00051 ros::Time t_i, t_i_1;
00052 double vl_i,vl_i_1;
00053 bool bool_init=true;
00054 double v_ant;
00055 void ImuCallback(const sensor_msgs::Imu::ConstPtr &msg )
00056 {
00057 imu_data=*msg;
00058 }
00059
00060 void VelocityMessageHandler(const atlascar_base::AtlascarVelocityStatus& msg)
00061 {
00062 base_velocity=msg;
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
00082 ros::init(argc, argv, "imu_egomotion");
00083 ros::NodeHandle n;
00084
00085 Subscriber imu= n.subscribe("/atc/imu/data",1, ImuCallback);
00086 Subscriber subscribeStatusMessages = n.subscribe ("/vhc/plc/status", 1, StatusMessageHandler);
00087 Subscriber subscribeVelocityStatusMessages = n.subscribe ("/vhc/velocity/status", 1, VelocityMessageHandler);
00088
00089 Publisher imu_norm=n.advertise<std_msgs::Float64>("/imu_norm",50);
00090 Publisher accel_tan=n.advertise<std_msgs::Float64>("/accel_tan",50);
00091 Publisher accel_cent=n.advertise<std_msgs::Float64>("/accel_cent",50);
00092
00093 ros::Rate r(20.0);
00094
00095 ROS_INFO("Starting to spin ...");
00096 double vl,phi;
00097 double phi_tmp=0;
00098
00099 while(n.ok())
00100 {
00101 spinOnce();
00102 r.sleep();
00103
00104
00105 vl=base_velocity.velocity;
00106 phi=base_status.steering_wheel;
00107
00108 if (phi ==0)
00109 phi=phi_tmp;
00110 else
00111 phi_tmp=phi;
00112
00113
00114
00115
00116 phi= phi +0.275;
00117
00118 if (phi <=0)
00119 {
00120 phi = phi*0.74;
00121 phi=phi*-1;
00122 }
00123 else if (phi>0)
00124 {
00125 phi= phi*0.825;
00126 phi=phi*-1;
00127 }
00128
00129
00130 double w=1.27;
00131 double l=2.6;
00132 double instant_radious=fabs(l/tan(phi));
00133 double v_corrected;
00134 if(phi>=0)
00135 v_corrected=vl*(instant_radious/(instant_radious-w/2));
00136 else
00137 v_corrected=vl*(instant_radious/(instant_radious+w/2));
00138
00139 cout << "vl_ant" << v_ant << "\n"<< endl;
00140 cout << "vl" << vl << "\n"<< endl;
00141 cout << "vl_corre" << v_corrected << "\n"<< endl;
00142
00143
00144 double dt = (t_i - t_i_1).toSec();
00145 double acc_cent=(v_corrected*v_corrected)/instant_radious;
00146
00147
00148
00149 v_ant=v_corrected;
00150
00151 tan_msg.data=dt;
00152 accel_tan.publish(tan_msg);
00153
00154 cent_msg.data=acc_cent;
00155 accel_cent.publish(cent_msg);
00156
00157 double accel_norm= sqrt((imu_data.linear_acceleration.x * imu_data.linear_acceleration.x) + (imu_data.linear_acceleration.y * imu_data.linear_acceleration.y) + (imu_data.linear_acceleration.z * imu_data.linear_acceleration.z));
00158
00159
00160 acc_norm_imu.data=accel_norm;
00161 imu_norm.publish(acc_norm_imu);
00162
00163
00164 }
00165 return 0;
00166 }