mobile articulated robot wheels slipping instead of rolling

asked 2023-04-22 02:00:37 -0600

zonared gravatar image

Hi there everyone and thanks for helping. A quick bit of background, I've built an articulated center steering four(4) wheeled mobile robot. I'm struggling to find any navigation packages which suit this type of geometry (currently using TEB nav, badly) so thought I would try RL (reinforcement learning) using robogym but firstly I need my robot to work properly in the simulator.

This brings me to my problem, when I articulate in the sim, the front wheels just slide sideways. I have an animated GIF of the real robot and one of the sim robot (which I cant add to this post because I don't have any karma)

After you launch all the nodes and everything is running if you publish a command to the controller manager to rotate the center steering you will see the front section rotate which will slide the wheels (no roller or rotation). I reality it should bend in the middle and all wheels should turn slightly.

Why are my wheels sliding? I have tried heaps of different 'mu' values, I've tried cone_model friction, I've tried bullet physics, I've tried the fdir option, adjusting the contact_surface_layer distance, nothing seems to make any difference. Any help is really appreciated, thanks in advance..

Run this command to articulate:

$ rostopic pub /artmule_body/fpj_position_controller/command std_msgs/Float64 "data: -0.50"

This is my world launch file /artmule_body/launch/gazebo.launch:

  <launch>
        <!-- these are the arguments you can pass this launch file, for example paused:=true -->
        <arg name="paused" default="false"/>
        <arg name="use_sim_time" default="true"/>
        <arg name="extra_gazebo_args" default=""/>
        <arg name="gui" default="true"/>
        <arg name="recording" default="false"/>
        <arg name="headless" default="false"/>
        <arg name="debug" default="false"/>
        <arg name="physics" default="ode"/>
        <arg name="verbose" default="false"/>
        <arg name="output" default="screen"/>
        <arg name="world_name" default="$(find artmule_body)/world/empty_world.world"/>
        <arg name="respawn_gazebo" default="false"/>
        <arg name="use_clock_frequency" default="false"/>
        <arg name="pub_clock_frequency" default="100"/>
        <arg name="enable_ros_network" default="true" />
        <arg name="server_required" default="false"/>
        <arg name="gui_required" default="false"/>

        <!-- set use_sim_time flag -->
        <param name="/use_sim_time" value="$(arg use_sim_time)"/>

        <!-- set command arguments -->
        <arg unless="$(arg paused)" name="command_arg1" value=""/>
        <arg     if="$(arg paused)" name="command_arg1" value="-u"/>
        <arg unless="$(arg recording)" name="command_arg2" value=""/>
        <arg     if="$(arg recording)" name="command_arg2" value="-r"/>
        <arg unless="$(arg verbose)" name="command_arg3" value=""/>
        <arg     if="$(arg verbose)" name="command_arg3" value="--verbose"/>
        <arg unless="$(arg debug)" name="script_type" value="gzserver"/>
        <arg     if="$(arg debug)" name="script_type" value="debug"/>

        <!-- start gazebo server-->
        <group if="$(arg use_clock_frequency)">
                  <param name="gazebo/pub_clock_frequency" value="$(arg pub_clock_frequency)" />
        </group>
        <group>
                  <param name="gazebo/enable_ros_network" value="$(arg enable_ros_network)" />
        </group>
        <node name="gazebo" pkg="gazebo_ros" type="$(arg script_type)" respawn="$(arg respawn_gazebo)" output="$(arg output)"
        args="$(arg command_arg1) $(arg command_arg2) $(arg command_arg3) -e $(arg physics) $(arg extra_gazebo_args) $(arg world_name)"
required="$(arg server_required)" />

        <!-- start gazebo client -->
        <group if="$(arg gui)">
                  <node name="gazebo_gui" pkg="gazebo_ros" type="gzclient" respawn="false" output="$(arg output)" args="$(arg command_arg3)"
  required="$(arg gui_required)"/>
        </group>

        <node
          name="tf_footprint_base"
          pkg="tf ...
(more)
edit retag flag offensive close merge delete