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

robot arm is broken link by link in gazebo

asked 2018-04-10 17:37:04 -0500

Oh233 gravatar image

updated 2018-04-13 12:27:54 -0500

Hi all,

I have succeeded loading my designed robot arm in rviz and finished planning and executing. Right now I want to use load kinect to get some simulated data for robot arm. Hence I am trying to load urdf file in gazebo. The problem is my robot arm is broken link by link. It seems joint element in urdf doesn't work. I followed the tutorial of urdf in gazebo and added friction and damping in the urdf. I am not sure where I got wrong. Thanks in advance for any suggestions.image description

Here is the pic that robot arm in the rviz image description

Here is the view that joint in gazebo: image description

Here is the pic of using simulation pause: image description

The pic of fixing exploding problem: image description

Here is the sample of urdf for the robot arm:

<link
name="base_link">
<inertial>
  <origin
    xyz="0.0321026763828113 2.50206915787532E-06 0.0657435992941309"
    rpy="0 0 0" />
  <mass
    value="1.10920648420033" />
  <inertia
    ixx="0.00147297997205269"
    ixy="5.79000298722719E-08"
    ixz="0.000465603614160418"
    iyy="0.00175551330106354"
    iyz="8.33670869119005E-08"
    izz="0.000282540363613262" />
</inertial>
<visual>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://finalarm_dualmotor/meshes/base_link.STL" />
  </geometry>
  <material
    name="">
    <color
      rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
  </material>
</visual>
<collision>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://finalarm_dualmotor/meshes/base_link.STL" />
  </geometry>
</collision>
</link>
 <link
name="link_2">
<inertial>
  <origin
    xyz="-0.109631651147839 0.00554931888805481 -0.00279543211641581"
    rpy="0 0 0" />
  <mass
    value="0.471538287399184" />
  <inertia
    ixx="0.000342180694725082"
    ixy="0.000123860746353015"
    ixz="-6.21619859185448E-05"
    iyy="0.000321444130264041"
    iyz="0.000137295563003535"
    izz="0.000525597338936957" />
</inertial>
<visual>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://finalarm_dualmotor/meshes/link_2.STL" />
  </geometry>
  <material
    name="">
    <color
      rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
  </material>
</visual>
<collision>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://finalarm_dualmotor/meshes/link_2.STL" />
  </geometry>
</collision>
</link>

 <joint
name="joint_1"
type="revolute">
<origin
  xyz="0.0672 0 0.058"
  rpy="0.46565 1.5708 0" />
<parent
  link="base_link" />
<child
  link="link_2" />
<axis
  xyz="-1 0 0" />
<limit
  lower="-3.14"
  upper="3.14"
  effort="6"
  velocity="2.0" />
<dynamics damping="0.7"/>
</joint>
edit retag flag offensive close merge delete

Comments

Can you post a sample of the urdf here? Something that shows a few links and joints.

Airuno2L gravatar image Airuno2L  ( 2018-04-10 18:21:57 -0500 )edit

@Airuno2L I have added a sample which contains link1, link2 and joint1 in the problem. I wanted to attach the whole urdf file but it doesn't allow me to do it. Please tell me if you need anything. Thank you for your help.

Oh233 gravatar image Oh233  ( 2018-04-10 18:46:10 -0500 )edit

Could you also update your post to include a picture of your robot in RViz, so we can see what it's supposed to look like? Also, in Gazebo could you try viewing joints (View -> Joints).

josephcoombe gravatar image josephcoombe  ( 2018-04-10 18:56:10 -0500 )edit

@josephcoombe I already post the pic of arm in rviz and the view of joint_1 in gazebo but I am not sure whether the view of joint is the one you want. Please let me know if you know further infomation. Thanks.

Oh233 gravatar image Oh233  ( 2018-04-10 20:05:14 -0500 )edit

@Oh233 By viewing joints, I mean in Gazebo go to top-left menu. Select 'View' menu. From drop-down list, check Joints. Gazebo will display RGB coordinate axes at each non-fixed joint in your model.

josephcoombe gravatar image josephcoombe  ( 2018-04-11 08:16:24 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
5

answered 2018-04-11 08:32:10 -0500

updated 2018-04-11 16:06:43 -0500

The URDF is spawning successfully in Gazebo (i.e. it's not actually broken).

The arm's links are jumbled up because the joints are not being actuated.

The robot is then "exploding" - after which all the links are collected at the origin.


Update: At least one of the links in the URDF has an incorrect Inertial matrices (probably way too small)

To fix:

1) Change all your inertia tags to:

<inertia ixx="0.0001" ixy="0.000"  ixz="0.000"  
         iyy="0.0001" iyz="0.000"
         izz="0.0001"
/>

(You can go back and fix these later. Either using geometric approximations or something like MeshLab

Note: In Gazebo, View -> Inertia will give you a ballpark idea of the inertial matrices. To understand what the purple boxes actually mean check out http://gazebosim.org/tutorials?tut=in... )

2) If model still explodes, disable self-collision for all links:

<gazebo reference="link_10">
  <selfCollide>False</selfCollide>
</gazebo>

You can re-enable self-collisions selectively. Links that are penetrating on spawn can cause the model to "explode"

3) (Optional) I always enable implicitSpringDamping for better stability simulating joint damping:

<gazebo reference="joint_9">
  <implicitSpringDamper>True</implicitSpringDamper>
</gazebo>

You should be able to spawn your model into Gazebo like so: image description

Note: Gazebo Answers ( http://answers.gazebosim.org/questions/ ) is usually where I go with these types of Gazebo-focused questions if you end up running into any other snags.


Old: Maybe useful info but not the correct answer to OP's problem

RViz is a visualizer, so you can "move" an arm in RViz just by broadcasting ideal joint states. Gazebo is a simulator, so you have to somehow inject joint forces into the simulated world. Otherwise you should expect limp arm behavior - similar to the real world.

You have to write/use a Gazebo Plugin that applies efforts to the joints or use en existing package like ros_control.


Some quick debugging:

  • Spawn URDF in Gazebo off the ground (e.g. -x 0 -y 0 -z 6).

    <!-- Spawn a urdf in Gazebo, taking the description from the parameter server -->
    <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model"
        args="-param robot_description -urdf -model robot -x 0 -y 0 -z 6" />
    
  • As @ARB suggests, turn gravity off for your arm.

  • View -> Joints
  • View -> Inertia
  • Start simulation Paused and manually advance simulation in small time steps to see if arm is collapsing normally under effects of gravity or is "exploding" due to some defect in model (inertial matrices looked pretty normal so unlikely).
  • Use the joint_state_publisher (with GUI) and robot_state_publisher in RViz to verify joints are as expected.
edit flag offensive delete link more

Comments

Hi josephcoombe, I will try your suggestion. I have tried the way of turning gravity off but it didn't help. I added the pic of view of joint. But there is no joint coordinate for every joint. And what is the purpose of lifting robot off the ground? I tried to lift it but it wasn't lifted.

Oh233 gravatar image Oh233  ( 2018-04-11 10:18:31 -0500 )edit

I added a fixed joint for base link and world. Does that link prevent me from lifting the arm?

Oh233 gravatar image Oh233  ( 2018-04-11 10:19:59 -0500 )edit

Yes, that link prevents you from moving the arm once spawn. You can set the spawn location of the arm via the spawn_urdf node in the gazebo_ros package (updated my answer with example).

josephcoombe gravatar image josephcoombe  ( 2018-04-11 10:42:32 -0500 )edit

The purpose to changing the spawn location to be above the ground plane is that it may help clarify the kinematic structure of arm. If it droops naturally, joints aren't actuated. If it stays in a jumble, something funky may be happening.

josephcoombe gravatar image josephcoombe  ( 2018-04-11 10:43:52 -0500 )edit

From the updated joint view, it appears that all your joints are spawning in the same location. Have you tried starting the simulation paused and manually advancing in small time steps?

josephcoombe gravatar image josephcoombe  ( 2018-04-11 10:45:10 -0500 )edit
1

I haven't tried that. I already tried to implement ros control but it didn't help solve the problem. I need to have lunch right now and will update my status as soon as possible. Thanks so much for your reply.

Oh233 gravatar image Oh233  ( 2018-04-11 11:12:05 -0500 )edit
1

I tried simulation pause and found that the arm is actually spawn right at first. But it will collapse after a small time step.

Oh233 gravatar image Oh233  ( 2018-04-11 12:18:39 -0500 )edit

What happens when you change spawn location to 6 meters above ground plane via gazebo_ros spawn_urdf node?

josephcoombe gravatar image josephcoombe  ( 2018-04-11 12:33:57 -0500 )edit
0

answered 2018-04-10 19:28:38 -0500

ARB gravatar image

Turn the gravity off for all links..might work

<gazebo reference="link">
       <turnGravityOff>true</turnGravityOff>
  </gazebo>
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2018-04-10 17:37:04 -0500

Seen: 2,713 times

Last updated: Apr 13 '18