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
00032 #include <iostream>
00033 #include <ros/ros.h>
00034
00035 #include <tf/transform_broadcaster.h>
00036 #include <nav_msgs/Odometry.h>
00037
00038 #define DEFAULT_WHEEL_BASE 0.497
00039
00040 #include <signal.h>
00041
00042 #include <atlasmv_base/AtlasmvStatus.h>
00043
00044 using namespace ros;
00045 using namespace std;
00046
00047 void IncommingDataHandler(int);
00048 bool ConvertEstimatedToMeasurment(double vl,double dir,double*dx,double*dy,double*dtheta,double dt,double l,double bwa);
00049
00050 bool new_status_message;
00051 atlasmv_base::AtlasmvStatus base_status;
00052
00053 void StatusMessageHandler(const atlasmv_base::AtlasmvStatus& msg)
00054 {
00055 base_status=msg;
00056 new_status_message=true;
00057 }
00058
00059 int main(int argc, char** argv)
00060 {
00061 ros::init(argc, argv, "atlasmv_egomotion");
00062
00063 ros::NodeHandle n;
00064 ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("/atlasmv/base/odometry", 50);
00065 tf::TransformBroadcaster odom_broadcaster;
00066
00067 Subscriber subscribeStatusMessages = n.subscribe ("/atlasmv/base/status", 1, StatusMessageHandler);
00068
00069 double x = 0.0;
00070 double y = 0.0;
00071 double th = 0.0;
00072
00073 double vx = 0.0;
00074 double vy = 0.0;
00075 double vth = 0.0;
00076
00077 double vl,phi;
00078 double l;
00079
00080 n.param("wheel_base",l,DEFAULT_WHEEL_BASE);
00081
00082 new_status_message=false;
00083
00084 ros::Time current_time, last_time;
00085 current_time = ros::Time::now();
00086 last_time = ros::Time::now();
00087
00088 ros::Rate r(60.0);
00089
00090 ROS_INFO("Starting to spin ...");
00091
00092 while(n.ok())
00093 {
00094 spinOnce();
00095 r.sleep();
00096
00097 if(!new_status_message)
00098 continue;
00099
00100 new_status_message=false;
00101
00102 current_time = ros::Time::now();
00103
00104 vl=base_status.speed;
00105 phi=base_status.dir;
00106
00107
00108 double dt = (current_time - last_time).toSec();
00109
00110 double delta_x;
00111 double delta_y;
00112 double delta_th;
00113
00114 delta_x=cos(th)*cos(phi)*vl*dt;
00115 delta_y=sin(th)*cos(phi)*vl*dt;
00116 delta_th=sin(phi/l)*vl*dt;
00117
00118 ROS_INFO("cos(th):%f,cos(phi):%f",cos(th),cos(phi));
00119 ROS_INFO("dx:%f,dy:%f,dth:%f",delta_x,delta_y,delta_th);
00120 ROS_INFO("th:%f,phi:%f,vl:%f",th,phi,vl);
00121
00122 vx = delta_x/dt;
00123 vy = delta_y/dt;
00124 vth = delta_th/dt;
00125
00126 x += delta_x;
00127 y += delta_y;
00128 th += delta_th;
00129
00130 ROS_INFO("dt:%f",dt);
00131 ROS_INFO("x:%f,y:%f,th:%f",x,y,th);
00132 ROS_INFO("vx:%f,vy:%f,vth:%f",vx,vy,vth);
00133
00134
00135 geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th);
00136
00137
00138 geometry_msgs::TransformStamped odom_trans;
00139 odom_trans.header.stamp = current_time;
00140 odom_trans.header.frame_id = "/odom";
00141 odom_trans.child_frame_id = "/base_link";
00142
00143 odom_trans.transform.translation.x = x;
00144 odom_trans.transform.translation.y = y;
00145 odom_trans.transform.translation.z = 0.0;
00146 odom_trans.transform.rotation = odom_quat;
00147
00148
00149 odom_broadcaster.sendTransform(odom_trans);
00150
00151
00152 nav_msgs::Odometry odom;
00153 odom.header.stamp = current_time;
00154 odom.header.frame_id = "/odom";
00155
00156
00157 odom.pose.pose.position.x = x;
00158 odom.pose.pose.position.y = y;
00159
00160
00161 odom.pose.pose.position.z = 0.0;
00162 odom.pose.pose.orientation = odom_quat;
00163
00164
00165 odom.child_frame_id = "/base_link";
00166 odom.twist.twist.linear.x = vx;
00167 odom.twist.twist.linear.y = vy;
00168 odom.twist.twist.angular.z = vth;
00169
00170
00171 odom_pub.publish(odom);
00172
00173 last_time = current_time;
00174 }
00175 }