Set Odometry in a new robot in ROS
I'm trying to create a robot with a new model in ROS .gazebo/models. I defined model.config and model.sdf. I have to set the ros message Odometry because in the 'risotopic list' there isn't /odom.
How can I define the odometry of my robot?
this is model.sdf:
<?xml version='1.0'?>
<link name='rack'>
<inertial>
<pose>0.001453 -0.000453 0.029787 0 0 0</pose>
<inertia>
<ixx>0.058640</ixx>
<ixy>0.000124</ixy>
<ixz>0.000615</ixz>
<iyy>0.058786</iyy>
<iyz>0.000014</iyz>
<izz>1.532440</izz>
</inertia>
<mass>2.234000</mass>
</inertial>
<collision name='plate_down'>
<pose>0 0 .05 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.19</radius>
<length>.015</length>
</cylinder>
</geometry>
</collision>
<visual name='plate_down'>
<geometry>
<cylinder>
<radius>.19</radius>
<length>.015</length>
</cylinder>
</geometry>
</visual>
<collision name='plate_up'>
<pose>0 0 .2 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.19</radius>
<length>.015</length>
</cylinder>
</geometry>
</collision>
<visual name='plate_up'>
<geometry>
<cylinder>
<radius>.19</radius>
<length>.015</length>
</cylinder>
</geometry>
</visual>
<collision name="left_wheel">
<!--<pose> y(per centrare le ruote) x(per avvicinare le ruote) z ro teta phi (angoli di rotazione)</pose>-->
<pose>0.025 0.1 0.05 0 1.5 1.5</pose>
<geometry>
<cylinder>
<radius>.05</radius>
<length>.02</length>
</cylinder>
</geometry>
</collision>
<visual name="left_wheel">
<geometry>
<cylinder>
<radius>.05</radius>
<length>.025</length>
</cylinder>
</geometry>
</visual>
<collision name="right_wheel">
<pose>0.025 -0.1 0.05 0 1.5 1.5</pose>
<geometry>
<cylinder>
<radius>.05</radius>
<length>.02</length>
</cylinder>
</geometry>
</collision>
<visual name="right_wheel">
<geometry>
<cylinder>
<radius>.05</radius>
<length>.025</length>
</cylinder>
</geometry>
</visual>
</model>
</sdf>
Asked by sdg on 2017-02-21 11:41:07 UTC
Answers
Calculating the odometry is typically done via a plugin, that is a piece of code inserted into the model that can do calculations and change the model based on an interface defined here
A Model plugin will give you access to joint information usually useful for calculating your odometry. For special arrangements its usually better to calculate your odometry and publish as you see fit, typically via a ros odometry message.
Alternatively for common arrangements there are some existing plugins available that might suit your purpose. I am thinking specifically of the differential drive ros plugin, skid steer plugin and planar drive plugin. They will give you a control interface (for issuing commands) as well as output odometry information.
Asked by PMilani on 2017-02-23 18:59:25 UTC
Comments
Thank you so much.
Asked by tiagosilvadev on 2021-08-15 20:06:39 UTC
Comments
does this model describe an ackerman steering arrangement for the robot? Asking as the better way is to implement in code.
Asked by PMilani on 2017-02-23 18:52:02 UTC