Skip to content

Commit

Permalink
Improve joint controller world visualization
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde committed Sep 13, 2023
1 parent d052491 commit b4c2deb
Showing 1 changed file with 6 additions and 2 deletions.
8 changes: 6 additions & 2 deletions examples/worlds/joint_controller.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
<direction>-0.5 0.1 -0.9</direction>
</light>
<model name="joint_controller_demo">
<pose>0 0 0 0 1.57 0</pose>
<pose>0 0 0 0 -1.57 0</pose>
<link name="base_link">
<pose>0.0 0.0 0.0 0 0 0</pose>
<inertial>
Expand Down Expand Up @@ -91,6 +91,8 @@
</geometry>
<material>
<ambient>0.2 0.8 0.2 1</ambient>
<diffuse>0.2 0.8 0.2 1</diffuse>
<specular>0.2 0.8 0.2 1</specular>
</material>
</visual>
<collision name="collision">
Expand Down Expand Up @@ -125,7 +127,7 @@
</model>

<model name="joint_controller_demo_2">
<pose>0 0.5 0 0 1.57 0</pose>
<pose>0 0.5 0 0 -1.57 0</pose>
<link name="base_link">
<pose>0.0 0.0 0.0 0 0 0</pose>
<inertial>
Expand Down Expand Up @@ -177,6 +179,8 @@
</geometry>
<material>
<ambient>0.2 0.8 0.2 1</ambient>
<diffuse>0.2 0.8 0.2 1</diffuse>
<specular>0.2 0.8 0.2 1</specular>
</material>
</visual>
<collision name="collision">
Expand Down

0 comments on commit b4c2deb

Please sign in to comment.