From 247360bc0c342020de73e79c4fcb1ddb63d3020f Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 21 Sep 2022 11:48:15 -0700 Subject: [PATCH] Update examples to used gazebosim Signed-off-by: Nate Koenig --- .../plugin/command_actor/command_actor.sdf | 2 +- .../joint_position_randomizer.sdf | 2 +- examples/scripts/log_video_recorder/README.md | 2 +- examples/standalone/joy_to_twist/README.md | 4 +- examples/standalone/joystick/README.md | 2 +- examples/worlds/actor.sdf | 10 +- examples/worlds/actor_crowd.sdf | 242 ++++++------- examples/worlds/actors_population.sdf.erb | 4 +- examples/worlds/auv_controls.sdf | 2 +- examples/worlds/boundingbox_camera.sdf | 2 +- examples/worlds/breadcrumbs.sdf | 2 +- examples/worlds/camera_sensor.sdf | 2 +- examples/worlds/dem_monterey_bay.sdf | 2 +- examples/worlds/dem_moon.sdf | 38 +- examples/worlds/dem_volcano.sdf | 2 +- examples/worlds/depth_camera_sensor.sdf | 2 +- examples/worlds/elevator.sdf | 2 +- examples/worlds/follow_actor.sdf | 8 +- examples/worlds/fuel.sdf | 28 +- examples/worlds/fuel_textured_mesh.sdf | 4 +- examples/worlds/gpu_lidar_sensor.sdf | 2 +- examples/worlds/heightmap.sdf | 2 +- examples/worlds/import_mesh.sdf | 2 +- examples/worlds/lightmap.sdf | 2 +- examples/worlds/log_record_resources.sdf | 2 +- examples/worlds/mecanum_drive.sdf | 2 +- examples/worlds/model_photo_shoot.sdf | 2 +- examples/worlds/multi_lrauv_race.sdf | 12 +- .../worlds/multicopter_velocity_control.sdf | 4 +- .../worlds/optical_tactile_sensor_plugin.sdf | 8 +- examples/worlds/particle_emitter.sdf | 2 +- examples/worlds/plot_3d.sdf | 2 +- examples/worlds/quadcopter.sdf | 2 +- examples/worlds/segmentation_camera.sdf | 20 +- examples/worlds/sensors_demo.sdf | 2 +- examples/worlds/shader_param.sdf | 4 +- examples/worlds/thermal_camera.sdf | 6 +- examples/worlds/tracked_vehicle_simple.sdf | 2 +- examples/worlds/triggered_camera_sensor.sdf | 2 +- examples/worlds/tunnel.sdf | 324 +++++++++--------- examples/worlds/visualize_lidar.sdf | 2 +- examples/worlds/wide_angle_camera.sdf | 2 +- include/gz/sim/EntityComponentManager.hh | 5 + 43 files changed, 390 insertions(+), 385 deletions(-) diff --git a/examples/plugin/command_actor/command_actor.sdf b/examples/plugin/command_actor/command_actor.sdf index d0193eec4f..28b7460c07 100644 --- a/examples/plugin/command_actor/command_actor.sdf +++ b/examples/plugin/command_actor/command_actor.sdf @@ -52,7 +52,7 @@ 1 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + https://fuel.gazebosim.org/1.0/Mingfei/models/actor diff --git a/examples/plugin/reset_plugin/joint_position_randomizer.sdf b/examples/plugin/reset_plugin/joint_position_randomizer.sdf index ba2ea56b8d..710bb3da33 100644 --- a/examples/plugin/reset_plugin/joint_position_randomizer.sdf +++ b/examples/plugin/reset_plugin/joint_position_randomizer.sdf @@ -37,7 +37,7 @@ - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Simple Arm + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Simple Arm diff --git a/examples/scripts/log_video_recorder/README.md b/examples/scripts/log_video_recorder/README.md index 080983ccbc..cbcc3dab82 100644 --- a/examples/scripts/log_video_recorder/README.md +++ b/examples/scripts/log_video_recorder/README.md @@ -40,7 +40,7 @@ timestamped directory where the `record_one_run.bash` is in. ## Troubleshooting 1. The world / models are not being loaded on log playback? - A: Make sure you have all the fuel models downloaded in ~/.ignition/fuel cache + A: Make sure you have all the fuel models downloaded in ~/.gz/fuel cache directory 1. I see `tmp_record` dir, `tmp_recording.mp4` and other left over mp4 files diff --git a/examples/standalone/joy_to_twist/README.md b/examples/standalone/joy_to_twist/README.md index 9ff83cdef1..ae35890d94 100644 --- a/examples/standalone/joy_to_twist/README.md +++ b/examples/standalone/joy_to_twist/README.md @@ -1,9 +1,9 @@ # Joy to Twist Standalone program that subscribes to -[gz::msgs::Joy](https://gazebosim.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) +[gz::msgs::Joy](https://gazebosim.org/api/msgs/9/classgz_1_1msgs_1_1Joy.html) messages and converts publishes -[gz::msgs::Twist](https://gazebosim.org/api/msgs/5.6/classignition_1_1msgs_1_1Twist.html) +[gz::msgs::Twist](https://gazebosim.org/api/msgs/9/classgz_1_1msgs_1_1Twist.html) messages according to user-defined configuration. ## Build diff --git a/examples/standalone/joystick/README.md b/examples/standalone/joystick/README.md index c42de18162..9c8782a0ab 100644 --- a/examples/standalone/joystick/README.md +++ b/examples/standalone/joystick/README.md @@ -1,7 +1,7 @@ # Joystick Standalone program that publishes -[gz::msgs::Joy](https://gazebosim.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) +[gz::msgs::Joy](https://gazebosim.org/api/msgs/9/classgz_1_1msgs_1_1Joy.html) messages from a joystick device using Gazebo Transport. The mapping of joystick buttons to fields in the message is the same as [this](http://wiki.ros.org/joy). diff --git a/examples/worlds/actor.sdf b/examples/worlds/actor.sdf index 6d721b173d..78fc3cceb6 100644 --- a/examples/worlds/actor.sdf +++ b/examples/worlds/actor.sdf @@ -67,16 +67,16 @@ demo_actor 0 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + https://fuel.gazebosim.org/1.0/Mingfei/models/actor - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor/tip/files/meshes/talk_b.dae + https://fuel.gazebosim.org/1.0/Mingfei/models/actor/tip/files/meshes/talk_b.dae 1.0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor/tip/files/meshes/talk_b.dae + https://fuel.gazebosim.org/1.0/Mingfei/models/actor/tip/files/meshes/talk_b.dae 0.055 true @@ -167,11 +167,11 @@ - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor/tip/files/meshes/walk.dae + https://fuel.gazebosim.org/1.0/Mingfei/models/actor/tip/files/meshes/walk.dae 1.0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor/tip/files/meshes/walk.dae + https://fuel.gazebosim.org/1.0/Mingfei/models/actor/tip/files/meshes/walk.dae true