Skip to content

Commit

Permalink
2 to 3
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina committed Jul 18, 2020
2 parents 8f0187d + 6671ee6 commit 781d8b1
Show file tree
Hide file tree
Showing 50 changed files with 2,367 additions and 389 deletions.
16 changes: 16 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,22 @@

## Ignition Gazebo 2.x

### Ignition Gazebo 2.21.0 (2020-07-16)

1. Added support for controlling which joints are published by the
JointStatePublisher.
* [Pull Request 222](https://github.com/ignitionrobotics/ign-gazebo/pull/222)

1. Added an additional pose offset for the performer detector plugin.
* [Pull Request 236](https://github.com/ignitionrobotics/ign-gazebo/pull/236)

1. Fixed battery issues and updated tutorial.
* [Pull Request 230](https://github.com/ignitionrobotics/ign-gazebo/pull/230)

### Ignition Gazebo 2.20.1 (2020-06-18)

1. Properly add new models into the scenegraph. With this fix, when a model is spawned it will be added into the graph and resulting calls to the `scene/info` service will return a correct `msgs::Scene`.
* [Pull Request 212](https://github.com/ignitionrobotics/ign-gazebo/pull/212)

### Ignition Gazebo 2.20.0 (2020-06-09)

Expand Down
2 changes: 1 addition & 1 deletion examples/worlds/breadcrumbs.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -472,7 +472,7 @@
<pose>-2 0 0 0 0 0</pose>
<include>
<uri>
https://fuel.ignitionrobotics.org/1.0/openrobotics/models/X2 Config 1
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/X2 Config 1
</uri>
</include>
</model>
Expand Down
2 changes: 1 addition & 1 deletion examples/worlds/camera_sensor.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -258,7 +258,7 @@
<include>
<pose>0 1 3 0.0 0.0 1.57</pose>
<uri>
https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Construction Cone
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Cone
</uri>
</include>

Expand Down
2 changes: 1 addition & 1 deletion examples/worlds/depth_camera_sensor.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -227,7 +227,7 @@
<include>
<pose>0 1 3 0.0 0.0 1.57</pose>
<uri>
https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Construction Barrel
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Barrel
</uri>
</include>

Expand Down
12 changes: 6 additions & 6 deletions examples/worlds/fuel.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -123,24 +123,24 @@
<!-- Included model without meshes -->
<include>
<pose>-3 0 0 0 0 0</pose>
<uri>https://fuel.ignitionrobotics.org/1.0/nate/models/double_pendulum_with_base/2</uri>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Double pendulum with base</uri>
</include>

<!-- Included model with meshes -->
<include>
<pose>3 -1 0 0 0 0</pose>
<uri>https://fuel.ignitionrobotics.org/1.0/nate/models/my_Backpack</uri>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack</uri>
</include>

<!-- Included model with meshes using relative paths -->
<include>
<pose>2 5 0 0 0 0</pose>
<uri>https://fuel.ignitionrobotics.org/1.0/chapulina/models/Gazebo - relative paths</uri>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Gazebo - relative paths</uri>
</include>

<!-- Included actor with meshes using relative paths -->
<include>
<uri>https://fuel.ignitionrobotics.org/1.0/chapulina/models/actor - relative paths</uri>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/actor - relative paths</uri>
</include>

<!-- Model with meshes -->
Expand All @@ -151,14 +151,14 @@
<collision name="collision">
<geometry>
<mesh>
<uri>https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Radio/4/files/meshes/Radio.dae</uri>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Radio/4/files/meshes/Radio.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Radio/4/files/meshes/Radio.dae</uri>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Radio/4/files/meshes/Radio.dae</uri>
</mesh>
</geometry>
</visual>
Expand Down
2 changes: 1 addition & 1 deletion examples/worlds/fuel_textured_mesh.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@
<static>true</static>
<name>Rescue Randy</name>
<pose>0 0 0 0 0 1.57</pose>
<uri>https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Rescue Randy</uri>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Rescue Randy</uri>
</include>

<!-- Tube Light -->
Expand Down
2 changes: 1 addition & 1 deletion examples/worlds/gpu_lidar_sensor.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -235,7 +235,7 @@
<include>
<pose>0 0 0 0 0 1.57</pose>
<uri>
https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Playground
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Playground
</uri>
</include>

Expand Down
98 changes: 97 additions & 1 deletion examples/worlds/joint_controller.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,17 @@
<!--
Ignition Gazebo joint controller plugin demo
Try sending joint velocity commands:
Try sending joint velocity commands (velocity mode):
ign topic -t "/model/joint_controller_demo/joint/j1/cmd_vel" -m ignition.msgs.Double -p "data: -1.0"
ign topic -t "/model/joint_controller_demo/joint/j1/cmd_vel" -m ignition.msgs.Double -p "data: 10.0"
Try sending joint velocity commands (force mode):
ign topic -t "/model/joint_controller_demo_2/joint/j1/cmd_vel" -m ignition.msgs.Double -p "data: -1.0"
ign topic -t "/model/joint_controller_demo_2/joint/j1/cmd_vel" -m ignition.msgs.Double -p "data: 10.0"
-->
<sdf version="1.6">
<world name="default">
Expand Down Expand Up @@ -152,10 +158,100 @@
<xyz>0 0 1</xyz>
</axis>
</joint>
<!-- Velocity mode -->
<plugin
filename="libignition-gazebo-joint-controller-system.so"
name="ignition::gazebo::systems::JointController">
<joint_name>j1</joint_name>
</plugin>
</model>

<model name="joint_controller_demo_2">
<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>
<inertia>
<ixx>2.501</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>2.501</iyy>
<iyz>0</iyz>
<izz>5</izz>
</inertia>
<mass>120.0</mass>
</inertial>
<visual name="base_visual">
<pose>0.0 0.0 0.0 0 0 0</pose>
<geometry>
<box>
<size>0.5 0.5 0.01</size>
</box>
</geometry>
</visual>
<collision name="base_collision">
<pose>0.0 0.0 0.0 0 0 0</pose>
<geometry>
<box>
<size>0.5 0.5 0.01</size>
</box>
</geometry>
</collision>
</link>
<link name="rotor2">
<pose>0.0 0.0 0.1 0 0 0</pose>
<inertial>
<inertia>
<ixx>0.032</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.032</iyy>
<iyz>0</iyz>
<izz>0.00012</izz>
</inertia>
<mass>0.6</mass>
</inertial>
<visual name="visual">
<geometry>
<box>
<size>0.25 0.1 0.05</size>
</box>
</geometry>
<material>
<ambient>0.2 0.8 0.2 1</ambient>
</material>
</visual>
<collision name="collision">
<geometry>
<box>
<size>0.25 0.1 0.05</size>
</box>
</geometry>
</collision>
</link>

<joint name="world_fixed" type="fixed">
<parent>world</parent>
<child>base_link</child>
</joint>

<joint name="j1" type="revolute">
<pose>0 0 -0.5 0 0 0</pose>
<parent>base_link</parent>
<child>rotor2</child>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>

<!-- Force mode -->
<plugin
filename="libignition-gazebo-joint-controller-system.so"
name="ignition::gazebo::systems::JointController">
<joint_name>j1</joint_name>
<use_force_commands>true</use_force_commands>
<p_gain>0.2</p_gain>
<i_gain>0.01</i_gain>
</plugin>
</model>
</world>
Expand Down
Loading

0 comments on commit 781d8b1

Please sign in to comment.