Skip to content

Commit

Permalink
Migrate shared lib references
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon committed Jun 17, 2022
1 parent 5e860a9 commit 54b0f6d
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 9 deletions.
8 changes: 4 additions & 4 deletions tutorials/segmentation_camera.md
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,7 @@ To assign a label to a model we use the label plugin in the SDF file:
<diffuse>0 0 1 1</diffuse>
<specular>0 0 0.3 1</specular>
</material>
<plugin filename="ignition-gazebo-label-system" name="gz::sim::systems::Label">
<plugin filename="gz-sim-label-system" name="gz::sim::systems::Label">
<label>10</label>
</plugin>
</visual>
Expand All @@ -150,7 +150,7 @@ To assign a label to a model we use the label plugin in the SDF file:
Lets zoom in the label plugin:

```xml
<plugin filename="ignition-gazebo-label-system" name="gz::sim::systems::Label">
<plugin filename="gz-sim-label-system" name="gz::sim::systems::Label">
<label>10</label>
</plugin>
```
Expand All @@ -167,7 +167,7 @@ You can also attach this plugin to the model's `<model>` tag:
<link name="sphere_link">
...
</link>
<plugin filename="ignition-gazebo-label-system" name="gz::sim::systems::Label">
<plugin filename="gz-sim-label-system" name="gz::sim::systems::Label">
<label>20</label>
</plugin>
</model>
Expand All @@ -181,7 +181,7 @@ If you're including a model from a place like [Gazebo Fuel](https://app.gazebosi
<uri>
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Cone
</uri>
<plugin filename="ignition-gazebo-label-system" name="gz::sim::systems::Label">
<plugin filename="gz-sim-label-system" name="gz::sim::systems::Label">
<label>30</label>
</plugin>
</include>
Expand Down
10 changes: 5 additions & 5 deletions tutorials/thermal_camera.md
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ Here's an example of how to attach a thermal camera sensor to a model in a [SDF]
<visualize>true</visualize>
<topic>thermal_camera_8bit/image</topic>
<plugin
filename="ignition-gazebo-thermal-sensor-system"
filename="gz-sim-thermal-sensor-system"
name="gz::sim::systems::ThermalSensor">
<min_temp>253.15</min_temp>
<max_temp>673.15</max_temp>
Expand Down Expand Up @@ -89,7 +89,7 @@ Let's take a closer look at the portion of the code above that focuses on the th
<visualize>true</visualize>
<topic>thermal_camera_8bit/image</topic>
<plugin
filename="ignition-gazebo-thermal-sensor-system"
filename="gz-sim-thermal-sensor-system"
name="gz::sim::systems::ThermalSensor">
<min_temp>253.15</min_temp>
<max_temp>673.15</max_temp>
Expand Down Expand Up @@ -190,7 +190,7 @@ Here's an example of a box model that has a uniform temperature assigned to it:
<specular>1 0 0 1</specular>
</material>
<plugin
filename="ignition-gazebo-thermal-system"
filename="gz-sim-thermal-system"
name="gz::sim::systems::Thermal">
<temperature>285.0</temperature>
</plugin>
Expand All @@ -203,7 +203,7 @@ Most of the code above is for the model - here's the key piece for temperature a

```xml
<plugin
filename="ignition-gazebo-thermal-system"
filename="gz-sim-thermal-system"
name="gz::sim::systems::Thermal">
<temperature>285.0</temperature>
</plugin>
Expand All @@ -221,7 +221,7 @@ If we take a look at Rescue Randy's `model.sdf`, we can see that it incorporates

```xml
<plugin
filename="ignition-gazebo-thermal-system"
filename="gz-sim-thermal-system"
name="gz::sim::systems::Thermal">
<heat_signature>materials/textures/RescueRandy_Thermal.png</heat_signature>
<max_temp>310</max_temp>
Expand Down

0 comments on commit 54b0f6d

Please sign in to comment.