Gazebo | Ignition | Community
Ask Your Question
0

How to use the gazebo_ros Skid Steer Drive plugin?

asked 2019-01-30 04:04:45 -0500

schokkobaer gravatar image

updated 2019-02-07 08:21:52 -0500

Hello, I'm new to Gazebo and ROS and wanted to implement the skid steering plugin from Gazebo for the a very basic 4 wheeled 'robot' , but I'm not sure what how the axis are supposed to be set and what some of the requiried variables truly mean e.g torque (not sure which number I should give as input) or broadcastTF (not sure why I should not want to broadcast) . At the moment I can drive backwards and forwards but it the robot does not turn. Here is the xacro that I'm using at the moment:

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"   name="base1">
<!-- variables-->
<xacro:property name="length_wheel" value="0.1"/>
<xacro:property name="radius_wheel" value="0.2"/>
<xacro:property name="base_heigth" value="0.3"/>
<xacro:property name="base_width" value="0.6"/>
<xacro:property name="base_length" value="1.0"/>
<xacro:property name="hokuyo_box_size" value="0.05"/>
<xacro:property name="camera_box_size" value="0.05"/>
<!--<xacro::property name="offset" value=""/>-->
<xacro:property name="PI" value="3.14159265359"/>
<!-- Gazebo colors -->
<xacro:include filename="$(find own_base)/urdf/base1.gazebo"/>

<!-- macros-->
<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>
<link name="base">
    <visual>
        <geometry>
            <box size="${base_length} ${base_width} ${base_heigth}"/>
        </geometry>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <material name="red">
            <color rgba="1 0 0 1"/>
        </material>       
    </visual>
    <collision>
        <geometry>
             <box size="${base_length} ${base_width} ${base_heigth}"/>
        </geometry>
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </collision>
    <xacro:default_inertial mass="100"/>
</link>

   <link name="wheele_1">
        <visual>
         <geometry>
            <cylinder length="${length_wheel}" radius="${radius_wheel}"/>
        </geometry>
        <material name="black"> 
            <color rgba="0 0 0 1"/>
        </material>
        <origin xyz="0 0 0" rpy="0 0 0"/>

    </visual>
    <collision>
        <geometry>
            <cylinder length="${length_wheel}" radius="${radius_wheel}"/>
        </geometry>
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </collision>
<xacro:default_inertial mass="5"/>
</link>

<link name="wheele_2">
        <visual>
         <geometry>
             <cylinder length="${length_wheel}" radius="${radius_wheel}"/>
        </geometry>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <material name="black"> 
            <color rgba="0 0 0 1"/>
        </material>
    </visual>
    <collision>
        <geometry>
            <cylinder length="${length_wheel}" radius="${radius_wheel}"/>
        </geometry>
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </collision>
     <xacro:default_inertial mass="5"/>

</link>

<link name="wheele_3">
        <visual>
         <geometry>
             <cylinder length="${length_wheel}" radius="${radius_wheel}"/>
        </geometry>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <material name="black"> 
            <color rgba="0 0 0 1"/>
        </material>
    </visual>
    <collision>
        <geometry>
            <cylinder length="${length_wheel}" radius="${radius_wheel}"/>
        </geometry>
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </collision>
     <xacro:default_inertial mass="5"/>
</link>


<link name="wheele_4">
        <visual>
         <geometry>
             <cylinder length="${length_wheel}" radius="${radius_wheel}"/>
        </geometry>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <material name="black"> 
            <color rgba="0 0 0 1"/>
        </material>
    </visual>
    <collision>
        <geometry>
            <cylinder length="${length_wheel}" radius="${radius_wheel}"/>
        </geometry>
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </collision>
     <xacro:default_inertial mass="5"/>
</link>
<link name="hokuyo_link">
    <visual>
        <geometry>
            <box size="${hokuyo_box_size} ${hokuyo_box_size} ${hokuyo_box_size}"/>
        </geometry ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2019-02-07 09:45:46 -0500

updated 2019-02-07 14:14:03 -0500

Plugin
Assuming it isn't well documented on a wiki, the most straightforward way to understand a plugin's XML declaration is to look at the source code:
https://github.com/ros-simulation/gaz...


Questions

I'm not sure what how the axis are supposed to be set

Looking at the source code for gazebo_ros_skid_steer_drive, it does not allow the wheel joint axes to be set via SDF/URDF.

Based on this section, the plugin assumes that all 4 wheel axes are oriented in the same direction:

void GazeboRosSkidSteerDrive::getWheelVelocities() {
  boost::mutex::scoped_lock scoped_lock(lock);

  double vr = x_;
  double va = rot_;

  wheel_speed_[RIGHT_FRONT] = vr + va * wheel_separation_ / 2.0;
  wheel_speed_[RIGHT_REAR] = vr + va * wheel_separation_ / 2.0;

  wheel_speed_[LEFT_FRONT] = vr - va * wheel_separation_ / 2.0;
  wheel_speed_[LEFT_REAR] = vr - va * wheel_separation_ / 2.0;

}

and what some of the required variables truly mean e.g torque (not sure which number I should give as input)

gazebo_ros_skid_steer_drive uses Gazebo Joint Motors to rotate each wheel joint at the desired velocity.

From the Setting Velocity on Links and Joints Tutorial:

Configuring a joint motor is done using Joint::SetParam().

      this->model->GetJoint("orange_joint")->SetParam("fmax", 0, 100.0);
      this->model->GetJoint("orange_joint")->SetParam("vel", 0, 1.0);

It accepts three parameters: key, axis, and value. The key parameter is a string that names the parameter to be changed. The axis parameter is an index that may be 0 or 1.
...
Setting up a joint motor requires requires two calls. The first call sets the key vel to the velocity the joint should travel at. It is meters per second for prismatic joints and radians per second for all others. The other call sets the key fmax. It is the maximum force or torque a joint motor may apply during a time step. Set it larger than the force required to be at the target velocity at the next time step. Set it smaller to apply a force over many time steps until the velocity is reached. Stop applying force by setting fmax back to zero.

In the gazebo_ros_skid_steer_drive plugin, these two steps occur here and here.

or broadcastTF (not sure why I should not want to broadcast)

Two possible reasons that come to mind:

  1. You aren't interested in odometry and want to reduce resource usage / bandwidth.
  2. You want to publish your own tf data in lieu of Gazebo's like this user.

At the moment I can drive backwards and forwards but it the robot does not turn.

I recommend an incremental testing strategy. First, test your robot while its suspended in the air by temporarily adding a fixed joint from the world link to your base link:

<link name="world" />
<joint name="world_to_base_link=" type="fixed">
  <parent link="world"/>
  <child link="base_link"/>
</joint>

Test to make sure your wheels are rotating as desired. Once you've got the skid_steer_drive_plugin working in the air, you can remove fixed joint (and possibly start debugging collision/friction issues with ground).

Here is the xacro that I'm using at the ...

(more)
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2019-01-30 04:04:45 -0500

Seen: 8,145 times

Last updated: Feb 07 '19