Gazebo | Ignition | Community
Ask Your Question

Revision history [back]

Why do I need to apply large force (10 kN) to move my robot?

I modeled my physical, simple diff-drive robot with two larger drive wheels and two casters. The robot total weight is around 30 kg. Body size is L=0.512 m, W=0.384 m , H=0.211 m

When I interact with the model (Apply Force/Torque) in Gazebo, I need to use very large forces to move it: 10 kN barely moves it, 100 kN pushes it around 1 m forward. The force feels completely disproportional.

Is there anything wrong with my model because this does not pass a smell test?

Appreciate any feedback.

The body inertial is as follows:

 <inertial>
  <mass value="30.0"/>
  <inertia ixx="0.7666624999999999" ixy="0.0" ixz="0.0" iyy="1.024" iyz="0.0" izz="0.47994250000000005"/>
</inertial>

The entire URDF:

<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- |    This document was autogenerated by xacro from travik.xacro                   | -->
<!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
<!-- =================================================================================== -->
<robot name="travik">
  <material name="black">
    <color rgba="0.0 0.0 0.0 1.0"/>
  </material>
  <material name="blue">
    <color rgba="0.0 0.0 0.8 1.0"/>
  </material>
  <material name="green">
    <color rgba="0.0 0.8 0.0 1.0"/>
  </material>
  <material name="grey">
    <color rgba="0.2 0.2 0.2 1.0"/>
  </material>
  <material name="orange">
    <color rgba="1.0 0.4235294117647059 0.0392156862745098 1.0"/>
  </material>
  <material name="brown">
    <color rgba="0.8705882352941177 0.8117647058823529 0.7647058823529411 1.0"/>
  </material>
  <material name="red">
    <color rgba="0.8 0.0 0.0 1.0"/>
  </material>
  <material name="white">
    <color rgba="1.0 1.0 1.0 1.0"/>
  </material>
  <!-- https://en.wikipedia.org/wiki/List_of_moments_of_inertia#List_of_3D_inertia_tensors -->
  <!-- prevent "The root base_link has an inertia specified in the URDF, but KDL" error -->
  <link name="base_footprint"/>
  <joint name="base_joint" type="fixed">
    <parent link="base_footprint"/>
    <child link="base_link"/>
    <origin rpy="0 0 0" xyz="0.0 0.0 0.010"/>
  </joint>
  <link name="base_link">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <box size="0.512 0.384 0.211"/>
      </geometry>
      <material name="green"/>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <box size="0.512 0.384 0.211"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="30.0"/>
      <inertia ixx="0.7666624999999999" ixy="0.0" ixz="0.0" iyy="1.024" iyz="0.0" izz="0.47994250000000005"/>
    </inertial>
  </link>
  <link name="left_front_wheel">
    <visual>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.083" radius="0.128"/>
      </geometry>
      <material name="black"/>
    </visual>
    <collision>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.083" radius="0.128"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
      <mass value="3"/>
      <inertia ixx="0.01401025" ixy="0" ixz="0" iyy="0.01401025" iyz="0" izz="0.024576"/>
    </inertial>
  </link>
  <joint name="left_front_wheel_joint" type="continuous">
    <axis rpy="0 0 0" xyz="0 1 0"/>
    <parent link="base_link"/>
    <child link="left_front_wheel"/>
    <origin rpy="0 0 0" xyz="0.128 0.2495 -0.04149999999999998"/>
    <dynamics damping="0.7"/>
  </joint>
  <link name="right_front_wheel">
    <visual>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.083" radius="0.128"/>
      </geometry>
      <material name="black"/>
    </visual>
    <collision>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.083" radius="0.128"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
      <mass value="3"/>
      <inertia ixx="0.01401025" ixy="0" ixz="0" iyy="0.01401025" iyz="0" izz="0.024576"/>
    </inertial>
  </link>
  <joint name="right_front_wheel_joint" type="continuous">
    <axis rpy="0 0 0" xyz="0 1 0"/>
    <parent link="base_link"/>
    <child link="right_front_wheel"/>
    <origin rpy="0 0 0" xyz="0.128 -0.2495 -0.04149999999999998"/>
    <dynamics damping="0.7"/>
  </joint>
  <!-- caster -->
  <!-- caster_swivel -->
  <!-- caster wheel -->
  <link name="left_rear_caster_swivel">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.125" radius="0.0125"/>
      </geometry>
      <material name="blue"/>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.125" radius="0.0125"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="1"/>
      <inertia ixx="0.0013411458333333333" ixy="0" ixz="0" iyy="0.0013411458333333333" iyz="0" izz="7.812500000000002e-05"/>
    </inertial>
    <dynamics damping="0.7"/>
  </link>
  <joint name="left_rear_swivel_joint" type="continuous">
    <axis rpy="0 0 0" xyz="0 0 1"/>
    <parent link="base_link"/>
    <child link="left_rear_caster_swivel"/>
    <origin rpy="0 0 0" xyz="-0.256 0.192 0"/>
  </joint>
  <link name="left_rear_caster_wheel">
    <visual>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.051" radius="0.0895"/>
      </geometry>
      <material name="black"/>
    </visual>
    <collision>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.051" radius="0.0895"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="1"/>
      <inertia ixx="0.0022193124999999995" ixy="0" ixz="0" iyy="0.0022193124999999995" iyz="0" izz="0.004005125"/>
    </inertial>
  </link>
  <joint name="left_rear_wheel_joint" type="continuous">
    <axis rpy="0 0 0" xyz="0 1 0"/>
    <parent link="left_rear_caster_swivel"/>
    <child link="left_rear_caster_wheel"/>
    <origin rpy="0 0 0" xyz="-0.04475 0 -0.07999999999999999"/>
    <dynamics damping="0.7"/>
  </joint>
  <!-- caster_swivel -->
  <!-- caster wheel -->
  <link name="right_rear_caster_swivel">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.125" radius="0.0125"/>
      </geometry>
      <material name="blue"/>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.125" radius="0.0125"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="1"/>
      <inertia ixx="0.0013411458333333333" ixy="0" ixz="0" iyy="0.0013411458333333333" iyz="0" izz="7.812500000000002e-05"/>
    </inertial>
    <dynamics damping="0.7"/>
  </link>
  <joint name="right_rear_swivel_joint" type="continuous">
    <axis rpy="0 0 0" xyz="0 0 1"/>
    <parent link="base_link"/>
    <child link="right_rear_caster_swivel"/>
    <origin rpy="0 0 0" xyz="-0.256 -0.192 0"/>
  </joint>
  <link name="right_rear_caster_wheel">
    <visual>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.051" radius="0.0895"/>
      </geometry>
      <material name="black"/>
    </visual>
    <collision>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.051" radius="0.0895"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="1"/>
      <inertia ixx="0.0022193124999999995" ixy="0" ixz="0" iyy="0.0022193124999999995" iyz="0" izz="0.004005125"/>
    </inertial>
  </link>
  <joint name="right_rear_wheel_joint" type="continuous">
    <axis rpy="0 0 0" xyz="0 1 0"/>
    <parent link="right_rear_caster_swivel"/>
    <child link="right_rear_caster_wheel"/>
    <origin rpy="0 0 0" xyz="-0.04475 0 -0.07999999999999999"/>
    <dynamics damping="0.7"/>
  </joint>
  <!-- Size of square 'camera' box -->
  <joint name="camera_joint" type="fixed">
    <axis xyz="0 1 0"/>
    <origin rpy="0 0 0" xyz="0.256 0 0.06799999999999999"/>
    <parent link="base_link"/>
    <child link="camera_link"/>
  </joint>
  <!-- Camera -->
  <link name="camera_link">
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <box size="0.05 0.05 0.05"/>
      </geometry>
    </collision>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <box size="0.05 0.05 0.05"/>
      </geometry>
      <material name="red"/>
    </visual>
    <inertial>
      <mass value="1e-5"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
    </inertial>
  </link>
  <!-- generate an optical frame http://www.ros.org/reps/rep-0103.html#suffix-frames
        so that ros and opencv can operate on the camera frame correctly -->
  <joint name="camera_optical_joint" type="fixed">
    <!-- these values have to be these values otherwise the gazebo camera image
          won't be aligned properly with the frame it is supposedly originating from -->
    <origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
    <parent link="camera_link"/>
    <child link="camera_link_optical"/>
  </joint>
  <link name="camera_link_optical"/>
  <!-- Size of 'laser' -->
  <joint name="laser_joint" type="fixed">
    <axis xyz="0 1 0"/>
    <origin rpy="0 0 0" xyz="0.128 0 0.1255"/>
    <parent link="base_link"/>
    <child link="laser_link"/>
  </joint>
  <!-- laser -->
  <link name="laser_link">
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.04" radius="0.02"/>
      </geometry>
    </collision>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.04" radius="0.02"/>
      </geometry>
      <material name="red"/>
    </visual>
    <inertial>
      <mass value="1e-5"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
    </inertial>
  </link>
  <!-- ros_control plugin -->
  <gazebo>
    <plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
      <robotNamespace>/travik</robotNamespace>
      <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
    </plugin>
  </gazebo>
  <!-- Friction coefficients
       https://www.engineeringtoolbox.com/friction-coefficients-d_778.html -->
  <gazebo reference="base_link">
    <mu1>0.2</mu1>
    <mu2>0.2</mu2>
    <material>Gazebo/Green</material>
  </gazebo>
  <gazebo reference="body_link">
    <mu1>0.2</mu1>
    <mu2>0.2</mu2>
    <material>Gazebo/Green</material>
  </gazebo>
  <gazebo reference="left_front_wheel">
    <mu1>0.2</mu1>
    <!-- 0.9 rubber on dry asphalt -->
    <mu2>0.2</mu2>
    <material>Gazebo/Black</material>
  </gazebo>
  <gazebo reference="right_front_wheel">
    <mu1>0.9</mu1>
    <!-- rubber on dry asphalt -->
    <mu2>0.2</mu2>
    <material>Gazebo/Black</material>
  </gazebo>
  <gazebo reference="left_rear_caster_swivel">
    <mu1>0.9</mu1>
    <mu2>0.2</mu2>
    <material>Gazebo/Orange</material>
  </gazebo>
  <gazebo reference="right_rear_caster_swivel">
    <mu1>0.2</mu1>
    <mu2>0.2</mu2>
    <material>Gazebo/Orange</material>
  </gazebo>
  <gazebo reference="left_rear_caster_wheel">
    <mu1>0.9</mu1>
    <!-- rubber on dry asphalt -->
    <mu2>0.2</mu2>
    <material>Gazebo/Black</material>
  </gazebo>
  <gazebo reference="right_rear_caster_wheel">
    <mu1>0.9</mu1>
    <!-- rubber on dry asphalt -->
    <mu2>0.2</mu2>
    <material>Gazebo/Black</material>
  </gazebo>
  <!-- Inno LD06 LIDAR-->
  <gazebo reference="laser_link">
    <sensor name="head_laser" type="gpu_ray">
      <pose>0.128 0 0 0 0 0</pose>
      <visualize>false</visualize>
      <update_rate>40</update_rate>
      <ray>
        <scan>
          <horizontal>
            <samples>720</samples>
            <resolution>1</resolution>
            <min_angle>-3.14159</min_angle>
            <max_angle>3.14159</max_angle>
          </horizontal>
        </scan>
        <range>
          <min>0.05</min>
          <max>12.0</max>
          <resolution>0.01</resolution>
        </range>
        <noise>
          <type>gaussian</type>
          <!-- Noise parameters based on published spec for Hokuyo laser
               achieving "+-30mm" accuracy at range < 10m.  A mean of 0.0m and
               stddev of 0.01m will put 99.7% of samples within 0.03m of the true
               reading. -->
          <mean>0.0</mean>
          <stddev>0.01</stddev>
        </noise>
      </ray>

-      
      <plugin filename="libgazebo_ros_gpu_laser.so" name="gazebo_ros_head_ld06_controller">
        <topicName>/scan</topicName>
        <frameName>laser_link</frameName>
      </plugin>
    </sensor>
  </gazebo>
  <!-- camera -->
  <gazebo reference="camera_link">
    <sensor name="head_camera" type="camera">
      <update_rate>30.0</update_rate>
      <camera name="head">
        <horizontal_fov>1.3962634</horizontal_fov>
        <image>
          <width>800</width>
          <height>800</height>
          <format>R8G8B8</format>
        </image>
        <clip>
          <near>0.02</near>
          <far>300</far>
        </clip>
        <noise>
          <type>gaussian</type>
          <!-- Noise is sampled independently per pixel on each frame.
               That pixel's noise value is added to each of its color
               channels, which at that point lie in the range [0,1]. -->
          <mean>0.0</mean>
          <stddev>0.007</stddev>
        </noise>
      </camera>
      <plugin filename="libgazebo_ros_camera.so" name="camera_controller">
        <alwaysOn>true</alwaysOn>
        <updateRate>0.0</updateRate>
        <cameraName>/travik/camera1</cameraName>
        <imageTopicName>image_raw</imageTopicName>
        <cameraInfoTopicName>camera_info</cameraInfoTopicName>
        <frameName>camera_link_optical</frameName>
        <!-- setting hackBaseline to anything but 0.0 will cause a misalignment
            between the gazebo sensor image and the frame it is supposed to
            be attached to -->
        <hackBaseline>0.0</hackBaseline>
        <distortionK1>0.0</distortionK1>
        <distortionK2>0.0</distortionK2>
        <distortionK3>0.0</distortionK3>
        <distortionT1>0.0</distortionT1>
        <distortionT2>0.0</distortionT2>
        <CxPrime>0</CxPrime>
        <Cx>0.0</Cx>
        <Cy>0.0</Cy>
        <focalLength>0.0</focalLength>
      </plugin>
    </sensor>
  </gazebo>
  <gazebo>
    <plugin filename="libgazebo_ros_diff_drive.so" name="differential_drive_controller">
      <alwaysOn>false</alwaysOn>
      <!-- Plugin update rate in Hz -->
      <updateRate>20</updateRate>
      <!-- Set to true to swap right and left wheels, defaults to true -->
      <legacyMode>false</legacyMode>
      <!-- Name of left joint, defaults to `left_joint` -->
      <leftJoint>left_front_wheel_joint</leftJoint>
      <!-- Name of right joint, defaults to `right_joint` -->
      <rightJoint>right_front_wheel_joint</rightJoint>
      <!-- The distance from the center of one wheel to the other, in meters, defaults to 0.34 m -->
      <wheelSeparation>0.083 + 0.384</wheelSeparation>
      <!-- Diameter of the wheels, in meters, defaults to 0.15 m -->
      <wheelDiameter>0.256</wheelDiameter>
      <!-- Wheel acceleration, in rad/s^2, defaults to 0.0 rad/s^2 -->
      <wheelAcceleration>1.0</wheelAcceleration>
      <!-- Maximum torque which the wheels can produce, in Nm, defaults to 5 Nm -->
      <wheelTorque>20</wheelTorque>
      <!-- Topic to receive geometry_msgs/Twist message commands, defaults to `cmd_vel` -->
      <commandTopic>/cmd_vel</commandTopic>
      <!-- Topic to publish nav_msgs/Odometry messages, defaults to `odom` -->
      <odometryTopic>/odom</odometryTopic>
      <!-- Odometry frame, defaults to `/odom` -->
      <odometryFrame>odom</odometryFrame>
      <!-- Robot frame to calculate odometry from, defaults to `base_footprint` -->
      <robotBaseFrame>base_footprint</robotBaseFrame>
      <!-- Odometry source, 0 for ENCODER, 1 for WORLD, defaults to WORLD -->
      <odometrySource>1</odometrySource>
      <!-- defaults to 1 -->
      <publishTF>1</publishTF>
      <!-- Set to true to publish transforms for the wheel links, defaults to false -->
      <publishWheelTF>true</publishWheelTF>
      <!-- Set to true to publish transforms for the odometry, defaults to true -->
      <publishOdom>true</publishOdom>
      <!-- Set to true to publish transforms for the odometry, defaults to true -->
      <publishOdomTF>true</publishOdomTF>
      <!-- Set to true to publish sensor_msgs/JointState on /joint_states for the wheel joints, defaults to false -->
      <publishWheelJointState>true</publishWheelJointState>
      <rosDebugLevel>na</rosDebugLevel>
    </plugin>
  </gazebo>
</robot>