Robotics StackExchange | Archived questions

Can not move model by joint tab or published command.

Yet another restatement of problem.

HINT: if I change the joint type to "continuous" the applying force via the force tab works. Why is this???

I ran this file as its original model.sdf and it works fine!!! Force tab works fine , the model moves. When modifed to run as a urdf file it stops working. Can any one see what the error if any in the conversion is? Here is the sdf file and the two xarco files that generate the urdf.

============================sdf model============================

<?xml version='1.0'?>
<sdf version='1.3'>
  <model name="my_robot">
    <link name='base_link'>
      <pose>0 0 .1 0 0 0</pose>
      <collision name='collision'>
        <geometry>
          <box>
            <size>.4 .2 .1</size>
          </box>
        </geometry>
      </collision>

      <visual name='visual'>
        <geometry>
          <box>
            <size>.4 .2 .1</size>
          </box>
        </geometry>
      </visual>

      <collision name='caster_collision'>
        <pose>-0.15 0 -0.05 0 0 0</pose>
        <geometry>
          <sphere>
          <radius>.05</radius>
        </sphere>
      </geometry>

      <surface>
        <friction>
          <ode>
            <mu>0</mu>
            <mu2>0</mu2>
            <slip1>1.0</slip1>
            <slip2>1.0</slip2>
          </ode>
        </friction>
      </surface>
    </collision>

    <visual name='caster_visual'>
      <pose>-0.15 0 -0.05 0 0 0</pose>
      <geometry>
        <sphere>
          <radius>.05</radius>
        </sphere>
      </geometry>
    </visual>
  </link>     
  <link name="left_wheel">
    <pose>0.1 0.13 0.1 0 1.5707 1.5707</pose>
    <collision name="collision">
      <geometry>
        <cylinder>
          <radius>.1</radius>
          <length>.05</length>
        </cylinder>
      </geometry>
    </collision>
    <visual name="visual">
      <geometry>
        <cylinder>
          <radius>.1</radius>
          <length>.05</length>
        </cylinder>
      </geometry>
    </visual>
  </link>

  <link name="right_wheel">
    <pose>0.1 -0.13 0.1 0 1.5707 1.5707</pose>
    <collision name="collision">
      <geometry>
        <cylinder>
          <radius>.1</radius>
          <length>.05</length>
        </cylinder>
      </geometry>
    </collision>
    <visual name="visual">
      <geometry>
        <cylinder>
          <radius>.1</radius>
          <length>.05</length>
        </cylinder>
      </geometry>
    </visual>
  </link>
  <joint type="revolute" name="joint1">
    <pose>0 0 -0.03 0 0 0</pose>
    <child>left_wheel</child>
    <parent>base_link</parent>
    <axis>
      <xyz>0 1 0</xyz>
    </axis>
  </joint>

  <joint type="revolute" name="joint2">
    <pose>0 0 0.03 0 0 0</pose>
    <child>right_wheel</child>
    <parent>base_link</parent>
    <axis>
      <xyz>0 1 0</xyz>
    </axis>
  </joint>
   </model>
</sdf>





      =====================Model urdf side =============================
<?xml version="1.0"?>
<!-- Revolute-Revolute Manipulator -->
<robot name="rrbot" xmlns:xacro="http://www.ros.org/wiki/xacro">

  <!-- Import all Gazebo-customization elements, including Gazebo colors -->
  <xacro:include filename="$(find rrbot_description)/urdf/rrbot.gazebo" />
  <!-- Import Rviz colors -->
  <xacro:include filename="$(find rrbot_description)/urdf/materials.xacro" />

   <link name='base_link'>
      <collision name='collision'>
        <origin xyz="0 0 .1 " rpy="0 0 0"/>
        <geometry>
          <box  size=".4 .2 .1"/>
        </geometry>
      </collision>

      <visual name='visual'>
        <origin xyz="0 0 .1 " rpy="0 0 0"/>
        <geometry>
          <box  size=".4 .2 .1"/>
        </geometry>
      </visual>

      <collision name='caster_collision'>
        <origin xyz="-0.15 0 0" rpy="0 0 0"/>
        <geometry>
          <sphere radius=".05"/>
        </geometry>

        <surface>
         <friction>
          <ode>
            <mu>0</mu>
            <mu2>0</mu2>
            <slip1>1.0</slip1>
            <slip2>1.0</slip2>
          </ode>
         </friction>
        </surface>

      </collision>

      <visual name='caster_visual'>
        <origin xyz="-0.15 0 0" rpy="0 0 0"/>
        <geometry>
          <sphere radius=".05"/>
        </geometry>
      </visual>

     <inertial>
        <mass value="1e-5" />
        <origin xyz="0 0 .1 " rpy="0 0 0"/>
        <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
     </inertial>
  </link> 



  <link name="left_wheel">
    <collision name="collision">
      <origin xyz="0.1 0.13 0.0" rpy="0 1.5707 1.5707"/>
      <geometry>
         <cylinder length="0.1" radius="0.05"/>
      </geometry>
    </collision>
    <visual name="visual">
      <origin xyz="0.1 0.13 0.0" rpy="0 1.5707 1.5707"/>
      <geometry>
        <cylinder length="0.1" radius="0.05"/>
      </geometry>
    </visual>
    <inertial>
      <mass value="1e-5" />
      <origin xyz="0.1 0.13 0.0"/>
      <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
    </inertial>
  </link>

  <link name="right_wheel">
    <collision name="collision">
      <origin xyz="0.1 -0.13 0.0" rpy="0 1.5707 1.5707"/>
      <geometry>
         <cylinder length="0.1" radius="0.05"/>
      </geometry>
    </collision>
    <visual name="visual">
      <origin xyz="0.1 -0.13 0.0" rpy="0 1.5707 1.5707"/>
      <geometry>
        <cylinder length="0.1" radius="0.05"/>
      </geometry>
    </visual>
    <inertial>
      <mass value="1e-5" />
      <origin xyz="0.1 -0.13 0.0"/>
      <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
    </inertial>
  </link>


  <joint type="revolute" name="joint1">
    <origin xyz="0.0 0.0 0.03" rpy="0 0 0"/>
    <child link="left_wheel">left_wheel</child>
    <parent link="base_link">base_link</parent>
    <axis xyz="0 1 0"/>
    <limit effort="30" velocity="1.0"  />
  </joint>

  <joint type="revolute" name="joint2">
    <origin xyz="0.0 0.0 0.03" rpy="0 0 0"/>
    <child link="right_wheel">right_wheel</child>
     <parent link="base_link">base_link</parent>
     <axis xyz="0 1 0"/>>
    <limit effort="30" velocity="1.0"  />
  </joint>

  <transmission name="tran1">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="joint1"/>
    <actuator name="motor1">
      <hardwareInterface>EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>

  <transmission name="tran2">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="joint2"/>
    <actuator name="motor2">
      <hardwareInterface>EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>


</robot>




        ==============================Model urdf files gazebo part ==========================

        <?xml version='1.0'?>
        <robot name="rrbot">

          <gazebo>
            <plugin name="ros_control" filename="libgazebo_ros_control.so">
              <robotNamespace>/rrbot</robotNamespace>
              <controlPeriod>0.001</controlPeriod>
              <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
            </plugin>
          </gazebo>

          <gazebo reference="base_link">
            <mu1>0.2</mu1>
            <mu2>0.2</mu2>
            <material>Gazebo/Red</material>
          </gazebo>

          <gazebo reference="left_wheel">
            <mu1>0.2</mu1>
            <mu2>0.2</mu2>
            <material>Gazebo/Red</material>
          </gazebo>

          <gazebo reference="right_wheel">
            <mu1>0.2</mu1>
            <mu2>0.2</mu2>
            <material>Gazebo/Red</material>
          </gazebo>

        </robot>

Asked by rnunziata on 2013-08-08 13:20:29 UTC

Comments

Answers

I was missing lower="" upper="" limit attributes in the effort element.

Asked by rnunziata on 2013-08-09 21:09:28 UTC

Comments