'Why isn't my mobile manipulator URDF stable on RViz and Gazebo?
I'm using ROS Melodic on Ubuntu 18.04. I have imported a the URDF from Solidworks using the plugin SW2URDF. I have been facing a lot of issues controlling the URDF on gazebo especially while teleoperating. Every time I move the robot using the:
rosrun teleop_twist_keyboard teleop_twist_keyboard.py
node, only one wheel out of the 4 moves causing the robot to lose the correct orientation.The plugin I am using for is the planar_move plugin as the wheels are mecanum wheels. Besides this the Pris 2 link of the robot arm is getting displayed differently on RViz and Gazebo.The Pris 2 link (The longer slider crank link) is supposed to look like what it looks on RViz.
Also the Pris 2 joint despite being set as revolute joint isn't showing up on the joint publisher.
Robot on Gazebo:

Joint Publishers:
Can anyone identify what the problem causing the above problems is? Here is the URDF:
<?xml version="1.0" encoding="utf-8"?>
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner ([email protected])
Commit Version: 1.6.0-1-g15f4949 Build Version: 1.6.7594.29634
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
<robot
name="final_assembly3">
<link name="odom" />
<joint name="fixed" type="fixed">
<parent link="odom" />
<child link="base_link" />
</joint>
<link
name="base_link">
<inertial>
<origin
xyz="0.14768 0.23303 0.22798"
rpy="0 0 0" />
<mass
value="7.6442" />
<inertia
ixx="0.075629"
ixy="3.85E-09"
ixz="-9.5343E-08"
iyy="0.14294"
iyz="1.6837E-11"
izz="0.081345" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/base_link.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/base_link.STL" />
</geometry>
</collision>
</link>
<link
name="Wheel 1">
<inertial>
<origin
xyz="-3.2558E-07 1.0722E-07 0.030838"
rpy="0 0 0" />
<mass
value="0.5000" />
<inertia
ixx="0.00072916667"
ixy="0.0000000"
ixz="0.0000000"
iyy="0.000625"
iyz="0.0000000"
izz="0.00072916667" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/Wheel 1.STL" />
</geometry>
<material
name="">
<color
rgba="0.89804 0.91765 0.92941 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/Wheel 1.STL" />
</geometry>
</collision>
</link>
<joint
name="Cont 1"
type="continuous">
<origin
xyz="-0.0034084 -0.12798 0.10053"
rpy="-1.5708 0 1.5708" />
<parent
link="base_link" />
<child
link="Wheel 1" />
<axis
xyz="0 0 1" />
</joint>
<link
name="Wheel 2">
<inertial>
<origin
xyz="-3.2557837015279E-07 1.07217308559227E-07 0.0308380289896838"
rpy="0 0 0" />
<mass
value="0.5000" />
<inertia
ixx="0.00072916667"
ixy="0.0000000"
ixz="0.0000000"
iyy="0.000625"
iyz="0.0000000"
izz="0.00072916667" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/Wheel 2.STL" />
</geometry>
<material
name="">
<color
rgba="0.898039215686275 0.917647058823529 0.929411764705882 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/Wheel 2.STL" />
</geometry>
</collision>
</link>
<joint
name="Cont 2"
type="continuous">
<origin
xyz="0.29877 -0.32798 0.10053"
rpy="1.5708 0 1.5708" />
<parent
link="base_link" />
<child
link="Wheel 2" />
<axis
xyz="0 0 1" />
</joint>
<link
name="Wheel 3">
<inertial>
<origin
xyz="-3.26336083100731E-07 1.07668861937249E-07 -0.0308380347831287"
rpy="0 0 0" />
<mass
value="0.5000" />
<inertia
ixx="0.00072916667"
ixy="0.0000000"
ixz="0.0000000"
iyy="0.000625"
iyz="0.0000000"
izz="0.00072916667" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/Wheel 3.STL" />
</geometry>
<material
name="">
<color
rgba="0.898039215686275 0.917647058823529 0.929411764705882 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/Wheel 3.STL" />
</geometry>
</collision>
</link>
<joint
name="Cont 3"
type="continuous">
<origin
xyz="-0.0034084 -0.32798 0.10053"
rpy="1.5708 0 1.5708" />
<parent
link="base_link" />
<child
link="Wheel 3" />
<axis
xyz="0 0 1" />
</joint>
<link
name="Wheel 4">
<inertial>
<origin
xyz="-3.26299866348911E-07 1.07652009542769E-07 0.0291707139063403"
rpy="0 0 0" />
<mass
value="0.5000" />
<inertia
ixx="0.00072916667"
ixy="0.0000000"
ixz="0.0000000"
iyy="0.000625"
iyz="0.0000000"
izz="0.00072916667" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/Wheel 4.STL" />
</geometry>
<material
name="">
<color
rgba="0.898039215686275 0.917647058823529 0.929411764705882 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/Wheel 4.STL" />
</geometry>
</collision>
</link>
<joint
name="Cont 4"
type="continuous">
<origin
xyz="0.30046 -0.12798 0.10053"
rpy="1.5708 0.62487 1.5708" />
<parent
link="base_link" />
<child
link="Wheel 4" />
<axis
xyz="0 0 1" />
</joint>
<link
name="New Static Link">
<inertial>
<origin
xyz="0.0172790917411035 0.102994908792773 -0.000286417787769305"
rpy="0 0 0" />
<mass
value="1.94401355435528" />
<inertia
ixx="0.00768941377852196"
ixy="-0.0023016367314421"
ixz="2.28881904576314E-05"
iyy="0.00450259485431559"
iyz="3.78227208152756E-05"
izz="0.0103483641272583" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/New Static Link.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/New Static Link.STL" />
</geometry>
</collision>
</link>
<joint
name="Fixed"
type="fixed">
<origin
xyz="0.14768 -0.22798 0.33053"
rpy="1.5708 0 -1.581" />
<parent
link="base_link" />
<child
link="New Static Link" />
<axis
xyz="0 1 0" />
</joint>
<link
name="Arm">
<inertial>
<origin
xyz="0.13229755761114 -0.000278839398755615 -0.0323012411261709"
rpy="0 0 0" />
<mass
value="1.80462691606488" />
<inertia
ixx="0.00337104522287667"
ixy="2.3173417802539E-05"
ixz="-0.000161183912931026"
iyy="0.0199987994056373"
iyz="-1.64319461670501E-06"
izz="0.0222082055539029" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/Arm.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/Arm.STL" />
</geometry>
</collision>
</link>
<joint
name="Rev1"
type="revolute">
<origin
xyz="0.06 0.18 -0.030782"
rpy="0 0 0.18829" />
<parent
link="New Static Link" />
<child
link="Arm" />
<axis
xyz="0 0 1" />
<limit
lower="-0.73"
upper="1"
effort="0"
velocity="0" />
</joint>
<link
name="Pris 1">
<inertial>
<origin
xyz="0.0335816493728636 1.71749397870347E-07 0.0119354658625156"
rpy="0 0 0" />
<mass
value="0.123182781546625" />
<inertia
ixx="3.77360992389157E-05"
ixy="1.28183032967861E-11"
ixz="-5.81374538385023E-06"
iyy="0.000122947375330809"
iyz="2.65123689114698E-10"
izz="0.000144337931781889" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/Pris 1.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/Pris 1.STL" />
</geometry>
</collision>
</link>
<joint
name="Pris 1"
type="revolute">
<origin
xyz="0.1 0 -0.063391"
rpy="3.1416 0 -1.9477" />
<parent
link="Arm" />
<child
link="Pris 1" />
<axis
xyz="0 0 1" />
<limit
lower="-1"
upper="1"
effort="0"
velocity="0" />
</joint>
<link
name="Pris 2">
<inertial>
<origin
xyz="1.8466057571942E-09 -5.55111512312578E-17 0.01"
rpy="0 0 0.90855" />
<mass
value="0.260668670250234" />
<inertia
ixx="7.94869252643328E-05"
ixy="-2.07014852308951E-18"
ixz="2.73993982613085E-18"
iyy="0.00115947637560852"
iyz="1.99348984198689E-09"
izz="0.00122317832768109" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/Pris 2.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/Pris 2.STL" />
</geometry>
</collision>
</link>
<joint
name="Pris 2"
type="revolute">
<origin
xyz="-0.0014893 -0.078861 0.020827"
rpy="0 0 0" />
<parent
link="Pris 1" />
<child
link="Pris 2" />
<axis
xyz="0 0 1" />
<limit
lower="0.93"
upper="0.93"
effort="0"
velocity="0" />
</joint>
<link
name="Pris 3">
<inertial>
<origin
xyz="-0.166565243027124 0.000967072198009372 0.0300000329001753"
rpy="0 0 0" />
<mass
value="0.449710314809642" />
<inertia
ixx="0.00137456804218307"
ixy="-4.43060167581936E-05"
ixz="9.82391747567394E-10"
iyy="0.002208699287522"
iyz="-1.54947639651244E-09"
izz="0.00315643719811711" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/Pris 3.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://final_assembly3/meshes/Pris 3.STL" />
</geometry>
</collision>
</link>
<joint
name="Pris 3"
type="prismatic">
<origin
xyz="0.20514 0.030503 -0.039218"
rpy="-1.5708 0 3.1416" />
<parent
link="Arm" />
<child
link="Pris 3" />
<axis
xyz="1 0 0" />
<limit
lower="-0.093"
upper="0.04"
effort="0"
velocity="0" />
</joint>
<gazebo>
<plugin name="object_controller" filename="libgazebo_ros_planar_move.so">
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<odometryRate>50.0</odometryRate>
<robotBaseFrame>base_link</robotBaseFrame>
</plugin>
</gazebo>
</robot>
Solution 1:[1]
I increased inertia to my base_link
<inertia
ixx="50.0" ixy="0.0" ixz="0.0"
iyy="50.0" iyz="0.0"
izz="50.0" />
and that solved the teleoperation problem that was occuring. But am yet to solve the robot arm issue.
Sources
This article follows the attribution requirements of Stack Overflow and is licensed under CC BY-SA 3.0.
Source: Stack Overflow
| Solution | Source |
|---|---|
| Solution 1 | Nidhi |

