ros-controls / gazebo_ros2_control

Wrappers, tools and additional API's for using ros2_control with Gazebo Classic
Apache License 2.0
210 stars 125 forks source link

When using an namespace for my omniroboter the controller_manager doesn't get an update_rate #366

Open AshBastian opened 3 months ago

AshBastian commented 3 months ago

Description of the bug I'm trying to use mutiple omni-directional roboter with the ROS navigationstack 2 and therefore I need to setup my own controller. When I only spawn 1 roboter without a namespace, the controller_manager gets loaded without any problems, but as soon as I give the roboter an namespace, the controller_manager doesn't receive the update_parameter anymore and therefore the whole gazebo_plugin fails.

Steps to reproduce the behavior:

import os

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.actions import Node

def generate_launch_description():
    # Create the launch description and populate
    ld = LaunchDescription()

    bringup_dir = get_package_share_directory('gazebo_simulation')
    pkg_gazebo_ros = get_package_share_directory('gazebo_ros')

    urdf = os.path.join(bringup_dir, 'urdf', 'rs_robot.urdf')

    remappings = [('/tf', 'tf'),
                  ('/tf_static', 'tf_static')]

    start_gazebo_server_cmd = IncludeLaunchDescription(
            PythonLaunchDescriptionSource(
                os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')
            ),
            launch_arguments={'world': 'omni_nav_world2.model'}.items(),
        )

    start_gazebo_client_cmd = IncludeLaunchDescription(
            PythonLaunchDescriptionSource(
                os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py')
            ),
        )

    omni_state_publisher = Node(
        package='robot_state_publisher',
        executable='robot_state_publisher',
        name='robot_state_publisher',
        namespace='',
        output='screen',
        parameters=[{'use_sim_time': False,
                        'publish_frequency': 10.0}],
        remappings=remappings,
        arguments=[urdf])

    spawn_omni = Node(
            package='gazebo_ros',
            executable='spawn_entity.py',
            arguments=[
                '-file', os.path.join(bringup_dir,'models', 'rs_robot/rs_robot.sdf'),
                '-entity', 'test',
                '-robot_namespace', '',
                '-x', '0.0', '-y', '0.0',
                '-z', '1.01', '-Y', '0.0',
                '-unpause',
            ],
            output='screen',
        )

    ld.add_action(start_gazebo_server_cmd)
    ld.add_action(start_gazebo_client_cmd)

    ld.add_action(omni_state_publisher)
    ld.add_action(spawn_omni)

    return ld

Change the namespace and -robot_namespace variable to something and the system fails

Expected behavior The expected behavior would be, that the system loads the controller_manager into the namespace with all the parameter.

Code important for the Execution My .yaml file that the system loads.

controller_manager:
  ros__parameters:
    update_rate: 1000  # Hz

    joint_state_broadcaster:
      type: joint_state_broadcaster/JointStateBroadcaster

    forward_velocity_controller:
      type: forward_command_controller/ForwardCommandController

forward_velocity_controller:
  ros__parameters:
    joints:
      - first_wheel_joint
      - second_wheel_joint
      - third_wheel_joint
      - fourth_wheel_joint
    interface_name: velocity
    command_interfaces:
      - velocity
    state_interfaces:
      - velocity

The part in the .sdf file wäre the gazebo plugin is called:

<ros2_control name="GazeboSystem" type="system">
    <hardware>
      <plugin>gazebo_ros2_control/GazeboSystem</plugin>
    </hardware>

    <joint name="first_wheel_joint">
      <command_interface name="velocity">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <state_interface name="velocity"/>
    </joint>

    <joint name="second_wheel_joint">
      <command_interface name="velocity">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <state_interface name="velocity"/>
    </joint>

    <joint name="third_wheel_joint">
      <command_interface name="velocity">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <state_interface name="velocity"/>
    </joint>

    <joint name="fourth_wheel_joint">
      <command_interface name="velocity">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <state_interface name="velocity"/>
    </joint>
  </ros2_control>

    <plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
<parameters>/home/bastian/Documents/omni_navigation/install/gazebo_simulation/share/gazebo_simulation/models/rs_robot/config/controllers.yaml</parameters>
    </plugin>

Environment (please complete the following information):

Additional Points for what I already found The system works as intended until the reset for the controller_manager in the gazebo_ros2_controll_plugin.cpp line 384 Here the systems doesn't load the update_rate and I believe the problem is in the executor that parses the information from the .yaml file incorrectly. Therefore the parameter for the update_rate is not set and the controller_manager therefore cannot set the value, which breaks the system. The arguments themself are given correctly to the executor in the lines 256 until 266 in the gazebo_ros2_controll_plugin.cpp. Screenshot from 2024-08-13 13-33-02 Screenshot from 2024-08-13 13-33-22

christophfroehlich commented 3 months ago

Is this maybe related to https://github.com/ros-controls/gazebo_ros2_control/pull/181?

christophfroehlich commented 3 months ago

Or maybe this is simpler, and you should add the namespace as argument to the plugin as described here.

AshBastian commented 3 months ago

Or maybe this is simpler, and you should add the namespace as argument to the plugin as described here.

That doesn't do anything, I tried

AshBastian commented 3 months ago

Is this maybe related to #181?

And I tried to comment out the lines mentioned in the other issue, but that also doesn't have any effect on my problem

AshBastian commented 3 months ago

Screenshot from 2024-08-13 18-08-18 Screenshot from 2024-08-13 18-09-17 It removes the __ns line from the arguments the executor will parse in the end. I made it visible like this in the lines 256 of the gazebo_ros2_control_plugin.cpp

std::vector<const char *> argv;
  for (const auto & arg : arguments) {
    argv.push_back(reinterpret_cast<const char *>(arg.data()));
    RCLCPP_WARN_STREAM(impl_->model_nh_->get_logger(),arg.data());
  }
christophfroehlich commented 3 months ago

I created a MWE in this https://github.com/ros-controls/gazebo_ros2_control/pull/367

ros2 launch gazebo_ros2_control_demos cart_example_position_namespaced.launch.py

runs successfully and

ros2 control list_controllers -c /my_ns/controller_manager
joint_trajectory_controller[joint_trajectory_controller/JointTrajectoryController] active    
joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster] active 

I think you forgot to namespace the parameters in the yaml file.

AshBastian commented 3 months ago

I namespaced everything like you did, but it still doesn't work, the different right now is that you use the urdf as the startingpoint for the plugin, while I start it from an sdf file

AshBastian commented 3 months ago

And I also tried to change my stuff into your example and it just doesn't load the urdf anymore, after that I tried to get your example unto my computer but that also just breaks when I try to colcon build it, so I cannot verify if your solution works on my system

christophfroehlich commented 3 months ago

you can just take the new files and add it to the humble branch of this repo, or cherry-pick the PR on top of it. The demo should run on every distro.

AshBastian commented 3 months ago

I'm really sorry, but I really don't know what I should do now to get the demo running on my system, because I'm not an expert on how to manages the git repos to get them on my system without destroying the rest of my ros

AshBastian commented 3 months ago

Do I just pull the current repo over an pull request and then add the new files. Afterwards I colcon build it on my system, source it and start the launch file like you did to hopefully get the same result?

christophfroehlich commented 3 months ago

As you are using Humble distro, you need to build the humble branch of this repo. Before that, add the three files of the PR in the respective folders. As an alternative, you can build the rolling version of the ros2_control stack, see "development version" here.

AshBastian commented 3 months ago

So the demo is running without any problems on my system, so could the problem be that my .sdf is wrong in some way, so the system is failing and if so, how would I need to change it?

<sdf version='1.7'>
  <model name='omni_robot'>

    <link name="base_footprint"/>

    <link name='base_link'>
      <inertial>
        <pose>0 0 0 0 0 0</pose>
        <mass>1.167</mass>
        <inertia>
          <ixx>0.0016</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.0016</iyy>
          <iyz>0</iyz>
          <izz>0.0032</izz>
        </inertia>
      </inertial>
      <collision name='base_footprint_fixed_joint_lump__base_link_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/base/base_link.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode>
              <mu>0.05</mu>
              <mu2>0.05</mu2>
            </ode>
          </friction>
        </surface>
      </collision>
      <visual name='base_footprint_fixed_joint_lump__base_link_visual'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/base/base_link.dae</uri>
          </mesh>
        </geometry>
      </visual>
      <self_collide>0</self_collide>
      <sensor name='front_lrf_sensor' type='ray'>
        <always_on>true</always_on>
        <visualize>true</visualize>
        <update_rate>40</update_rate>
        <pose>0 0 0.1395 0 -0 0</pose>
          <ray>
            <scan>
              <horizontal>
                <samples>720</samples>
                <resolution>1.000000</resolution>
                <min_angle>-3.14158</min_angle>
                <max_angle>3.14158</max_angle>
              </horizontal>
            </scan>
            <range>
              <min>0.120000</min>
              <max>20</max>
              <resolution>0.015000</resolution>
            </range>
            <noise>
              <type>gaussian</type>
              <mean>0.0</mean>
              <stddev>0.01</stddev>
            </noise>
          </ray>
          <plugin name="omni_laserscan" filename="libgazebo_ros_ray_sensor.so">
            <ros>
                <remapping>~/out:=scan</remapping>
            </ros>
            <output_type>sensor_msgs/LaserScan</output_type>
            <frame_name>front_lrf_link</frame_name>
          </plugin>
      </sensor>
    </link>
    <joint name='first_wheel_joint' type='revolute'>
      <pose relative_to='base_link'>0.086338 -0.086338 -0.022 0 0 -2.3562</pose>
      <parent>base_link</parent>
      <child>first_wheel_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <effort>100</effort>
          <velocity>100</velocity>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='first_wheel_link'>
      <pose relative_to='first_wheel_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 -0.011 0 0 -0 0</pose>
        <mass>0.25</mass>
        <inertia>
          <ixx>0.00031</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.0005</iyy>
          <iyz>0</iyz>
          <izz>0.00031</izz>
        </inertia>
      </inertial>
      <collision name='first_wheel_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/omni_wheel/omni_wheel.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='first_wheel_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/omni_wheel/omni_wheel.dae</uri>
          </mesh>
        </geometry>
      </visual>
      <self_collide>0</self_collide>
    </link>
    <joint name='r10_F_roller_joint' type='revolute'>
      <pose relative_to='first_wheel_link'>-0.022885 0.006 -0.007436 1.25664 -0 1.5708</pose>
      <parent>first_wheel_link</parent>
      <child>r10_F_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r10_F_roller_link'>
      <pose relative_to='r10_F_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r10_F_roller_link_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r10_F_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r1_F_roller_joint' type='revolute'>
      <pose relative_to='first_wheel_link'>0 -0.006 0.024063 0 -0 1.5708</pose>
      <parent>first_wheel_link</parent>
      <child>r1_F_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r1_F_roller_link'>
      <pose relative_to='r1_F_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r1_F_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r1_F_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r2_F_roller_joint' type='revolute'>
      <pose relative_to='first_wheel_link'>-0.022885 -0.006 0.007436 -1.25664 -0 1.5708</pose>
      <parent>first_wheel_link</parent>
      <child>r2_F_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r2_F_roller_link'>
      <pose relative_to='r2_F_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r2_F_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r2_F_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r3_F_roller_joint' type='revolute'>
      <pose relative_to='first_wheel_link'>-0.014144 -0.006 -0.019467 -2.51327 -0 1.5708</pose>
      <parent>first_wheel_link</parent>
      <child>r3_F_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r3_F_roller_link'>
      <pose relative_to='r3_F_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r3_F_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r3_F_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r4_F_roller_joint' type='revolute'>
      <pose relative_to='first_wheel_link'>0.014144 -0.006 -0.019467 2.51327 -0 1.5708</pose>
      <parent>first_wheel_link</parent>
      <child>r4_F_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r4_F_roller_link'>
      <pose relative_to='r4_F_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r4_F_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
        </geometry>
      </collision>
      <visual name='r4_F_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r5_F_roller_joint' type='revolute'>
      <pose relative_to='first_wheel_link'>0.022885 -0.006 0.007436 1.25664 -0 1.5708</pose>
      <parent>first_wheel_link</parent>
      <child>r5_F_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r5_F_roller_link'>
      <pose relative_to='r5_F_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r5_F_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r5_F_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r6_F_roller_joint' type='revolute'>
      <pose relative_to='first_wheel_link'>0 0.006 -0.024063 0 -0 1.5708</pose>
      <parent>first_wheel_link</parent>
      <child>r6_F_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r6_F_roller_link'>
      <pose relative_to='r6_F_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r6_F_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r6_F_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r7_F_roller_joint' type='revolute'>
      <pose relative_to='first_wheel_link'>0.022885 0.006 -0.007436 -1.25664 -0 1.5708</pose>
      <parent>first_wheel_link</parent>
      <child>r7_F_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r7_F_roller_link'>
      <pose relative_to='r7_F_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r7_F_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r7_F_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r8_F_roller_joint' type='revolute'>
      <pose relative_to='first_wheel_link'>0.014144 0.006 0.019467 -2.51327 -0 1.5708</pose>
      <parent>first_wheel_link</parent>
      <child>r8_F_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r8_F_roller_link'>
      <pose relative_to='r8_F_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r8_F_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r8_F_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r9_F_roller_joint' type='revolute'>
      <pose relative_to='first_wheel_link'>-0.014144 0.006 0.019467 2.51327 -0 1.5708</pose>
      <parent>first_wheel_link</parent>
      <child>r9_F_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r9_F_roller_link'>
      <pose relative_to='r9_F_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r9_F_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r9_F_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='fourth_wheel_joint' type='revolute'>
      <pose relative_to='base_link'>-0.086338 -0.086338 -0.022 0 -0 2.3562</pose>
      <parent>base_link</parent>
      <child>fourth_wheel_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <effort>100</effort>
          <velocity>100</velocity>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='fourth_wheel_link'>
      <pose relative_to='fourth_wheel_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 -0.011 0 0 -0 0</pose>
        <mass>0.25</mass>
        <inertia>
          <ixx>0.00031</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.0005</iyy>
          <iyz>0</iyz>
          <izz>0.00031</izz>
        </inertia>
      </inertial>
      <collision name='fourth_wheel_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/omni_wheel/omni_wheel.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='fourth_wheel_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/omni_wheel/omni_wheel.dae</uri>
          </mesh>
        </geometry>
      </visual>
      <self_collide>0</self_collide>
    </link>
    <joint name='r10_R_roller_joint' type='revolute'>
      <pose relative_to='fourth_wheel_link'>-0.022885 0.006 -0.007436 1.25664 -0 1.5708</pose>
      <parent>fourth_wheel_link</parent>
      <child>r10_R_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r10_R_roller_link'>
      <pose relative_to='r10_R_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r10_R_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r10_R_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r1_R_roller_joint' type='revolute'>
      <pose relative_to='fourth_wheel_link'>0 -0.006 0.024063 0 -0 1.5708</pose>
      <parent>fourth_wheel_link</parent>
      <child>r1_R_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r1_R_roller_link'>
      <pose relative_to='r1_R_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r1_R_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r1_R_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r2_R_roller_joint' type='revolute'>
      <pose relative_to='fourth_wheel_link'>-0.022885 -0.006 0.007436 -1.25664 -0 1.5708</pose>
      <parent>fourth_wheel_link</parent>
      <child>r2_R_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r2_R_roller_link'>
      <pose relative_to='r2_R_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r2_R_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r2_R_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r3_R_roller_joint' type='revolute'>
      <pose relative_to='fourth_wheel_link'>-0.014144 -0.006 -0.019467 -2.51327 -0 1.5708</pose>
      <parent>fourth_wheel_link</parent>
      <child>r3_R_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r3_R_roller_link'>
      <pose relative_to='r3_R_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r3_R_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r3_R_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r4_R_roller_joint' type='revolute'>
      <pose relative_to='fourth_wheel_link'>0.014144 -0.006 -0.019467 2.51327 -0 1.5708</pose>
      <parent>fourth_wheel_link</parent>
      <child>r4_R_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r4_R_roller_link'>
      <pose relative_to='r4_R_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r4_R_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r4_R_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r5_R_roller_joint' type='revolute'>
      <pose relative_to='fourth_wheel_link'>0.022885 -0.006 0.007436 1.25664 -0 1.5708</pose>
      <parent>fourth_wheel_link</parent>
      <child>r5_R_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r5_R_roller_link'>
      <pose relative_to='r5_R_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r5_R_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r5_R_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r6_R_roller_joint' type='revolute'>
      <pose relative_to='fourth_wheel_link'>0 0.006 -0.024063 0 -0 1.5708</pose>
      <parent>fourth_wheel_link</parent>
      <child>r6_R_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r6_R_roller_link'>
      <pose relative_to='r6_R_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r6_R_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r6_R_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r7_R_roller_joint' type='revolute'>
      <pose relative_to='fourth_wheel_link'>0.022885 0.006 -0.007436 -1.25664 -0 1.5708</pose>
      <parent>fourth_wheel_link</parent>
      <child>r7_R_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r7_R_roller_link'>
      <pose relative_to='r7_R_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r7_R_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r7_R_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r8_R_roller_joint' type='revolute'>
      <pose relative_to='fourth_wheel_link'>0.014144 0.006 0.019467 -2.51327 -0 1.5708</pose>
      <parent>fourth_wheel_link</parent>
      <child>r8_R_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r8_R_roller_link'>
      <pose relative_to='r8_R_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r8_R_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r8_R_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r9_R_roller_joint' type='revolute'>
      <pose relative_to='fourth_wheel_link'>-0.014144 0.006 0.019467 2.51327 -0 1.5708</pose>
      <parent>fourth_wheel_link</parent>
      <child>r9_R_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r9_R_roller_link'>
      <pose relative_to='r9_R_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r9_R_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r9_R_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='second_wheel_joint' type='revolute'>
      <pose relative_to='base_link'>0.086338 0.086338 -0.022 0 0 -0.785398</pose>
      <parent>base_link</parent>
      <child>second_wheel_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <effort>100</effort>
          <velocity>100</velocity>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='second_wheel_link'>
      <pose relative_to='second_wheel_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 -0.011 0 0 -0 0</pose>
        <mass>0.25</mass>
        <inertia>
          <ixx>0.00031</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.0005</iyy>
          <iyz>0</iyz>
          <izz>0.00031</izz>
        </inertia>
      </inertial>
      <collision name='second_wheel_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/omni_wheel/omni_wheel.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='second_wheel_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/omni_wheel/omni_wheel.dae</uri>
          </mesh>
        </geometry>
      </visual>
      <self_collide>0</self_collide>
    </link>
    <joint name='r10_S_roller_joint' type='revolute'>
      <pose relative_to='second_wheel_link'>-0.022885 0.006 -0.007436 1.25664 -0 1.5708</pose>
      <parent>second_wheel_link</parent>
      <child>r10_S_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r10_S_roller_link'>
      <pose relative_to='r10_S_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r10_S_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r10_S_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r1_S_roller_joint' type='revolute'>
      <pose relative_to='second_wheel_link'>0 -0.006 0.024063 0 -0 1.5708</pose>
      <parent>second_wheel_link</parent>
      <child>r1_S_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r1_S_roller_link'>
      <pose relative_to='r1_S_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r1_S_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r1_S_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r2_S_roller_joint' type='revolute'>
      <pose relative_to='second_wheel_link'>-0.022885 -0.006 0.007436 -1.25664 -0 1.5708</pose>
      <parent>second_wheel_link</parent>
      <child>r2_S_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r2_S_roller_link'>
      <pose relative_to='r2_S_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r2_S_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r2_S_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r3_S_roller_joint' type='revolute'>
      <pose relative_to='second_wheel_link'>-0.014144 -0.006 -0.019467 -2.51327 -0 1.5708</pose>
      <parent>second_wheel_link</parent>
      <child>r3_S_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r3_S_roller_link'>
      <pose relative_to='r3_S_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r3_S_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r3_S_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r4_S_roller_joint' type='revolute'>
      <pose relative_to='second_wheel_link'>0.014144 -0.006 -0.019467 2.51327 -0 1.5708</pose>
      <parent>second_wheel_link</parent>
      <child>r4_S_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r4_S_roller_link'>
      <pose relative_to='r4_S_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r4_S_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r4_S_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r5_S_roller_joint' type='revolute'>
      <pose relative_to='second_wheel_link'>0.022885 -0.006 0.007436 1.25664 -0 1.5708</pose>
      <parent>second_wheel_link</parent>
      <child>r5_S_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r5_S_roller_link'>
      <pose relative_to='r5_S_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r5_S_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r5_S_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r6_S_roller_joint' type='revolute'>
      <pose relative_to='second_wheel_link'>0 0.006 -0.024063 0 -0 1.5708</pose>
      <parent>second_wheel_link</parent>
      <child>r6_S_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r6_S_roller_link'>
      <pose relative_to='r6_S_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r6_S_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r6_S_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r7_S_roller_joint' type='revolute'>
      <pose relative_to='second_wheel_link'>0.022885 0.006 -0.007436 -1.25664 -0 1.5708</pose>
      <parent>second_wheel_link</parent>
      <child>r7_S_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r7_S_roller_link'>
      <pose relative_to='r7_S_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r7_S_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r7_S_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r8_S_roller_joint' type='revolute'>
      <pose relative_to='second_wheel_link'>0.014144 0.006 0.019467 -2.51327 -0 1.5708</pose>
      <parent>second_wheel_link</parent>
      <child>r8_S_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r8_S_roller_link'>
      <pose relative_to='r8_S_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r8_S_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r8_S_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r9_S_roller_joint' type='revolute'>
      <pose relative_to='second_wheel_link'>-0.014144 0.006 0.019467 2.51327 -0 1.5708</pose>
      <parent>second_wheel_link</parent>
      <child>r9_S_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r9_S_roller_link'>
      <pose relative_to='r9_S_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r9_S_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r9_S_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='third_wheel_joint' type='revolute'>
      <pose relative_to='base_link'>-0.086338 0.086338 -0.022 0 -0 0.785398</pose>
      <parent>base_link</parent>
      <child>third_wheel_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <effort>100</effort>
          <velocity>100</velocity>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='third_wheel_link'>
      <pose relative_to='third_wheel_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 -0.011 0 0 -0 0</pose>
        <mass>0.25</mass>
        <inertia>
          <ixx>0.00031</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.0005</iyy>
          <iyz>0</iyz>
          <izz>0.00031</izz>
        </inertia>
      </inertial>
      <collision name='third_wheel_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/omni_wheel/omni_wheel.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='third_wheel_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/omni_wheel/omni_wheel.dae</uri>
          </mesh>
        </geometry>
      </visual>
      <self_collide>0</self_collide>
    </link>
    <joint name='r10_T_roller_joint' type='revolute'>
      <pose relative_to='third_wheel_link'>-0.022885 0.006 -0.007436 1.25664 -0 1.5708</pose>
      <parent>third_wheel_link</parent>
      <child>r10_T_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r10_T_roller_link'>
      <pose relative_to='r10_T_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r10_T_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r10_T_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r1_T_roller_joint' type='revolute'>
      <pose relative_to='third_wheel_link'>0 -0.006 0.024063 0 -0 1.5708</pose>
      <parent>third_wheel_link</parent>
      <child>r1_T_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r1_T_roller_link'>
      <pose relative_to='r1_T_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r1_T_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r1_T_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r2_T_roller_joint' type='revolute'>
      <pose relative_to='third_wheel_link'>-0.022885 -0.006 0.007436 -1.25664 -0 1.5708</pose>
      <parent>third_wheel_link</parent>
      <child>r2_T_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r2_T_roller_link'>
      <pose relative_to='r2_T_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r2_T_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r2_T_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r3_T_roller_joint' type='revolute'>
      <pose relative_to='third_wheel_link'>-0.014144 -0.006 -0.019467 -2.51327 -0 1.5708</pose>
      <parent>third_wheel_link</parent>
      <child>r3_T_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r3_T_roller_link'>
      <pose relative_to='r3_T_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r3_T_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r3_T_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r4_T_roller_joint' type='revolute'>
      <pose relative_to='third_wheel_link'>0.014144 -0.006 -0.019467 2.51327 -0 1.5708</pose>
      <parent>third_wheel_link</parent>
      <child>r4_T_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r4_T_roller_link'>
      <pose relative_to='r4_T_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r4_T_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r4_T_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r5_T_roller_joint' type='revolute'>
      <pose relative_to='third_wheel_link'>0.022885 -0.006 0.007436 1.25664 -0 1.5708</pose>
      <parent>third_wheel_link</parent>
      <child>r5_T_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r5_T_roller_link'>
      <pose relative_to='r5_T_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r5_T_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r5_T_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r6_T_roller_joint' type='revolute'>
      <pose relative_to='third_wheel_link'>0 0.006 -0.024063 0 -0 1.5708</pose>
      <parent>third_wheel_link</parent>
      <child>r6_T_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r6_T_roller_link'>
      <pose relative_to='r6_T_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r6_T_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r6_T_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r7_T_roller_joint' type='revolute'>
      <pose relative_to='third_wheel_link'>0.022885 0.006 -0.007436 -1.25664 -0 1.5708</pose>
      <parent>third_wheel_link</parent>
      <child>r7_T_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r7_T_roller_link'>
      <pose relative_to='r7_T_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r7_T_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r7_T_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r8_T_roller_joint' type='revolute'>
      <pose relative_to='third_wheel_link'>0.014144 0.006 0.019467 -2.51327 -0 1.5708</pose>
      <parent>third_wheel_link</parent>
      <child>r8_T_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r8_T_roller_link'>
      <pose relative_to='r8_T_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r8_T_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r8_T_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='r9_T_roller_joint' type='revolute'>
      <pose relative_to='third_wheel_link'>-0.014144 0.006 0.019467 2.51327 -0 1.5708</pose>
      <parent>third_wheel_link</parent>
      <child>r9_T_roller_link</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='r9_T_roller_link'>
      <pose relative_to='r9_T_roller_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.009</mass>
        <inertia>
          <ixx>1.257e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>3.42e-07</iyy>
          <iyz>0</iyz>
          <izz>1.257e-06</izz>
        </inertia>
      </inertial>
      <collision name='r9_T_roller_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/STL/roller/roller.stl</uri>
          </mesh>
        </geometry>
        <surface>
          <contact>
            <ode>
              <max_vel>0.01</max_vel>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu>1.5</mu>
              <mu2>1.5</mu2>
              <kp>1e15</kp>
              <kd>1e13</kd>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0.01</restitution_coefficient>
            <threshold>0</threshold>
          </bounce>
        </surface>
      </collision>
      <visual name='r9_T_roller_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rs_robot/meshes/DAE/roller/roller.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>

    <static>0</static>

    <plugin name="omni_robot_joint_state" filename="libgazebo_ros_joint_state_publisher.so">
      <ros>
          <remapping>~/out:=joint_states</remapping>
      </ros>
      <update_rate>20</update_rate>
      <joint_name>first_wheel_joint</joint_name>
      <joint_name>second_wheel_joint</joint_name>
      <joint_name>third_wheel_joint</joint_name>
      <joint_name>fourth_wheel_joint</joint_name>

      <joint_name>r1_F_roller_joint</joint_name>
      <joint_name>r2_F_roller_joint</joint_name>
      <joint_name>r3_F_roller_joint</joint_name>
      <joint_name>r4_F_roller_joint</joint_name>
      <joint_name>r5_F_roller_joint</joint_name>
      <joint_name>r6_F_roller_joint</joint_name>
      <joint_name>r7_F_roller_joint</joint_name>
      <joint_name>r8_F_roller_joint</joint_name>
      <joint_name>r9_F_roller_joint</joint_name>
      <joint_name>r10_F_roller_joint</joint_name>

      <joint_name>r1_R_roller_joint</joint_name>
      <joint_name>r2_R_roller_joint</joint_name>
      <joint_name>r3_R_roller_joint</joint_name>
      <joint_name>r4_R_roller_joint</joint_name>
      <joint_name>r5_R_roller_joint</joint_name>
      <joint_name>r6_R_roller_joint</joint_name>
      <joint_name>r7_R_roller_joint</joint_name>
      <joint_name>r8_R_roller_joint</joint_name>
      <joint_name>r9_R_roller_joint</joint_name>
      <joint_name>r10_R_roller_joint</joint_name>

      <joint_name>r1_S_roller_joint</joint_name>
      <joint_name>r2_S_roller_joint</joint_name>
      <joint_name>r3_S_roller_joint</joint_name>
      <joint_name>r4_S_roller_joint</joint_name>
      <joint_name>r5_S_roller_joint</joint_name>
      <joint_name>r6_S_roller_joint</joint_name>
      <joint_name>r7_S_roller_joint</joint_name>
      <joint_name>r8_S_roller_joint</joint_name>
      <joint_name>r9_S_roller_joint</joint_name>
      <joint_name>r10_S_roller_joint</joint_name>

      <joint_name>r1_T_roller_joint</joint_name>
      <joint_name>r2_T_roller_joint</joint_name>
      <joint_name>r3_T_roller_joint</joint_name>
      <joint_name>r4_T_roller_joint</joint_name>
      <joint_name>r5_T_roller_joint</joint_name>
      <joint_name>r6_T_roller_joint</joint_name>
      <joint_name>r7_T_roller_joint</joint_name>
      <joint_name>r8_T_roller_joint</joint_name>
      <joint_name>r9_T_roller_joint</joint_name>
      <joint_name>r10_T_roller_joint</joint_name>
    </plugin>

<ros2_control name="GazeboSystem" type="system">
    <hardware>
      <plugin>gazebo_ros2_control/GazeboSystem</plugin>
    </hardware>

    <joint name="first_wheel_joint">
      <command_interface name="velocity">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <state_interface name="velocity"/>
    </joint>

    <joint name="second_wheel_joint">
      <command_interface name="velocity">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <state_interface name="velocity"/>
    </joint>

    <joint name="third_wheel_joint">
      <command_interface name="velocity">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <state_interface name="velocity"/>
    </joint>

    <joint name="fourth_wheel_joint">
      <command_interface name="velocity">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <state_interface name="velocity"/>
    </joint>
  </ros2_control>

    <plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
      <ros>
        <namespace>omni1</namespace>
      </ros>
      <parameters>/home/bastian/Documents/omni_navigation/install/gazebo_simulation/share/gazebo_simulation/models/rs_robot/config/controllers.yaml</parameters>
    </plugin>
  </model>
</sdf>
christophfroehlich commented 3 months ago

We don't have any examples with directly loading sdf. Why would you do that, instead of using the URDF-way?

AshBastian commented 3 months ago

It is used in my example that way, that is why I have both data formats, an urdf and an sdf file

AshBastian commented 3 months ago

And the sdf file specifies the laserscaner, while the urdf just loads libgazebo_ros_laser.so, so I don't know, if the simple change to urdf will work as intended

christophfroehlich commented 3 months ago

parts inside <gazebo> tags in the URDF are directly used in the internally generated sdf. You can test this with

xacro /path/to/model.urdf.xacro > MODEL.urdf
gz sdf -p MODEL.urdf > MODEL.sdf
AshBastian commented 3 months ago

Thanks for the quick answer, I will try that and update here as soon as I'm finished

AshBastian commented 3 months ago

Screenshot from 2024-08-14 10-59-47 Screenshot from 2024-08-14 11-00-05 It seems to work to load the urdf corrrectly, but now that I try to start the system gazebo just crashes

AshBastian commented 3 months ago

And if I load your udrf file into my simulation, gazebo starts, but then I get the following error: Screenshot from 2024-08-14 11-48-26 And that is because of the namespace inside the yaml file, because my normal controller.yaml without the namespacing loads into the old state of not setting the update_rate

AshBastian commented 3 months ago

I finally found the problems in my system, there are two things you need to look out for, to not get into the same problem as me, with the other additional information in this Issue First of all, if you try to load the <plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so"> you need to use <parameters>$(find gazebo_simulation)/rest_of_path/controllers_namespaced.yaml</parameters> with the find ros_package, because the abolute path crashes the system. Second of all you need to use <mesh filename="file:///$(find robot_models)/rest_of_path/model.stl"/> with the file:/// search, because if you don't use that, your gazebo will just crash

AshBastian commented 3 months ago

Only one last thing I'm unable to get started, is to use an arg parameter in the urdf and the python file to set the namespace dynamically and not using specific files for each individual robot