Skip to content

Commit

Permalink
3 ➡️ 4 (#792)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina authored Apr 29, 2021
2 parents 1f564df + 803130e commit 1326174
Show file tree
Hide file tree
Showing 13 changed files with 784 additions and 98 deletions.
19 changes: 9 additions & 10 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -14,13 +14,12 @@ jobs:
uses: ignition-tooling/action-ignition-ci@bionic
with:
codecov-token: ${{ secrets.CODECOV_TOKEN }}
# TODO(anyone) Enable Focal CI and fix failing tests
# focal-ci:
# runs-on: ubuntu-latest
# name: Ubuntu Focal CI
# steps:
# - name: Checkout
# uses: actions/checkout@v2
# - name: Compile and test
# id: ci
# uses: ignition-tooling/action-ignition-ci@focal
focal-ci:
runs-on: ubuntu-latest
name: Ubuntu Focal CI
steps:
- name: Checkout
uses: actions/checkout@v2
- name: Compile and test
id: ci
uses: ignition-tooling/action-ignition-ci@focal
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ ign_find_package (Qt5

#--------------------------------------
# Find ignition-physics
ign_find_package(ignition-physics3 VERSION 3.1
ign_find_package(ignition-physics3 VERSION 3.2
COMPONENTS
mesh
sdf
Expand Down
279 changes: 279 additions & 0 deletions examples/worlds/pendulum_links.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,279 @@
<?xml version="1.0" ?>
<!--
Ignition Gazebo link velocity control demo
Try sending commands:
ign topic -t "/model/double_pendulum_with_base/link/lower_link/cmd_vel" -m ignition.msgs.Twist -p "angular: {x: 0.5}"
ign topic -t "/model/double_pendulum_with_base/link/upper_link/cmd_vel" -m ignition.msgs.Twist -p "linear: {x:0.2}, angular: {x: 0.5}"
-->

<?xml version="1.0" ?>
<sdf version="1.7">
<world name="double_pendulum">
<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="libignition-gazebo-physics-system.so"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="libignition-gazebo-user-commands-system.so"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="libignition-gazebo-scene-broadcaster-system.so"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>

<model name="double_pendulum_with_base">
<link name="base">
<inertial>
<mass>100</mass>
</inertial>
<visual name="vis_plate_on_ground">
<pose>0 0 0.01 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.8</radius>
<length>0.02</length>
</cylinder>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<visual name="vis_pole">
<pose>-0.275 0 1.1 0 0 0</pose>
<geometry>
<box>
<size>0.2 0.2 2.2</size>
</box>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<collision name="col_plate_on_ground">
<pose>0 0 0.01 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.8</radius>
<length>0.02</length>
</cylinder>
</geometry>
</collision>
<collision name="col_pole">
<pose>-0.275 0 1.1 0 0 0</pose>
<geometry>
<box>
<size>0.2 0.2 2.2</size>
</box>
</geometry>
</collision>
</link>
<!-- upper link, length 1, IC -90 degrees -->
<link name="upper_link">
<pose>0 0 2.1 -1.5708 0 0</pose>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0.5 0 0 0</pose>
</inertial>
<visual name="vis_upper_joint">
<pose>-0.05 0 0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.3</length>
</cylinder>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<visual name="vis_lower_joint">
<pose>0 0 1.0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.2</length>
</cylinder>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<visual name="vis_cylinder">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.9</length>
</cylinder>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<collision name="col_upper_joint">
<pose>-0.05 0 0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.3</length>
</cylinder>
</geometry>
</collision>
<collision name="col_lower_joint">
<pose>0 0 1.0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.2</length>
</cylinder>
</geometry>
</collision>
<collision name="col_cylinder">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.9</length>
</cylinder>
</geometry>
</collision>
</link>
<!-- lower link, length 1, IC ~-120 degrees more -->
<link name="lower_link">
<pose>0.25 1.0 2.1 -2 0 0</pose>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0.5 0 0 0</pose>
</inertial>
<visual name="vis_lower_joint">
<pose>0 0 0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.08</radius>
<length>0.3</length>
</cylinder>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<visual name="vis_cylinder">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.9</length>
</cylinder>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<collision name="col_lower_joint">
<pose>0 0 0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.08</radius>
<length>0.3</length>
</cylinder>
</geometry>
</collision>
<collision name="col_cylinder">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.9</length>
</cylinder>
</geometry>
</collision>
</link>
<!-- pin joint for upper link, at origin of upper link -->
<joint name="upper_joint" type="revolute">
<parent>base</parent>
<child>upper_link</child>
<axis>
<xyz>1.0 0 0</xyz>
</axis>
</joint>
<!-- pin joint for lower link, at origin of child link -->
<joint name="lower_joint" type="revolute">
<parent>upper_link</parent>
<child>lower_link</child>
<axis>
<xyz>1.0 0 0</xyz>
</axis>
</joint>

<plugin
filename="ignition-gazebo-velocity-control-system"
name="ignition::gazebo::systems::VelocityControl">
<link_name>base</link_name>
<link_name>upper_link</link_name>
<link_name>lower_link</link_name>
</plugin>
</model>
</world>
</sdf>
Loading

0 comments on commit 1326174

Please sign in to comment.