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
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <ros/ros.h>
00038 #include <tf/transform_broadcaster.h>
00039 #include <nav_msgs/Odometry.h>
00040
00041 int main(int argc, char** argv){
00042 ros::init(argc, argv, "odometry_publisher");
00043
00044 ros::NodeHandle n;
00045 ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("odom", 50);
00046 tf::TransformBroadcaster odom_broadcaster;
00047
00048 double x = 0.0;
00049 double y = 0.0;
00050 double th = 0.0;
00051
00052 double vx = 0.1;
00053 double vy = -0.1;
00054 double vth = 0.1;
00055
00056 ros::Time current_time, last_time;
00057 current_time = ros::Time::now();
00058 last_time = ros::Time::now();
00059
00060 ros::Rate r(1.0);
00061 while(n.ok()){
00062 current_time = ros::Time::now();
00063
00064
00065 double dt = (current_time - last_time).toSec();
00066 double delta_x = (vx * cos(th) - vy * sin(th)) * dt;
00067 double delta_y = (vx * sin(th) + vy * cos(th)) * dt;
00068 double delta_th = vth * dt;
00069
00070 x += delta_x;
00071 y += delta_y;
00072 th += delta_th;
00073
00074
00075 geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th);
00076
00077
00078 geometry_msgs::TransformStamped odom_trans;
00079 odom_trans.header.stamp = current_time;
00080 odom_trans.header.frame_id = "odom";
00081 odom_trans.child_frame_id = "base_link";
00082
00083 odom_trans.transform.translation.x = x;
00084 odom_trans.transform.translation.y = y;
00085 odom_trans.transform.translation.z = 0.0;
00086 odom_trans.transform.rotation = odom_quat;
00087
00088
00089 odom_broadcaster.sendTransform(odom_trans);
00090
00091
00092 nav_msgs::Odometry odom;
00093 odom.header.stamp = current_time;
00094 odom.header.frame_id = "odom";
00095 odom.child_frame_id = "base_link";
00096
00097
00098 odom.pose.pose.position.x = x;
00099 odom.pose.pose.position.y = y;
00100 odom.pose.pose.position.z = 0.0;
00101 odom.pose.pose.orientation = odom_quat;
00102
00103
00104 odom.twist.twist.linear.x = vx;
00105 odom.twist.twist.linear.y = vy;
00106 odom.twist.twist.angular.z = vth;
00107
00108
00109 odom_pub.publish(odom);
00110
00111 last_time = current_time;
00112 r.sleep();
00113 }
00114 }