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

ROS Gazebo Differential Drive only goes straight

asked 2018-02-21 08:40:14 -0500

I am trying to simulate my robot in Gazebo following the urdf tutorial found here to create an R2D2 model. The tutorial makes sense to me and I can successfully run it on my machine.

I tried to create my own model - a robot with left and right wheels in the center of a box and two casters on the front. I have modeled the casters as spheres setting the friction parameters to 0. The problem I am having is that my robot will only drive in the forward direction - it will not steer like the tutorial does. I am using the same rqt_robot_steering package to make the robot move but I cannot figure out why it does not turn. (Interesting side note - I copied the urdf tutorial files onto my machine and rant them in my bender_model package and was not successful in making R2D2 turn.)

All my code can be found on my github acount

I am running ROS Version: 1.12.12, Ubuntu 16.04 LTS, Gazebo 7.

I appreciate any help making my robot model turn!! I am not very good at ROS and out of ideas!!

I create my model from the model.urdf.xacro:

<?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="1 1 1 1.5"/>
    </material>


    <link name="base_link">
        <visual>
          <geometry>
            <box size="${base_len} ${base_wid} ${base_height}"/>
          </geometry>
          <material name="white"/>
        </visual>
        <collision>
            <geometry>
              <box size="${base_len} ${base_wid} ${base_height}"/>
            </geometry>
        </collision>
        <xacro:default_inertial mass="1"/>
    </link>


    <xacro:macro name="caster" params="position reflect">
        <joint name="${position}_wheel_joint" type="fixed">
            <parent link="base_link"/>
            <child link="${position}_wheel"/>
            <axis xyz="0 0 1"/>
            <origin xyz="${reflect*(base_wid/2)} 0 ${-1 * base_height}" rpy="${pi/2} 0 0"/>
        </joint>
        <link name="${position}_wheel">
            <visual>
                <geometry>
                    <sphere radius="${caster_radius}"/>
                </geometry>
                <material name="white"/>
            </visual>
            <collision>
                <geometry>
                  <sphere radius="${caster_radius}"/>
                </geometry>
            </collision>
            <xacro:default_inertial mass="0.5"/>
        </link>

<!-- This block provides the simulator (Gazebo) with information on a few additional
physical properties. See http://gazebosim.org/tutorials/?tut=ros_urdf for more-->
        <gazebo reference="${position}_wheel">
            <mu1 value = "0.0"/>
            <mu2 value = "0.0"/>
            <kp  value = "10000000.0"/>
            <kd  value = "1.0"/>
            <material>Gazebo/Grey/</material>
        </gazebo>
    </xacro:macro>

    <xacro:macro name="wheel" params="position reflect">
        <joint name="${position}_wheel_joint" type="continuous">
            <parent link="base_link"/>
            <child link="${position}_wheel"/>
            <axis xyz="0 0 1"/>
            <origin xyz="0 ${reflect ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2018-02-21 12:03:47 -0500

Humpelstilzchen gravatar image

updated 2018-02-21 12:08:31 -0500

Looks like a typo in your diffdrive.yaml:

angular:
  z:
    has_velocity_limits    : true
    max_velocity           : 2.0   # rad/s
    has_acceleration_limits: true
max_acceleration           : 6.0 # rad/s^2

See the last line, it is not indented into the angular->z namespace so DiffDriveController reads the default 0 for this value. Without acceleration there is of course no movement. Correct the indention to the same level as has_acceleration_limits and you should be able to turn.

edit flag offensive delete link more

Comments

Sir, Thank you!! Indenting max_acceleration solved my problem!!

cmfuhrman gravatar image cmfuhrman  ( 2018-02-21 12:20:43 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-02-21 08:26:15 -0500

Seen: 1,308 times

Last updated: Feb 21 '18