Robotics StackExchange | Archived questions

Four Wheeled Robot doesn't turn but keep going straigth with a PID Controller

Hi everyone, I'm new with Gazebo and ROS. I'm trying to control a 4 wheeled robot using a PI controller, with Velocity Controller. During the simulation, if I set the same velocity for all wheels the robot moves in the right way (forward or backward). Instead, if I try a steering maneuver (a skid steering maneuver, increasing/decerasing left or right velocity) the robot doesn't turn and keep going straight, even tough the velocity that I read on /myrobot/jointstates are ok, as in the next picture (trying to turn right) image description

I've tried to control the robot with planar move plugin and it works fine. Instead, using the skid steeering plugin I always have the same problem.

I'm not sure if the problem is the controller implementation, but I have the feeling that the problem is due to some physical parameters. I've tried to increase or decrease mu1 and mu2 and to increase the mass of the wheels but nothing has changed. Any suggestions?

This is all my code. The urdf are taken from here. Thank you all!


Control config

summit:
  # Publish all joint states -----------------------------------
  joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 50  

  # Position Controllers ---------------------------------------
  joint_fl_effort_controller:
    type: velocity_controllers/JointVelocityController
    joint: summit_front_left_wheel_joint
    pid: {p: 1.0, i: 0.01, d: 0}
  joint_fr_effort_controller:
    type: velocity_controllers/JointVelocityController
    joint: summit_front_right_wheel_joint
    pid: {p: 1.0, i: 0.01, d: 0}
  joint_rl_effort_controller:
    type: velocity_controllers/JointVelocityController
    joint: summit_back_left_wheel_joint
    pid: {p: 1.0, i: 0.01, d: 0}
  joint_rr_effort_controller:
    type: velocity_controllers/JointVelocityController
    joint: summit_back_right_wheel_joint
    pid: {p: 1.0, i: 0.01, d: 0}

Control launch

<launch>

  <!-- Load joint controller configurations from YAML file to parameter server -->
  <rosparam file="$(find summit_control)/config/summit_control.yaml" command="load"/>

  <!-- load the controllers -->
  <node name="controller_spawner"
    pkg="controller_manager"
    type="spawner" respawn="false"
    output="screen" ns="/summit"
    args="joint_state_controller
    joint_fl_effort_controller
    joint_fr_effort_controller
    joint_rl_effort_controller
    joint_rr_effort_controller"
  />

  <!-- convert joint states to TF transforms for rviz, etc -->
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
    respawn="false" output="screen">
    <remap from="/joint_states" to="/summit/joint_states" />
  </node>


</launch>

Robot

<robot name="summit_xl" xmlns:xacro="http://www.ros.org/wiki/xacro">

    <!-- Import summit XL wheels -->
    <xacro:include filename="$(find summit_description)/urdf/wheels/omni_wheel.urdf.xacro" />
    <xacro:include filename="$(find summit_description)/urdf/base/summit_base.urdf.xacro" />

    <!-- Wheel parameters -->
    <xacro:property name="wheel_offset_x" value="0.2225" />    <!-- x,y,z in translation from base_link to the center of the wheel -->
    <xacro:property name="wheel_offset_y" value="0.2045" />
    <xacro:property name="wheel_offset_z" value="0.0" />

    <xacro:macro name="robot">
        <xacro:summit_base/>

        <xacro:omni_wheel prefix="summit_front_left" parent="summit_base_link" reflect="true">
            <origin xyz="${wheel_offset_x} ${wheel_offset_y} ${wheel_offset_z}" rpy="0 0 0"/>
        </xacro:omni_wheel>

        <xacro:omni_wheel prefix="summit_front_right" parent="summit_base_link" reflect="false">
            <origin xyz="${wheel_offset_x} -${wheel_offset_y} ${wheel_offset_z}" rpy="0 0 0"/>
        </xacro:omni_wheel>

        <xacro:omni_wheel prefix="summit_back_left" parent="summit_base_link" reflect="true">
            <origin xyz="-${wheel_offset_x} ${wheel_offset_y} ${wheel_offset_z}" rpy="0 0 0"/>
        </xacro:omni_wheel>

        <xacro:omni_wheel prefix="summit_back_right" parent="summit_base_link" reflect="false">
            <origin xyz="-${wheel_offset_x} -${wheel_offset_y} ${wheel_offset_z}" rpy="0 0 0"/>
        </xacro:omni_wheel>
   </xacro:macro>

   <xacro:robot/>

    <gazebo>
        <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
                <robotNamespace>/summit</robotNamespace>
        </plugin>
        <plugin name="p3d_base_controller" filename="libgazebo_ros_p3d.so">
            <alwaysOn>true</alwaysOn>
            <updateRate>50.0</updateRate>
            <bodyName>summit_base_footprint</bodyName>
            <topicName>odom</topicName>
            <gaussianNoise>0.0</gaussianNoise>
            <frameName>world</frameName>
            <xyzOffsets>0 0 0</xyzOffsets>
            <rpyOffsets>0 0 0</rpyOffsets>
        </plugin>
    </gazebo>

</robot>

omni_wheel.urdf

    <?xml version="1.0"?>
<robot name="wheel" xmlns:xacro="http://www.ros.org/wiki/xacro">

  <xacro:property name="PI" value="3.1415926535897931" />

  <!-- Wheels -->
  <xacro:property name="wheel_radius" value="0.127" />
  <xacro:property name="wheel_height" value="0.087" />
  <xacro:property name="wheel_mass" value="6.5" /> <!-- in kg-->

  <xacro:macro name="cylinder_inertia" params="m r h">
    <inertia  ixx="${m*(3*r*r+h*h)/12}" ixy = "0" ixz = "0"
              iyy="${m*r*r/2}" iyz = "0"
              izz="${m*(3*r*r+h*h)/12}" />
  </xacro:macro>

  <xacro:macro name="omni_wheel" params="prefix parent *origin reflect">

    <joint name="${prefix}_wheel_joint" type="continuous">
      <parent link="${parent}"/>
      <child link="${prefix}_wheel_link"/>
      <xacro:insert_block name="origin" />
      <axis xyz="0 1 0" rpy="0 0 0" />
      <limit effort="100" velocity="100"/>
      <joint_properties damping="0.0" friction="0.0"/>
    </joint>

    <link name="${prefix}_wheel_link">
      <visual>
        <origin xyz="0 0 0" rpy="0 0 0" />
        <xacro:if value="${reflect}">
          <geometry>
            <mesh filename="package://summit_description/meshes/wheels/omni_wheel_1.dae" />
          </geometry>
          </xacro:if>
          <xacro:unless value="${reflect}">
            <geometry>
              <mesh filename="package://summit_description/meshes/wheels/omni_wheel_2.dae" />
            </geometry>
            </xacro:unless>
      </visual>

      <collision>
                <origin xyz="0 0 0" rpy="${PI/2} 0 0" />
        <geometry>
                    <cylinder length="${wheel_height}" radius="${wheel_radius}" />
        </geometry>
      </collision>

      <inertial>
        <origin xyz="0 0 0" />
    <mass value="6.5"/>
         <inertia  ixx="0.0303" ixy = "0.0" ixz = "0.0"
              iyy="0.0524" iyz = "0.0"
              izz="0.0303" />
      </inertial>
    </link>

    <!-- Transmission is important to link the joints and the controller (see summit_xl_control/config/summit_xl_control.yaml)-->
    <transmission name="${prefix}_wheel_joint_trans">
      <type>transmission_interface/SimpleTransmission</type>
      <joint name="${prefix}_wheel_joint" >
        <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
      </joint>
      <actuator name="${prefix}_wheel_joint_motor">
     <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
         <mechanicalReduction>1</mechanicalReduction>
      </actuator>
    </transmission>

    <gazebo reference="${prefix}_wheel_link">
        <mu1 value="1"/>
        <mu2 value="1"/>
        <kp value="10000000.0" />
        <kd value="1.0" />
        <fdir1 value="1 0 0"/>
        <turnGravityOff>false</turnGravityOff>
    </gazebo>

  </xacro:macro>
</robot>

summit_base.urdf

<?xml version="1.0"?>
<robot name="summit_xl" xmlns:xacro="http://www.ros.org/wiki/xacro">

  <xacro:macro name="summit_base">

    <!-- Robot mechanical and motor parameters -->
    <xacro:property name="PI" value="3.1415926535897931"/>
    <xacro:property name="wheel_width" value="0.175" />

    <!-- BASE FOOTPRINT -->
    <link name="summit_base_footprint">
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <box size="0.001 0.001 0.001" />
            </geometry>
        </visual>
    </link>

    <joint name="summit_base_footprint_joint" type="fixed">
        <origin xyz="0 0 ${wheel_radius}" rpy="0 0 0" /> <!-- ${wheel_radius} property must be defined inside wheel description -->
        <parent link="summit_base_footprint"/>
        <child link="summit_base_link" />
    </joint>

  <!-- BASE_LINK -->
  <link name="summit_base_link">
    <inertial>
      <mass value="125.0" />
      <origin xyz="0 0 0" />
      <inertia  ixx="1.391" ixy="0.004"  ixz="0.0"  iyy="6.853"  iyz="0.0"  izz="6.125" />
    </inertial>

    <visual>
       <origin xyz="0 0 0" rpy="0 0 0" />

       <geometry>
         <mesh filename="package://summit_description/meshes/base/summit_base.dae"/>
       </geometry>

       <material name="darkgrey">
         <color rgba="0.1 0.1 0.1 1"/>
       </material>

    </visual>

    <collision>
       <origin xyz="0 0 0" rpy="0 0 0 " />
       <geometry>
         <mesh filename="package://summit_description/meshes/base/summit_base.dae"/>
       </geometry>
    </collision>

  </link>

  </xacro:macro>

</robot>

Asked by dries on 2021-03-03 07:49:31 UTC

Comments

Did you solve the problem, i have the same issue.

Asked by UgurY on 2022-02-27 10:40:57 UTC

Answers