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

How can I simulate Ackermann steering in Gazebo? [closed]

asked 2011-03-19 10:30:04 -0600

Jim Rothrock gravatar image

updated 2014-01-28 17:09:22 -0600

ngrennan gravatar image

I have created a URDF file that describes a vehicle with Ackermann steering (a Traxxas E-Maxx RC truck) and need to simulate the vehicle in Gazebo. To simulate Ackermann steering, I am considering writing a Gazebo controller plug-in like this:

ackermann_steering_controller:
    leftJointName (string)
    rightJointName (string)
    track (float)
    wheelbase (float)

The controller would subscribe to messages from joy_node, getting the steering angle from it, then would perform PID servo control on the left and right joints to keep them rotated to angles that satisfy the Ackermann equation. Is there a better way to do this? I've read the transmission tutorials, but haven't been able to figure out how to adapt the PR2 transmission system to a Gazebo simulation of Ackermann steering.

edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by Jim Rothrock
close date 2015-08-24 17:57:43.368036

Comments

I haven't done anything related to this, but you may be able to check out the Gazebo model for the ClodBuster. It's a 4-wheel Ackerman robot.
mjcarroll gravatar image mjcarroll  ( 2011-03-20 11:09:46 -0600 )edit
I would like to use gazebo for an autonomous car with Ackermann steering. Please keep everyone posted on what you do.
joq gravatar image joq  ( 2011-03-25 15:35:50 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
5

answered 2011-03-25 20:40:29 -0600

hsu gravatar image

updated 2011-03-25 20:45:01 -0600

One way is the implement the 4 bar linkage. Here's a simple model constructed with 4 bar linkage steering mechanism. I did not compute the exact linkage lengths for Ackermann steering, but the basic idea is there:

  <robot
        xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz"
        xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model"
        xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
        xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"
        xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom"
        xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint"
        xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
        xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
        xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering"
        xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics"
        name="ackermann">

    <property name="M_PI" value="3.1415926535897931" />

    <link name="base">
      <inertial>
        <mass value="1.0" />
        <origin xyz="0 0 0" /> 
        <inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="1.0"  iyz="0.0"  izz="1.0" />
      </inertial>
      <visual>
        <origin xyz="0 0 0" rpy="0 0 0" />
        <geometry>
          <box size="2.0 1.0 0.1" />
        </geometry>
      </visual>
      <collision>
        <origin xyz="0 0 0" rpy="0 0 0" />
        <geometry>
          <box size="2.0 1.0 0.1" />
        </geometry>
      </collision>
    </link>
    <gazebo reference="base">
      <material>Gazebo/Blue</material>
      <turnGravityOff>false</turnGravityOff>
    </gazebo>

    <link name="front_left_bar">
      <inertial>
        <mass value="1.0" />
        <origin xyz="0 0 0" /> 
        <inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="1.0"  iyz="0.0"  izz="1.0" />
      </inertial>
      <visual>
        <origin xyz="-0.2 -0.2 0" rpy="0 0 0" />
        <geometry>
          <box size="0.4 0.5 0.01" />
        </geometry>
      </visual>
      <collision>
        <origin xyz="-0.2 -0.2 0" rpy="0 0 0" />
        <geometry>
          <box size="0.4 0.5 0.01" />
        </geometry>
      </collision>
    </link>
    <gazebo reference="front_left_bar">
      <material>Gazebo/Green</material>
      <turnGravityOff>false</turnGravityOff>
    </gazebo>
    <joint name="front_left_bar_joint" type="revolute" >
      <limit lower="-0.2" upper="0.2" effort="100" velocity="10" />
      <axis xyz="0 0 1" />
      <parent link="base" />
      <child link="front_left_bar" />
      <origin xyz="1.0 0.5 0.055" rpy="0 0 0" />
    </joint>

    <link name="front_right_bar">
      <inertial>
        <mass value="1.0" />
        <origin xyz="0 0 0" /> 
        <inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="1.0"  iyz="0.0"  izz="1.0" />
      </inertial>
      <visual>
        <origin xyz="-0.2 0.2 0" rpy="0 0 0" />
        <geometry>
          <box size="0.4 0.5 0.01" />
        </geometry>
      </visual>
      <collision>
        <origin xyz="-0.2 0.2 0" rpy="0 0 0" />
        <geometry>
          <box size="0.4 0.5 0.01" />
        </geometry>
      </collision>
    </link>
    <gazebo reference="front_right_bar">
      <material>Gazebo/Green</material>
      <turnGravityOff>false</turnGravityOff>
    </gazebo>
    <joint name="front_right_bar_joint" type="revolute" >
      <limit lower="-0.2" upper="0.2" effort="100" velocity="10" />
      <axis xyz="0 0 1" />
      <parent link="base" />
      <child link="front_right_bar" />
      <origin xyz="1.0 -0.5 0.055" rpy="0 0 0" />
    </joint>

    <link name="front_left_wheel">
      <inertial>
        <mass value="1.0" />
        <origin xyz="0 0 0" /> 
        <inertia ...
(more)
edit flag offensive delete link more

Comments

adjusting the 4 bar linkage lengths so the 4 bar linkage enforces Ackermann steering. After that you still need a transmission to control one of the linkage joints using a pr2_controllers if you wish.
hsu gravatar image hsu  ( 2011-03-25 20:44:02 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2011-03-19 10:30:04 -0600

Seen: 5,361 times

Last updated: Mar 25 '11