Gazebo | Ignition | Community
Ask Your Question
0

Wheels rotating without any order given

asked 2018-04-25 11:28:07 -0600

DonutsSauvage gravatar image

updated 2018-04-25 11:45:02 -0600

sloretz gravatar image

Hello everyone, I know there are a lot of topics about this kind of problems but I read through a lot of them without getting an answer to my problem. So basically, I have a robot which is made of a base_link (collada file, but it's similar to a rectangle), 2 caster wheels to the front and 2 rotating wheels to the back. So what happens when I launch the simulation, the robot rotates around the Z axis without any cmd_vel being applied to the wheel or for or whatever. I'm really lost here guys so I request your help. I also add that when I turn on collisions view on Gazebo, it shows that every part of my robot is in collision, even with the self-collide turned on false, and the floor itslef is also in collision (it's the basic empty world). I join you my xacro file so that you may help me, and thanks everyone for reading to this point. I'm using Gazebo 7.0.

robot.xacro:

<?xml version='1.0'?>
<robot name="robot" xmlns:xacro="http://www.ros.org/wiki/xacro">
        <!-- Put here the robot description -->

<xacro:include filename="$(find robot_description)/urdf/robot.gazebo" />
<xacro:include filename="$(find robot_description)/urdf/macros.xacro" />


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

<xacro:property name="chassis_Height" value="0.002"/>
<xacro:property name="chassis_Length" value="0.310"/>
<xacro:property name="chassis_Width" value="0.240"/>
<xacro:property name="chassis_Mass" value="0.375"/>

<xacro:property name="casterRadius" value="0.0075"/>
<xacro:property name="casterMass" value="0.2"/>

<xacro:property name="wheelWidth" value="0.03175"/>
<xacro:property name="wheelRadius" value="0.03175"/>
<xacro:property name="wheelMass" value="0.2"/>


<link name="base_link"/>
<!-- Link chassis -->
<link name='chassis_link'>
  <collision>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <geometry>
      <mesh filename="package://robot_description/meshes/chassis_milieu.dae"/>
    </geometry>
  </collision>
  <visual>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <geometry>
      <mesh filename="package://robot_description/meshes/chassis_milieu.dae"/>
    </geometry>
  </visual>
  <inertial>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <mass value="${chassis_Mass}"/>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <box_inertia m="${chassis_Mass}" x="${chassis_Length}" y="${chassis_Width}"           z="${chassis_Height}"/>
  </inertial>
</link>

<!-- Joint chassis sur base_link -->
<joint name="base_joint" type="fixed">
  <origin xyz="0 0 100" rpy="0 0 0"/> <!-- The 100 here was to make sure my robot isn't actually conflicting with the floor -->
  <parent link="base_link"/>
  <child link="chassis_link"/>
</joint>

<!-- Macro (link+joint) roues -->
<wheel lr="left" tY="1"/>
<wheel lr="right" tY="-1"/>

<!-- Link roue libre gauche  -->
<link name="caster_wheel_left">
  <collision>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <geometry>
      <sphere radius="${casterRadius}"/>
    </geometry>
  </collision>
  <visual>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <geometry>
      <sphere radius="${casterRadius}"/>
    </geometry>
  </visual>
  <inertial>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <mass value="${casterMass}"/>
    <sphere_inertia m="${casterMass}" r="${casterRadius}"/>
  </inertial>
</link>

<joint name="caster_wheel_left_joint" type="continuous">
 <origin xyz="0.15 0.05 ${-casterRadius-chassis_Height/2}" rpy="0 0 0"/>
 <axis xyz="1 1 1" rpy="0 0 ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2018-04-27 02:37:02 -0600

Raskkii gravatar image

There are some things you can try to minimize the drift.

1) Increase the kp value of your wheels like so:

<gazebo reference="${lr}_wheel">
  <mu1 value="1.0"/>
  <mu2 value="1.0"/>
  <kp  value="10000000.0" />
  <kd  value="1.0" />
  <fdir1 value="1 0 0"/>
</gazebo>

This is the value I use and I get minimal drift. (though my robot is 4-wheeled)

2) Lower your robot's center of mass by lowering the body's intertia z position.

3) Increase real_time_update rate in your physics settings (while lowering max_step_size) if your computer can handle it.

Though because it is a vehicle with two casters some of the drift may be unavoidable considering one side of the robot is very easy to move.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2018-04-25 11:23:05 -0600

Seen: 5,354 times

Last updated: Apr 27 '18