ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

odometry in place

asked 2018-02-26 16:07:50 -0500

updated 2018-02-27 10:08:16 -0500

I am setting up a Gazebo model for use with the navigation stack. I have been reading the Navigation Tuning Guide and am confused about the lidar data in the odom frame. I would think that the tuning guide, when it says:

"The first test checks how reasonable the odometry is for rotation. I open up rviz, set the frame to "odom," display the laser scan the robot provides, set the decay time on that topic high (something like 20 seconds), and perform an in-place rotation. Then, I look at how closely the scans match each other on subsequent rotations. Ideally, the scans will fall right on top of each other, but some rotational drift is expected, so I just make sure that the scans aren't off by more than a degree or two. (Nav Stack Tuning)"

it means that the lidar data is supposed to be in approximately the same place before, during, and after the rotation. I have been reading and it seems that these sweeping swirls that I see are correct? I have been trying to use gmapping in my simulation and whenever I rotate the map gets horridly disfigured - I believe that odometry is to blame.

I have recorded what the lidar data looks like in the odom frame. Is this correct or should it look differently?


Edit 1: I followed this tutorial to build the initial model and simulate it. I created a (visually) crude model with two wheels (left and right) that move and two frictionless casters (front and back) using their general framework. I changed the shape of the robot but just followed their procedure and tried to reproduce it. I have tried to flip the x rotation for the left and right wheels from -pi/2 to pi/2 and that just reversed the direction of motion, which I expected, but does not change the issue of streaky lidar from the odom frame. I am puzzled because the straight odometry data keeps the laser scans in the same position (as one would expect) but when I rotate the robot I get the streaks. I don't really know the mechanism behind calculating the odometry data in Gazebo so I am stuck as to fixing this issue.

The urdf file is shown:

<?xml version="1.0"?>
<robot name="bender" xmlns:xacro="http://ros.org/wiki/xacro">

    <xacro:property name="pi" value="3.141592653589794" />
    <xacro:property name="base_len" value="0.89" />
    <xacro:property name="base_wid" value="0.80" />
    <xacro:property name="base_height" value="0.20" />
    <xacro:property name="caster_length" value="0.10" />
    <xacro:property name="caster_radius" value="0.15" />
    <xacro:property name="wheel_length" value="0.10" />
    <xacro:property name="wheel_radius" value="0.15" />
    <xacro:property name="update_rate" value="50"/>
    <xacro:property name="hokuyo_size" value="0.05"/>

    <xacro:macro name="default_inertial" params="mass">
        <inertial>
          <mass value="${mass}" />
          <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
        </inertial>
    </xacro:macro>


    <material name="white">
       <color rgba ...
(more)
edit retag flag offensive close merge delete

Comments

It shouldn't swirl like that. The gazebo robot appears to be rotating the opposite direction as in rviz - or is the rviz display upside down looking through the floor?

lucasw gravatar image lucasw  ( 2018-02-26 18:53:22 -0500 )edit

Should the robot spawn in the same direction in both? I didn't set any parameters it just was that way. When I went through URDF tutorials the R2D2 we made appeared that way. Plus, it drives forward the way I expect and the lidar scanning with large decay stays in a constant position.

cmfuhrman gravatar image cmfuhrman  ( 2018-02-26 19:19:14 -0500 )edit

Maybe there is a way to flip the direction of the odometry rotation (the crudest way would be to subscribe to it, flip the sign, then republish under a new name and have rviz use that.)

lucasw gravatar image lucasw  ( 2018-02-26 20:10:52 -0500 )edit
1

Do you have a custom urdf you can post? Update the question with it if so. What is the link to the tutorial you are following, and are you following it exactly or what changes have you made?

lucasw gravatar image lucasw  ( 2018-02-26 20:12:02 -0500 )edit

I have been following another example as outlined in Edit 2 in above post. The 'streaking' behavior occurs in the x direction rather than when rotating. What could make this occur?

cmfuhrman gravatar image cmfuhrman  ( 2018-02-27 10:10:08 -0500 )edit

If you are able to individually turn wheels it would be good to verify that the left wheel in gazebo is the left wheel in rviz and is turning in a consistent direction and the same for the right wheel.

lucasw gravatar image lucasw  ( 2018-02-28 10:49:49 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-02-28 11:03:25 -0500

Humpelstilzchen gravatar image

I checked your repository, noticed that when sending the command to turn right it does so in rviz, but turns left in gazebo.

That is because the wheels are turning in the wrong direction, both wireframe mode in gazebo and tf in rviz do show that. To fix that you need to rotate both wheels by 180 degree.

Removing the minus sign of rpy in your model.urdf.xacro, line 102 should do that:

<origin xyz="0 ${reflect*(base_wid/2)} ${-1*base_height}" rpy="${-pi/2} 0 0"/>
edit flag offensive delete link more

Comments

You are definitely right! I also think that the left and right wheels were on the wrong side of the bot. I think this is going in the right direction, no? Thank you!

cmfuhrman gravatar image cmfuhrman  ( 2018-02-28 21:54:04 -0500 )edit

Update: I incorporated your feedback, and changed the configuration of the wheels to be on the correct sides of the robot (DUH!!). I also removed the base_footprint for now and I was able to map the simulated environment with gmapping - showing that odometry is working properly.

cmfuhrman gravatar image cmfuhrman  ( 2018-02-28 23:28:55 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2018-02-26 16:07:50 -0500

Seen: 1,118 times

Last updated: Feb 28 '18