3
$\begingroup$

I have built my differential drive mobile robot in solidworks and converted that to URDF file using soliworks2urdf converter. I successfully launched and robot and simulated with tele-operation node. Since i am intended to use navigation stack in i viewed the transform of the robot in rviz which resulted as below.

enter image description here

As you can see the base plate is the one which supports the wheels and castors but the tf of base plate is shown away from the actual link and even odom is away from the model. Where have i gone wrong and how to fix this. Refer the URDF of model below.

    <?xml   version="1.0"?>
<robot
  name="JMbot">
  <link
    name="Base_plate">
    <inertial>
      <origin
        xyz="-0.3317 0.71959 -0.39019"
        rpy="0 0 0" />
      <mass
        value="0.55378" />
      <inertia
        ixx="0.0061249"
        ixy="0.00016086"
        ixz="-8.6651E-18"
        iyy="0.0041631"
        iyz="-1.4656E-17"
        izz="0.010283" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://jmbot_description/meshes/Base_plate.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.74902 0.74902 0.74902 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://jmbot_description/meshes/Base_plate.STL" />
      </geometry>
    </collision>
  </link>
  <link
    name="Wheel_R">
    <inertial>
      <origin
        xyz="0.010951 1.1102E-16 -1.1102E-16"
        rpy="0 0 0" />
      <mass
        value="0.45064" />
      <inertia
        ixx="0.00091608"
        ixy="-1.2355E-19"
        ixz="1.0715E-18"
        iyy="0.00053395"
        iyz="-6.7763E-20"
        izz="0.00053395" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://jmbot_description/meshes/Wheel_R.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.74902 0.74902 0.74902 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://jmbot_description/meshes/Wheel_R.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="Wheel_R"
    type="continuous">
    <origin
      xyz="-0.14688 0.40756 -0.73464"
      rpy="-2.7127 -0.081268 -3.1416" />
    <parent
      link="Base_plate" />
    <child
      link="Wheel_R" />
    <axis
      xyz="1 0 0" />
  </joint>
  <link
    name="Wheel_L">
    <inertial>
      <origin
        xyz="-0.039049 2.2204E-16 2.498E-15"
        rpy="0 0 0" />
      <mass
        value="0.45064" />
      <inertia
        ixx="0.00091608"
        ixy="-9.6693E-19"
        ixz="-1.7816E-18"
        iyy="0.00053395"
        iyz="1.3553E-19"
        izz="0.00053395" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://jmbot_description/meshes/Wheel_L.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.74902 0.74902 0.74902 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://jmbot_description/meshes/Wheel_L.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="Wheel_L"
    type="continuous">
    <origin
      xyz="-0.46668 0.40756 -0.70859"
      rpy="2.512 0.081268 3.4272E-15" />
    <parent
      link="Base_plate" />
    <child
      link="Wheel_L" />
    <axis
      xyz="-1 0 0" />
  </joint>
  <link
    name="Castor_F">
    <inertial>
      <origin
        xyz="2.2204E-16 0 0.031164"
        rpy="0 0 0" />
      <mass
        value="0.056555" />
      <inertia
        ixx="2.4476E-05"
        ixy="-2.8588E-35"
        ixz="1.0281E-20"
        iyy="2.4476E-05"
        iyz="-1.2617E-20"
        izz="7.4341E-06" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://jmbot_description/meshes/Castor_F.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.75294 0.75294 0.75294 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://jmbot_description/meshes/Castor_F.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="Castor_F"
    type="continuous">
    <origin
      xyz="-0.31952 0.39256 -0.57008"
      rpy="-1.5708 1.1481 -1.3614E-16" />
    <parent
      link="Base_plate" />
    <child
      link="Castor_F" />
    <axis
      xyz="0 0 1" />
  </joint>
  <link
    name="Castor_R">
    <inertial>
      <origin
        xyz="-1.1102E-16 0 0.031164"
        rpy="0 0 0" />
      <mass
        value="0.056555" />
      <inertia
        ixx="2.4476E-05"
        ixy="0"
        ixz="-3.9352E-20"
        iyy="2.4476E-05"
        iyz="-1.951E-20"
        izz="7.4341E-06" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://jmbot_description/meshes/Castor_R.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.75294 0.75294 0.75294 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://jmbot_description/meshes/Castor_R.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="Castor_R"
    type="continuous">
    <origin
      xyz="-0.34387 0.39256 -0.86909"
      rpy="1.5708 -0.93144 3.1416" />
    <parent
      link="Base_plate" />
    <child
      link="Castor_R" />
    <axis
      xyz="0 0 1" />
  </joint>

<gazebo>
<plugin name="differential_drive_controller"
    filename="libgazebo_ros_diff_drive.so">
    <leftJoint>Wheel_L</leftJoint>  
    <rightJoint>Wheel_R</rightJoint>
    <robotBaseFrame>Base_plate</robotBaseFrame>
    <wheelSeparation>0.235</wheelSeparation>
    <wheelDiameter>0.12</wheelDiameter>
    <publishWheelJointState>true</publishWheelJointState>
    </plugin>
<plugin name="joint_state_publisher"
    filename="libgazebo_ros_joint_state_publisher.so">
    <jointName>Castor_F, Castor_R</jointName>
    </plugin>

</gazebo>

</robot>
$\endgroup$
4
  • $\begingroup$ Can you try changing the Fixed Frame on RViz? Sometimes wrong selection there can cause weird results. $\endgroup$
    – George ZP
    Jan 12, 2016 at 11:58
  • $\begingroup$ That doesn't help. Even if i change the fixed frame the origin falls out of the base_plate $\endgroup$ Jan 12, 2016 at 12:52
  • $\begingroup$ The Odom frame is supposed to stay away from the model since it is the inertial frame, so that part is ok $\endgroup$
    – hauptmech
    Jan 12, 2016 at 23:17
  • 1
    $\begingroup$ Also, you will get better help for this at answers.ros.org $\endgroup$
    – hauptmech
    Jan 12, 2016 at 23:19

1 Answer 1

3
$\begingroup$

It looks like most of your parts have no rotation, but some of them do, so I'm going to guess that you didn't mate your assembly to the origin planes in Solidworks.

First, on your base plate, open the Solidworks part file and check that the origin planes run through what you want the origin of the part to be. If they don't and it's a pain to re-draw the part, then go to the "Reference Feature" button and then "Plane" and draw what you want the origin planes to be. SAVE THE PART.

Open your assembly, and check if it says "underdefined" at the bottom. Solidworks (annoyingly) puts the first part down fixed, but not mated, to a random position in the assembly space.

So, in the parts tree, right click the top part (should have (f) after the name, indicating it's fixed), and click "float". You may have to expand the option list to see this.

Now go to Mates, then expand the part list for your base plate, then mate the origin (or reference) planes of your base plate to the origin planes of your assembly space.

You may also need to mate the wheels to prevent them from rotating in order to get the "fully defined" message at the bottom.

I'm on my phone at the moment; I'll add some figures after I get to work.

:EDIT:

Here are some pictures OP provided. I've marked up what I believe to be the error. I think that the URDF Global Origin is set to be the same as the Solidworks assembly origin. In this case, for the robot, the robot (global) origin should be the origin of the Base Plate, but I am betting that the Base Plate is not mated to the assembly origin, so this is causing the discrepancy in the simulation visualization.

Solidworks URDF Assembly Origin

Solidworks URDF Global Origin

:EDIT 2:

Here's a picture walk-through of mating a part to the assembly origin. If you need anything clarified, please let me know in a comment, but if you have a new question about something then please just make a new question (they're free!)

Solidworks URDF Part Origin

Solidworks URDF Under defined Assembly

Solidworks URDF Part Assembly Mating

Solidworks URDF Fully Defined Assembly

$\endgroup$
3
  • $\begingroup$ Thank you, I have couple of pics showing my origin here and i feel its fine, can you please verify $\endgroup$ Jan 12, 2016 at 14:07
  • $\begingroup$ Great! So this is the problem am i right? $\endgroup$ Jan 13, 2016 at 7:22
  • $\begingroup$ @user3725099 - Yes, I believe that is the problem - that your global reference frame is in a random location. I believe if you constrain (mate) the center of your robot to the center of your assembly space it will fix that, which will then fix your simulations. $\endgroup$
    – Chuck
    Jan 13, 2016 at 14:13

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge that you have read and understand our privacy policy and code of conduct.

Not the answer you're looking for? Browse other questions tagged or ask your own question.