ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
It's hard to tell from just the one Gazebo view, but I think your urdf has spawned successfully in Gazebo (i.e. it's not actually broken).
The arm's links are jumbled up because the joints are not being actuated.
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 ways to check this:
2 | No.2 Revision |
It's hard to tell from just the one Gazebo view, but I think your urdf has spawned successfully in Gazebo (i.e. it's not actually broken).
The arm's links are jumbled up because the joints are not being actuated.
Edit: Based on OP update, it seems urdf in Gazebo has no joints.
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 ways to check this:
3 | No.3 Revision |
It's hard to tell from just the one Gazebo view, but I think your urdf has spawned successfully in Gazebo (i.e. it's not actually broken).
The arm's links are jumbled up because the joints are not being actuated.
Edit: Based on OP update, it seems urdf in Gazebo has no joints.all the joints in the same location...
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 ways to check this:
4 | No.4 Revision |
It's hard to tell from just the one Gazebo view, but I think your urdf has spawned successfully in Gazebo (i.e. it's not actually broken).
The arm's links are jumbled up because the joints are not being actuated.
Edit: Based on OP update, it seems urdf in Gazebo has all the joints in the same location...
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 ways to check this:
5 | No.5 Revision |
It's hard to tell from just the one Gazebo view, but I think your urdf has spawned successfully in Gazebo (i.e. it's not actually broken).
The arm's links are jumbled up because the joints are not being actuated.
Edit: Based on OP update, it seems urdf in Gazebo has all the joints in the same location...
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 ways to check this:
<!-- 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.
6 | No.6 Revision |
The URDF is spawning successfully in Gazebo It's hard to tell from just the one view, but I think your urdf has spawned 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.
Edit: Based 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=inertia#CheckinginGazebo)
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 OP update, it seems urdf in 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 has all the joints in the same location...like so:
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 ways to check this: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.