ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

Is there no one who can help me?

Is there no one who can help me?

thanks Zephyrin!!!

Also I have found a solution. Simply I modified the file kobuki_gazebo.urdf.xacro. Because there is a problem with the plugin "kobuki_controller". I replace this plugin with "differential_drive_controller".

This is the new kobuki_gazebo.urdf.xacro

<?xml version="1.0"?>

<robot name="kobuki_sim" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="kobuki_sim">
  <gazebo reference="wheel_left_link">
    <mu1>1.0</mu1>
    <mu2>1.0</mu2>
    <kp>100000000.0</kp>
    <kd>10000.0</kd>
  </gazebo>

  <gazebo reference="wheel_right_link">
    <mu1>1.0</mu1>
    <mu2>1.0</mu2>
    <kp>100000000.0</kp>
    <kd>10000.0</kd>
  </gazebo>

  <gazebo reference="caster_front_link">
    <mu1>0.0</mu1>
    <mu2>0.0</mu2>
    <kp>100000000.0</kp>
    <kd>10000.0</kd>
  </gazebo>

  <gazebo reference="caster_back_link">
    <mu1>0.0</mu1>
    <mu2>0.0</mu2>
    <kp>100000000.0</kp>
    <kd>10000.0</kd>
  </gazebo>

  <gazebo reference="base_link">
    <sensor type="contact" name="bumpers">
      <always_on>1</always_on>
      <update_rate>50.0</update_rate>
      <visualize>true</visualize>
      <contact>
        <collision>base_footprint_collision_base_link</collision>
      </contact>
    </sensor>
  </gazebo>

  <gazebo reference="cliff_sensor_left_link">
    <sensor type="ray" name="cliff_sensor_left">
      <always_on>true</always_on>
      <update_rate>50</update_rate>
      <visualize>true</visualize>
      <ray>
        <scan>
          <horizontal>
            <samples>50</samples>
            <resolution>1.0</resolution>
            <min_angle>-0.0436</min_angle>  <!-- -2.5 degree -->
            <max_angle>0.0436</max_angle> <!-- 2.5 degree -->
          </horizontal>
      <!--            Can't use vertical rays until this bug is resolved: -->
      <!--            https://bitbucket.org/osrf/gazebo/issue/509/vertical-sensor-doesnt-works -->
     <!--             <vertical> -->
     <!--               <samples>50</samples> -->
     <!--               <resolution>1.0</resolution> -->
     <!--               <min_angle>-0.0436</min_angle>  -2.5 degree -->
     <!--               <max_angle>0.0436</max_angle> 2.5 degree -->
     <!--             </vertical> -->
        </scan>
        <range>
          <min>0.01</min>
          <max>0.15</max>
          <resolution>1.0</resolution>
        </range>
      </ray>
    </sensor>
  </gazebo>

  <gazebo reference="cliff_sensor_right_link">
    <sensor type="ray" name="cliff_sensor_right">
      <always_on>true</always_on>
      <update_rate>50</update_rate>
      <visualize>true</visualize>
      <ray>
        <scan>
          <horizontal>
            <samples>50</samples>
            <resolution>1.0</resolution>
            <min_angle>-0.0436</min_angle>  <!-- -2.5 degree -->
            <max_angle>0.0436</max_angle> <!-- 2.5 degree -->
          </horizontal>
      <!--            Can't use vertical rays until this bug is resolved: -->
      <!--            https://bitbucket.org/osrf/gazebo/issue/509/vertical-sensor-doesnt-works -->
      <!--            <vertical> -->
      <!--              <samples>50</samples> -->
      <!--              <resolution>1.0</resolution> -->
      <!--              <min_angle>-0.0436</min_angle>  -2.5 degree -->
      <!--              <max_angle>0.0436</max_angle> 2.5 degree -->
      <!--            </vertical> -->
        </scan>
        <range>
          <min>0.01</min>
          <max>0.15</max>
          <resolution>1.0</resolution>
        </range>
      </ray>
    </sensor>
  </gazebo>

  <gazebo reference="cliff_sensor_front_link">
    <sensor type="ray" name="cliff_sensor_front">
      <always_on>true</always_on>
      <update_rate>50</update_rate>
      <visualize>true</visualize>
      <ray>
        <scan>
          <horizontal>
            <samples>50</samples>
            <resolution>1.0</resolution>
            <min_angle>-0.0436</min_angle>  <!-- -2.5 degree -->
            <max_angle>0.0436</max_angle> <!-- 2.5 degree -->
          </horizontal>
      <!--            Can't use vertical rays until this bug is resolved: -->
      <!--            https://bitbucket.org/osrf/gazebo/issue/509/vertical-sensor-doesnt-works -->
      <!--            <vertical> -->
      <!--              <samples>50</samples> -->
      <!--              <resolution>1.0</resolution> -->
      <!--              <min_angle>-0.0436</min_angle>  -2.5 degree -->
      <!--              <max_angle>0.0436</max_angle> 2.5 degree -->
      <!--            </vertical> -->
        </scan>
        <range>
          <min>0.01</min>
          <max>0.15</max>
          <resolution>1.0</resolution>
        </range>
      </ray>
    </sensor>
  </gazebo>

  <gazebo reference="gyro_link">
   <sensor type="imu" name="imu">
    <always_on>true</always_on>
    <update_rate>50</update_rate>
    <visualize>false</visualize>
    <imu>
      <noise>
        <type>gaussian</type>
          <rate>
            <mean>0.0</mean>
            <stddev>${0.0014*0.0014}</stddev> <!-- 0.25 x 0.25 (deg/s) -->
            <bias_mean>0.0</bias_mean>
            <bias_stddev>0.0</bias_stddev>
          </rate>
            <accel> <!-- not used in the plugin and real robot, hence using tutorial values -->
                <mean>0.0</mean>
                <stddev>1.7e-2</stddev>
                <bias_mean>0.1</bias_mean>
                <bias_stddev>0.001</bias_stddev>
            </accel>
      </noise>
      </imu>
  </sensor>
  </gazebo>

 <gazebo>
 <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
 <alwaysOn>true</alwaysOn>
 <updateRate>15</updateRate>
 <leftJoint>wheel_left_joint</leftJoint>
 <rightJoint>wheel_right_joint</rightJoint>
 <wheelSeparation>0.5380</wheelSeparation>
 <wheelDiameter>0.2410</wheelDiameter>
 <torque>20</torque>
 <commandTopic>cmd_vel</commandTopic>
 <odometryTopic>odom</odometryTopic>
 <odometryFrame>odom</odometryFrame>
 <robotBaseFrame>base_footprint</robotBaseFrame>
 </plugin>
 </gazebo>

 </xacro:macro>
 </robot>

I change only the last lines. This part:

 <gazebo>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<alwaysOn>true</alwaysOn>
<updateRate>15</updateRate>
<leftJoint>wheel_left_joint</leftJoint>
<rightJoint>wheel_right_joint</rightJoint>
<wheelSeparation>0.5380</wheelSeparation>
<wheelDiameter>0.2410</wheelDiameter>
<torque>20</torque>
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<robotBaseFrame>base_footprint</robotBaseFrame>
</plugin>
</gazebo>

Now I have both robot1/odom-->robot1/base_footprint and robot2/odom-->robot2/base_footprint.

The next step is to connect /map with robot1/odom and robot2/odom.

I hope that is a good way to use multi robot in Gazebo.