Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

In the TurtleBot3 Gazebo simulation, the angular velocity exhibits significant fluctuations at certain points, leading to instability. ( I edited the .gazebo.xacro file) #1029

Open
2 tasks done
2892510130 opened this issue Aug 8, 2024 · 4 comments
Assignees

Comments

@2892510130
Copy link

2892510130 commented Aug 8, 2024

  1. Which TurtleBot3 platform do you use?

    • Waffle Pi
  2. Which ROS is working with TurtleBot3?

    • ROS 1 Noetic
  3. Please describe the issue in detail.
    I am using Ubuntu 20.04 and Gazebo 11.11 to simulate the TurtleBot 3 Waffle Pi robot (roslaunch turtlebot3_empty_world.launch). I modified the .gazebo.xacro file because the default settings result in significant slipping, especially at higher speeds (e.g., vx = 1.0, w = 1.0, which are not considered excessively fast).

    Then I encountered the issue depicted in the image below, where the angular velocity is unstable and exhibits significant spikes. How should I adjust the parameters in the .gazebo.xacro file to address this problem? maxVel, minDepth seems to have no effect on this issue. So it maybe other params like kp, kd...

Untitled

Here is the edited .gazebo.xacro file:

<?xml version="1.0"?>
<robot name="turtlebot3_waffle_pi_sim" xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:arg name="laser_visual"  default="false"/>
  <xacro:arg name="camera_visual" default="false"/>
  <xacro:arg name="imu_visual"    default="false"/>

  <gazebo reference="base_link">
    <material>Gazebo/DarkGrey</material>
  </gazebo>

  <gazebo reference="wheel_left_link">
    <mu1>1.0</mu1>
    <mu2>1.0</mu2>
    <soft_cfm>0.0</soft_cfm>
    <soft_erp>0.2</soft_erp>
    <kp>1e15</kp>
    <kd>4e12</kd>
    <minDepth>0.001</minDepth>
    <maxVel>10</maxVel>
    <fdir1>1 0 0</fdir1>
    <material>Gazebo/FlatBlack</material>
  </gazebo>

  <gazebo reference="wheel_right_link">
    <mu1>1.0</mu1>
    <mu2>1.0</mu2>
    <soft_cfm>0.0</soft_cfm>
    <soft_erp>0.2</soft_erp>
    <kp>1e15</kp>
    <kd>4e12</kd>
    <minDepth>0.001</minDepth>
    <maxVel>10</maxVel>
    <fdir1>1 0 0</fdir1>
    <material>Gazebo/FlatBlack</material>
  </gazebo>

  <gazebo reference="caster_back_right_link">
    <mu1>0.01</mu1>
    <mu2>0.01</mu2>
    <soft_cfm>0.0</soft_cfm>
    <soft_erp>0.2</soft_erp>
    <kp>1e15</kp>
    <kd>4e12</kd>
    <minDepth>0.001</minDepth>
    <maxVel>10</maxVel>
    <material>Gazebo/FlatBlack</material>
  </gazebo>

  <gazebo reference="caster_back_left_link">
    <mu1>0.01</mu1>
    <mu2>0.01</mu2>
    <soft_cfm>0.0</soft_cfm>
    <soft_erp>0.2</soft_erp>
    <kp>1e15</kp>
    <kd>4e12</kd>
    <minDepth>0.001</minDepth>
    <maxVel>10</maxVel>
    <material>Gazebo/FlatBlack</material>
  </gazebo>

  <gazebo reference="imu_link">
    <sensor type="imu" name="imu">
      <always_on>true</always_on>
      <visualize>$(arg imu_visual)</visualize>
    </sensor>
    <material>Gazebo/Grey</material>
  </gazebo>

  <gazebo>
    <plugin name="turtlebot3_waffle_pi_controller" filename="libgazebo_ros_diff_drive.so">
      <commandTopic>cmd_vel</commandTopic>
      <odometryTopic>odom</odometryTopic>
      <odometryFrame>odom</odometryFrame>
      <odometrySource>world</odometrySource>
      <publishOdomTF>true</publishOdomTF>
      <robotBaseFrame>base_footprint</robotBaseFrame>
      <publishWheelTF>false</publishWheelTF>
      <publishTf>true</publishTf>
      <publishWheelJointState>true</publishWheelJointState>
      <legacyMode>false</legacyMode>
      <updateRate>100</updateRate>
      <leftJoint>wheel_left_joint</leftJoint>
      <rightJoint>wheel_right_joint</rightJoint>
      <wheelSeparation>0.287</wheelSeparation>
      <wheelDiameter>0.066</wheelDiameter>
      <wheelAcceleration>4</wheelAcceleration>
      <wheelTorque>10</wheelTorque>
      <rosDebugLevel>na</rosDebugLevel>
    </plugin>
  </gazebo>

  <gazebo>
    <plugin name="imu_plugin" filename="libgazebo_ros_imu.so">
      <alwaysOn>true</alwaysOn>
      <bodyName>imu_link</bodyName>
      <frameName>imu_link</frameName>
      <topicName>imu</topicName>
      <serviceName>imu_service</serviceName>
      <gaussianNoise>0.0</gaussianNoise>
      <updateRate>0</updateRate>
      <imu>
        <noise>
          <type>gaussian</type>
          <rate>
            <mean>0.0</mean>
            <stddev>2e-4</stddev>
            <bias_mean>0.0000075</bias_mean>
            <bias_stddev>0.0000008</bias_stddev>
          </rate>
          <accel>
            <mean>0.0</mean>
            <stddev>1.7e-2</stddev>
            <bias_mean>0.1</bias_mean>
            <bias_stddev>0.001</bias_stddev>
          </accel>
        </noise>
      </imu>
    </plugin>
  </gazebo>

  <gazebo reference="base_scan">
    <material>Gazebo/FlatBlack</material>
    <sensor type="ray" name="lds_lfcd_sensor">
      <pose>0 0 0 0 0 0</pose>
      <visualize>$(arg laser_visual)</visualize>
      <update_rate>5</update_rate>
      <ray>
        <scan>
          <horizontal>
            <samples>360</samples>
            <resolution>1</resolution>
            <min_angle>0.0</min_angle>
            <max_angle>6.28319</max_angle>
          </horizontal>
        </scan>
        <range>
          <min>0.120</min>
          <max>3.5</max>
          <resolution>0.015</resolution>
        </range>
        <noise>
          <type>gaussian</type>
          <mean>0.0</mean>
          <stddev>0.01</stddev>
        </noise>
      </ray>
      <plugin name="gazebo_ros_lds_lfcd_controller" filename="libgazebo_ros_laser.so">
        <topicName>scan</topicName>
        <frameName>base_scan</frameName>
      </plugin>
    </sensor>
  </gazebo>

<!--link : https://www.raspberrypi.org/documentation/hardware/camera/-->
  <gazebo reference="camera_rgb_frame">
    <sensor type="camera" name="Pi Camera">
      <always_on>true</always_on>
      <visualize>$(arg camera_visual)</visualize>
      <camera>
          <horizontal_fov>1.085595</horizontal_fov>
          <image>
              <width>640</width>
              <height>480</height>
              <format>R8G8B8</format>
          </image>
          <clip>
              <near>0.03</near>
              <far>100</far>
          </clip>
      </camera>
      <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
        <alwaysOn>true</alwaysOn>
        <updateRate>30.0</updateRate>
        <cameraName>camera</cameraName>
        <frameName>camera_rgb_optical_frame</frameName>
        <imageTopicName>rgb/image_raw</imageTopicName>
        <cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
        <hackBaseline>0.07</hackBaseline>
        <distortionK1>0.0</distortionK1>
        <distortionK2>0.0</distortionK2>
        <distortionK3>0.0</distortionK3>
        <distortionT1>0.0</distortionT1>
        <distortionT2>0.0</distortionT2>
      </plugin>
    </sensor>
  </gazebo>

</robot>
@farhan-haroon
Copy link

Did this edit resolve the issue?

@2892510130
Copy link
Author

Did this edit resolve the issue?

It was my change that caused the problem, but with the original configuration, there was a noticeable slippage, which I didn't want (which is why I changed the configuration).

Sorry for the late reply.

@2892510130
Copy link
Author

Any ideas?

  1. Is the problem not caused by the robot but the gazobo?
  2. Or the control algrithm(but the cmd vel and angular are smooth enough)?
  3. Or the cmd v and w are too big?

@sunghowoo
Copy link

@2892510130 This instability might stem from Gazebo's physics engine rather than the robot itself or the control algorithm. The parameters in the .gazebo.xacro file may not fully address physics issues, particularly at higher velocities. In my testing, I observed instability when the linear speed was set to 1.0 m/s and the angular speed exceeded 0.5 rad/s. To improve this, consider adjusting the robot’s inertia, mass, and mu (friction coefficient) parameters. These adjustments can help stabilize the robot's motion at higher speeds by better aligning with realistic dynamics in the simulation.

@sunghowoo sunghowoo self-assigned this Nov 12, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

3 participants