You can do that by doing two options:
- You compute the odometry based on the movement of the robot and odometry equations
- You get the odometry directly asking Gazebo how much your robot moved
Once you have that data, you create a topic with Odometry msg type and publish the data obtained from the call.
Since you are not providing any information about your robot, we cannot explain here option 1. Let's explain option 2
In order to get how much the robot moved you should call the /gazebo/get_model_state
service provided by Gazebo. That service will provide you with the current position of the robot in the world. In order to call it, do the following:
rosservice call /gazebo/get_model_state "model_name: 'the_name_of_your_robot' relative_entity_name: ' ' "
Just calling that service you will get the current position of the robot in Gazebo. However, you must do that call inside a node to get the position data and publish it later in an odometry topic. You can do all that with the following code:
#! /usr/bin/env python
from nav_msgs.msg import Odometry
from std_msgs.msg import Header
from gazebo_msgs.srv import GetModelState, GetModelStateRequest
rospy.init_node('odom_pub')
odom_pub=rospy.Publisher ('/my_odom', odometry)
rospy.wait_for_service ('/gazebo/get_model_state')
get_model_srv = rospy.ServiceProxy('/gazebo/get_model_state', GetModelstate)
odom=Odometry()
header = Header()
header.frame_id='/odom'
model = GetModelStateRequest()
model.model_name='the_name_of_your_robot'
r = rospy.Rate(2)
while not rospy.is_shutdown():
result = get_model_srv(model)
odom.pose.pose = result.pose
odom.twist.twist = result.twist
header.stamp = rospy.Time.now()
odom.header = header
odom_pub.publish (odom)
r.sleep()
That's it! That Python code will do exactly that: get the robot position from the simulator, and then publish it in an odometry topic.
Here you can find a video ( https://youtu.be/I_5leJK8vhQ ) that shows how to do all the explained above with a full example for a kobuki robot.