From 61df2c3abe88bd8c428dde3e823227ff9a4671ed Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Thu, 3 Nov 2022 12:17:07 -0700 Subject: [PATCH] 3 to 6 20221013 (#1762) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * 🎈 3.14.0~pre1 (#1650) Signed-off-by: Louise Poubel * Remove redundant namespace references (#1635) Signed-off-by: methylDragon * 🎈 3.14.0 (#1657) Signed-off-by: Louise Poubel Signed-off-by: Louise Poubel * readd namespaces for Q_ARGS (#1670) * Remove actors from screen when they are supposed to (#1699) # 🦟 Bug fix Supercedes #1697. Note: When forward porting we will have to update the hashmaps to erase the new hashmaps created. Fixes # ## Summary Found that when actors are De-spawned the actor visuals are not destroyed. This commit addresses this bug by adding the missing remove logic in RenderUtils. ## Before ![bug](https://user-images.githubusercontent.com/542272/189558600-196d98c5-1dcf-4d6c-93d6-7493df38c0e4.gif) ## After ![no_bug](https://user-images.githubusercontent.com/542272/189558924-3f2e3c5d-68f3-4d80-aee4-3dc3ce6742a1.gif) ## Notes: Theres a lot of hashmaps being populated in RenderUtils whenever a new actor is spawned. I hope I've caught them all. Also while I need these working in garden (as all the projects Im working on use garden), should I backport these changes? Signed-off-by: Arjo Chakravarty * Update examples to use gazebosim.org Signed-off-by: Nate Koenig * Citadel: Removed warnings (#1753) Signed-off-by: ahcorde * Added collection name to About Dialog (#1756) Signed-off-by: ahcorde * Convert ignitionrobotics to gazebosim in tests directory (#1757) * Convert ignitionrobotics to gaazebosim in tests directory Signed-off-by: Nate Koenig * fix gz-gazebo Signed-off-by: Nate Koenig Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig * Convert ignitionrobotics to gazebosim in sources and includes (#1758) Signed-off-by: Nate Koenig Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig * Convert ignitionrobotics to gazebosim in tutorials (#1759) Signed-off-by: Nate Koenig Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig * Final update of ignitionrobotics to gazebosim for citadel (#1760) Signed-off-by: Nate Koenig Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig * remove PlotIcon (#1658) Signed-off-by: youhy Signed-off-by: youhy * Fix UNIT_ign_TEST Signed-off-by: Nate Koenig Signed-off-by: Louise Poubel Signed-off-by: methylDragon Signed-off-by: Arjo Chakravarty Signed-off-by: Nate Koenig Signed-off-by: ahcorde Signed-off-by: youhy Co-authored-by: Louise Poubel Co-authored-by: methylDragon Co-authored-by: Jenn Nguyen Co-authored-by: Arjo Chakravarty Co-authored-by: Nate Koenig Co-authored-by: Alejandro Hernández Cordero Co-authored-by: AzulRadio <50132891+AzulRadio@users.noreply.github.com> --- CMakeLists.txt | 2 +- CODE_OF_CONDUCT.md | 2 +- CONTRIBUTING.md | 2 +- Changelog.md | 549 ++++++++++-------- NEWS | 2 +- docker/README.md | 2 +- docker/scripts/build_ign.sh | 6 +- docker/scripts/upload_json_benchmark.sh | 8 +- examples/standalone/joy_to_twist/README.md | 4 +- examples/standalone/joystick/README.md | 2 +- examples/worlds/actor.sdf | 6 +- examples/worlds/actors_population.sdf.erb | 4 +- examples/worlds/breadcrumbs.sdf | 2 +- examples/worlds/camera_sensor.sdf | 2 +- examples/worlds/depth_camera_sensor.sdf | 2 +- examples/worlds/elevator.sdf | 2 +- examples/worlds/fuel.sdf | 14 +- examples/worlds/fuel_textured_mesh.sdf | 4 +- examples/worlds/gpu_lidar_sensor.sdf | 2 +- examples/worlds/import_mesh.sdf | 2 +- examples/worlds/log_record_resources.sdf | 2 +- .../worlds/multicopter_velocity_control.sdf | 4 +- examples/worlds/plot_3d.sdf | 2 +- examples/worlds/quadcopter.sdf | 2 +- examples/worlds/sensors_demo.sdf | 2 +- examples/worlds/tracked_vehicle_simple.sdf | 2 +- examples/worlds/tunnel.sdf | 279 +++++---- include/ignition/gazebo/Entity.hh | 3 +- include/ignition/gazebo/ServerConfig.hh | 4 +- src/Component_TEST.cc | 4 +- src/Conversions.cc | 126 ++-- src/Conversions_TEST.cc | 28 +- src/EntityComponentManager.cc | 14 +- src/EntityComponentManager_TEST.cc | 66 +-- src/SdfEntityCreator_TEST.cc | 80 +-- src/SdfGenerator_TEST.cc | 12 +- src/ServerConfig.cc | 38 +- src/ServerConfig_TEST.cc | 8 +- src/ServerPrivate.cc | 8 +- src/Server_TEST.cc | 30 +- src/SimulationRunner.cc | 28 +- src/SimulationRunner_TEST.cc | 396 ++++++------- src/SystemLoader_TEST.cc | 2 +- src/TestFixture.cc | 6 +- src/Util_TEST.cc | 2 +- src/World.cc | 8 +- src/cmd/cmdgazebo.rb.in | 4 +- src/gui/AboutDialogHandler.cc | 9 +- src/gui/GuiFileHandler.cc | 2 +- src/gui/GuiRunner.cc | 2 +- src/gui/Gui_TEST.cc | 12 +- src/gui/plugins/align_tool/AlignTool.cc | 18 +- .../component_inspector/ComponentInspector.cc | 42 +- src/gui/plugins/entity_tree/EntityTree.cc | 6 +- .../JointPositionController.cc | 12 +- src/gui/plugins/modules/EntityContextMenu.cc | 18 +- .../playback_scrubber/PlaybackScrubber.cc | 2 +- src/gui/plugins/plot_3d/Plot3D.cc | 6 +- .../resource_spawner/ResourceSpawner.cc | 12 +- src/gui/plugins/scene3d/Scene3D.cc | 40 +- src/gui/plugins/shapes/Shapes.cc | 2 +- .../transform_control/TransformControl.cc | 10 +- .../plugins/video_recorder/VideoRecorder.cc | 16 +- src/gui/plugins/view_angle/ViewAngle.cc | 2 +- src/ign.cc | 54 +- src/ign.hh | 2 +- src/ign_TEST.cc | 13 +- src/network/NetworkManagerPrimary.cc | 2 +- src/network/PeerInfo.cc | 28 +- src/network/PeerTracker.cc | 2 +- src/rendering/MarkerManager.cc | 122 ++-- src/rendering/RenderUtil.cc | 12 +- src/rendering/SceneManager.cc | 28 +- .../ackermann_steering/AckermannSteering.cc | 34 +- src/systems/altimeter/Altimeter.cc | 1 - .../apply_joint_force/ApplyJointForce.cc | 8 +- .../battery_plugin/LinearBatteryPlugin.cc | 14 +- .../battery_plugin/LinearBatteryPlugin.hh | 2 +- src/systems/breadcrumbs/Breadcrumbs.cc | 6 +- src/systems/buoyancy/Buoyancy.cc | 10 +- .../CameraVideoRecorder.cc | 6 +- .../CameraVideoRecorder.hh | 2 +- .../ColladaWorldExporter.cc | 10 +- src/systems/contact/Contact.cc | 2 +- .../detachable_joint/DetachableJoint.cc | 6 +- src/systems/diff_drive/DiffDrive.cc | 36 +- src/systems/imu/Imu.cc | 2 +- .../joint_controller/JointController.cc | 10 +- .../JointPositionController.cc | 10 +- .../JointStatePublisher.cc | 6 +- src/systems/lift_drag/LiftDrag.cc | 32 +- src/systems/log/LogPlayback.cc | 6 +- src/systems/log/LogRecord.cc | 8 +- .../log_video_recorder/LogVideoRecorder.cc | 18 +- .../LogicalAudioSensorPlugin.cc | 26 +- src/systems/magnetometer/Magnetometer.cc | 2 +- .../MulticopterVelocityControl.cc | 8 +- .../MulticopterMotorModel.cc | 14 +- .../performer_detector/PerformerDetector.cc | 6 +- src/systems/physics/EntityFeatureMap_TEST.cc | 4 +- src/systems/physics/Physics.cc | 124 ++-- src/systems/pose_publisher/PosePublisher.cc | 14 +- .../scene_broadcaster/SceneBroadcaster.cc | 36 +- src/systems/sensors/Sensors.cc | 2 +- src/systems/thermal/Thermal.cc | 4 +- src/systems/touch_plugin/TouchPlugin.cc | 2 +- .../track_controller/TrackController.cc | 50 +- src/systems/tracked_vehicle/TrackedVehicle.cc | 50 +- .../triggered_publisher/TriggeredPublisher.cc | 2 +- .../velocity_control/VelocityControl.cc | 28 +- src/systems/wheel_slip/WheelSlip.cc | 2 +- src/systems/wind_effects/WindEffects.cc | 2 +- test/integration/ackermann_steering_system.cc | 16 +- test/integration/air_pressure_system.cc | 6 +- test/integration/altimeter_system.cc | 6 +- test/integration/apply_joint_force_system.cc | 2 +- test/integration/battery_plugin.cc | 16 +- test/integration/breadcrumbs.cc | 30 +- test/integration/buoyancy.cc | 16 +- .../integration/camera_video_record_system.cc | 6 +- test/integration/components.cc | 14 +- test/integration/depth_camera.cc | 4 +- test/integration/detachable_joint.cc | 8 +- test/integration/diff_drive_system.cc | 16 +- test/integration/each_new_removed.cc | 2 +- test/integration/elevator_system.cc | 2 +- test/integration/entity_erase.cc | 4 +- test/integration/examples_build.cc | 14 +- test/integration/gpu_lidar.cc | 4 +- test/integration/imu_system.cc | 8 +- test/integration/joint_controller_system.cc | 16 +- .../joint_position_controller_system.cc | 8 +- test/integration/level_manager.cc | 22 +- .../level_manager_runtime_performers.cc | 22 +- test/integration/lift_drag_system.cc | 8 +- test/integration/log_system.cc | 20 +- .../logical_audio_sensor_plugin.cc | 6 +- test/integration/logical_camera_system.cc | 22 +- test/integration/magnetometer_system.cc | 8 +- test/integration/multicopter.cc | 18 +- test/integration/network_handshake.cc | 10 +- test/integration/performer_detector.cc | 4 +- test/integration/physics_system.cc | 184 +++--- test/integration/play_pause.cc | 14 +- test/integration/pose_publisher_system.cc | 14 +- test/integration/rgbd_camera.cc | 4 +- test/integration/save_world.cc | 2 +- test/integration/scene_broadcaster_system.cc | 34 +- test/integration/sdf_frame_semantics.cc | 22 +- test/integration/sdf_include.cc | 6 +- test/integration/sensors_system.cc | 4 +- test/integration/thermal_system.cc | 6 +- test/integration/touch_plugin.cc | 4 +- test/integration/tracked_vehicle_system.cc | 22 +- test/integration/user_commands.cc | 20 +- test/integration/velocity_control_system.cc | 8 +- test/integration/wheel_slip.cc | 57 +- test/integration/wind_effects.cc | 6 +- test/performance/level_manager.cc | 10 +- test/performance/sdf_runner.cc | 18 +- test/plugins/TestSystem.cc | 2 +- test/worlds/breadcrumbs.sdf | 2 +- .../worlds/test%20world/2/test.sdf | 5 + .../worlds/test%20world/2/test.world | 5 + .../worlds/test%20world/2/thumbnails/1.png | Bin 0 -> 6279 bytes test/worlds/include.sdf | 2 +- test/worlds/log_record_resources.sdf | 2 +- test/worlds/save_world.sdf | 6 +- tutorials/battery.md | 2 +- tutorials/detachable_joints.md | 2 +- tutorials/distributed_simulation.md | 2 +- tutorials/erb_template.md | 8 +- tutorials/gui_config.md | 8 +- tutorials/levels.md | 12 +- tutorials/log.md | 2 +- tutorials/logical_audio_sensor.md | 6 +- tutorials/mesh_to_fuel.md | 18 +- tutorials/migrating_ardupilot_plugin.md | 6 +- tutorials/migration_link_api.md | 2 +- tutorials/migration_model_api.md | 2 +- tutorials/migration_sdf.md | 2 +- tutorials/migration_world_api.md | 2 +- tutorials/physics.md | 4 +- tutorials/point_cloud_to_mesh.md | 22 +- tutorials/rendering_plugins.md | 12 +- tutorials/resources.md | 24 +- tutorials/server_config.md | 8 +- tutorials/terminology.md | 2 +- tutorials/test_fixture.md | 2 +- tutorials/triggered_publisher.md | 4 +- tutorials/video_recorder.md | 2 +- 191 files changed, 1949 insertions(+), 1860 deletions(-) create mode 100644 test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.sdf create mode 100644 test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.world create mode 100644 test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/thumbnails/1.png diff --git a/CMakeLists.txt b/CMakeLists.txt index 38008583c9..c97405df04 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -235,7 +235,7 @@ configure_file(${CMAKE_SOURCE_DIR}/tools/desktop/ignition-gazebo.svg.in ${CMAKE_ # disable doxygen on macOS due to issues with doxygen 1.9.0 # there is an unreleased fix; revert this when 1.9.1 is released -# https://github.com/ignitionrobotics/ign-gazebo/issues/520 +# https://github.com/gazebosim/gz-sim/issues/520 if (NOT APPLE) ign_create_docs( API_MAINPAGE_MD "${CMAKE_BINARY_DIR}/api.md" diff --git a/CODE_OF_CONDUCT.md b/CODE_OF_CONDUCT.md index 820e43fdbb..65eec816ef 100644 --- a/CODE_OF_CONDUCT.md +++ b/CODE_OF_CONDUCT.md @@ -56,7 +56,7 @@ further defined and clarified by project maintainers. ## Enforcement Instances of abusive, harassing, or otherwise unacceptable behavior may be -reported by contacting the project team at [https://ignitionrobotics.org/support](https://ignitionrobotics.org/support). All +reported by contacting the project team at [https://gazebosim.org/support](https://gazebosim.org/support). All complaints will be reviewed and investigated and will result in a response that is deemed necessary and appropriate to the circumstances. The project team is obligated to maintain confidentiality with regard to the reporter of an incident. diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index 147239ce5f..fbcac678cf 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -1 +1 @@ -See the [Ignition Robotics contributing guide](https://ignitionrobotics.org/docs/all/contributing). +See [Gazebo's contribution guide](https://gazebosim.org/docs/all/contributing). diff --git a/Changelog.md b/Changelog.md index 2487f3b1ce..3e0257d495 100644 --- a/Changelog.md +++ b/Changelog.md @@ -2122,7 +2122,56 @@ 1. Add window focus upon mouse entering the render window * [Github pull request 97](https://github.com/ignitionrobotics/ign-gazebo/pull/97) -## Ignition Gazebo 3.x +## Gazebo Sim 3.x + +### Gazebo Sim 3.14.0 (2022-08-17) + +1. Change `CODEOWNERS` and maintainer to Michael + * [Pull request #1644](https://github.com/gazebosim/gz-sim/pull/1644) + +1. Replace pose in `ViewAngle` with `GzPose` + * [Pull request #1641](https://github.com/gazebosim/gz-sim/pull/1641) + +1. Fix loading worlds from CLI + * [Pull request #1627](https://github.com/gazebosim/gz-sim/pull/1627) + +1. Quick start dialog + * [Pull request #1536](https://github.com/gazebosim/gz-sim/pull/1536) + +1. Quiet `libSDFormat` console on --verbose 0 + * [Pull request #1621](https://github.com/gazebosim/gz-sim/pull/1621) + +1. Add Ackermann Steering system (backport from Fortress) + * [Pull request #1613](https://github.com/gazebosim/gz-sim/pull/1613) + +1. New Apply Link Wrench system + * [Pull request #1593](https://github.com/gazebosim/gz-sim/pull/1593) + +1. Implement Component Inspector `Vector3` with common widget `Vector3` + * [Pull request #1569](https://github.com/gazebosim/gz-sim/pull/1569) + +1. Helper function to get an entity from an entity message + * [Pull request #1595](https://github.com/gazebosim/gz-sim/pull/1595) + +1. Ignition -> Gazebo + * [Pull request #1596](https://github.com/gazebosim/gz-sim/pull/1596) + +1. Add Model::CanonicalLink getter + * [Pull request #1594](https://github.com/gazebosim/gz-sim/pull/1594) + +1. Implement Pose3d with common widget pose + * [Pull request #1571](https://github.com/gazebosim/gz-sim/pull/1571) + +1. Test fixes and updates + * [Pull request #1545](https://github.com/gazebosim/gz-sim/pull/1545) + * [Pull request #1531](https://github.com/gazebosim/gz-sim/pull/1531) + * [Pull request #1599](https://github.com/gazebosim/gz-sim/pull/1599) + +1. Bash completion for flags + * [Pull request #1504](https://github.com/gazebosim/gz-sim/pull/1504) + +1. Add new `GZ_GUI_RESOURCE_PATH` to help message + * [Pull request #1470](https://github.com/gazebosim/gz-sim/pull/1470) ### Ignition Gazebo 3.13.0 (2022-06-01) @@ -2184,606 +2233,610 @@ ### Ignition Gazebo 3.12.0 (2021-11-11) 1. Prevent creation of spurious `` elements when saving worlds - * [Pull request #1192](https://github.com/ignitionrobotics/ign-gazebo/pull/1192) + * [Pull request #1192](https://github.com/gazebosim/gz-sim/pull/1192) 1. Added support for tracked vehicles - * [Pull request #869](https://github.com/ignitionrobotics/ign-gazebo/pull/869) + * [Pull request #869](https://github.com/gazebosim/gz-sim/pull/869) 1. Add components to dynamically set joint limits - * [Pull request #847](https://github.com/ignitionrobotics/ign-gazebo/pull/847) + * [Pull request #847](https://github.com/gazebosim/gz-sim/pull/847) 1. Fix updating a component's data via SerializedState msg - * [Pull request #1149](https://github.com/ignitionrobotics/ign-gazebo/pull/1149) + * [Pull request #1149](https://github.com/gazebosim/gz-sim/pull/1149) 1. Sensor systems work if loaded after sensors - * [Pull request #1104](https://github.com/ignitionrobotics/ign-gazebo/pull/1104) + * [Pull request #1104](https://github.com/gazebosim/gz-sim/pull/1104) 1. Fix generation of systems library symlinks in build directory - * [Pull request #1160](https://github.com/ignitionrobotics/ign-gazebo/pull/1160) + * [Pull request #1160](https://github.com/gazebosim/gz-sim/pull/1160) 1. Backport gazebo::Util::validTopic() from ign-gazebo4. - * [Pull request #1153](https://github.com/ignitionrobotics/ign-gazebo/pull/1153) + * [Pull request #1153](https://github.com/gazebosim/gz-sim/pull/1153) 1. Support setting the background color for sensors - * [Pull request #1147](https://github.com/ignitionrobotics/ign-gazebo/pull/1147) + * [Pull request #1147](https://github.com/gazebosim/gz-sim/pull/1147) 1. Use uint64_t for ComponentInspector Entity IDs - * [Pull request #1144](https://github.com/ignitionrobotics/ign-gazebo/pull/1144) + * [Pull request #1144](https://github.com/gazebosim/gz-sim/pull/1144) 1. Fix integers and floats on component inspector - * [Pull request #1143](https://github.com/ignitionrobotics/ign-gazebo/pull/1143) + * [Pull request #1143](https://github.com/gazebosim/gz-sim/pull/1143) ### Ignition Gazebo 3.11.0 (2021-10-21) 1. Updates to camera video record from subt. - * [Pull request #1117](https://github.com/ignitionrobotics/ign-gazebo/pull/1117) + * [Pull request #1117](https://github.com/gazebosim/gz-sim/pull/1117) 1. Fix performance level test flakiness. - * [Pull request #1129](https://github.com/ignitionrobotics/ign-gazebo/pull/1129) + * [Pull request #1129](https://github.com/gazebosim/gz-sim/pull/1129) ### Ignition Gazebo 3.10.0 (2021-10-15) 1. Performance: use std::unordered_map where possible in SceneManager - * [Pull request #1083](https://github.com/ignitionrobotics/ign-gazebo/pull/1083) + * [Pull request #1083](https://github.com/gazebosim/gz-sim/pull/1083) 1. Enable new CMake policy to fix protobuf compilation - * [Pull request #1059](https://github.com/ignitionrobotics/ign-gazebo/pull/1059) + * [Pull request #1059](https://github.com/gazebosim/gz-sim/pull/1059) 1. Fix setting cast_shadows for visuals without material - * [Pull request #1015](https://github.com/ignitionrobotics/ign-gazebo/pull/1015) + * [Pull request #1015](https://github.com/gazebosim/gz-sim/pull/1015) 1. Remove duplicate XML tag in pendulum_links example world - * [Pull request #1002](https://github.com/ignitionrobotics/ign-gazebo/pull/1002) + * [Pull request #1002](https://github.com/gazebosim/gz-sim/pull/1002) 1. Enable sensor metrics on example worlds - * [Pull request #982](https://github.com/ignitionrobotics/ign-gazebo/pull/982) + * [Pull request #982](https://github.com/gazebosim/gz-sim/pull/982) 1. Improved doxygen - * [Pull request #996](https://github.com/ignitionrobotics/ign-gazebo/pull/996) + * [Pull request #996](https://github.com/gazebosim/gz-sim/pull/996) 1. JointPositionController: Improve misleading error message - * [Pull request #1098](https://github.com/ignitionrobotics/ign-gazebo/pull/1098) + * [Pull request #1098](https://github.com/gazebosim/gz-sim/pull/1098) 1. Adjust pose decimals based on element width - * [Pull request #1089](https://github.com/ignitionrobotics/ign-gazebo/pull/1089) + * [Pull request #1089](https://github.com/gazebosim/gz-sim/pull/1089) 1. Fixed IMU system plugin - * [Pull request #1043](https://github.com/ignitionrobotics/ign-gazebo/pull/1043) + * [Pull request #1043](https://github.com/gazebosim/gz-sim/pull/1043) 1. Use QTimer to update plugins in the Qt thread - * [Pull request #1095](https://github.com/ignitionrobotics/ign-gazebo/pull/1095) + * [Pull request #1095](https://github.com/gazebosim/gz-sim/pull/1095) ### Ignition Gazebo 3.9.0 (2021-08-16) 1. Entity tree: prevent creation of repeated entity items - * [Pull request #974](https://github.com/ignitionrobotics/ign-gazebo/pull/974) + * [Pull request #974](https://github.com/gazebosim/gz-sim/pull/974) 1. Don't use $HOME on most tests (InternalFixture) - * [Pull request #971](https://github.com/ignitionrobotics/ign-gazebo/pull/971) + * [Pull request #971](https://github.com/gazebosim/gz-sim/pull/971) 1. Be more specific when looking for physics plugins - * [Pull request #965](https://github.com/ignitionrobotics/ign-gazebo/pull/965) + * [Pull request #965](https://github.com/gazebosim/gz-sim/pull/965) 1. Drag and drop meshes into scene - * [Pull request #939](https://github.com/ignitionrobotics/ign-gazebo/pull/939) + * [Pull request #939](https://github.com/gazebosim/gz-sim/pull/939) 1. Set protobuf_MODULE_COMPATIBLE before any find_package call - * [Pull request #957](https://github.com/ignitionrobotics/ign-gazebo/pull/957) + * [Pull request #957](https://github.com/gazebosim/gz-sim/pull/957) 1. [DiffDrive] add enable/disable - * [Pull request #772](https://github.com/ignitionrobotics/ign-gazebo/pull/772) + * [Pull request #772](https://github.com/gazebosim/gz-sim/pull/772) 1. Fix component inspector shutdown crash - * [Pull request #724](https://github.com/ignitionrobotics/ign-gazebo/pull/724) + * [Pull request #724](https://github.com/gazebosim/gz-sim/pull/724) 1. Add UserCommands Plugin. - * [Pull request #719](https://github.com/ignitionrobotics/ign-gazebo/pull/719) + * [Pull request #719](https://github.com/gazebosim/gz-sim/pull/719) 1. Setting the intiial velocity for a model or joint - * [Pull request #693](https://github.com/ignitionrobotics/ign-gazebo/pull/693) + * [Pull request #693](https://github.com/gazebosim/gz-sim/pull/693) 1. Examples and tutorial on using rendering API from plugins - * [Pull request #596](https://github.com/ignitionrobotics/ign-gazebo/pull/596) + * [Pull request #596](https://github.com/gazebosim/gz-sim/pull/596) 1. Add missing IGNITION_GAZEBO_VISIBLE macros - * [Pull request #563](https://github.com/ignitionrobotics/ign-gazebo/pull/563) + * [Pull request #563](https://github.com/gazebosim/gz-sim/pull/563) 1. Fix visibility macro names when used by a different component (Windows) - * [Pull request #564](https://github.com/ignitionrobotics/ign-gazebo/pull/564) + * [Pull request #564](https://github.com/gazebosim/gz-sim/pull/564) 1. No install apt recommends and clear cache - * [Pull request #423](https://github.com/ignitionrobotics/ign-gazebo/pull/423) + * [Pull request #423](https://github.com/gazebosim/gz-sim/pull/423) 1. Add 25percent darker view angle icons - * [Pull request #426](https://github.com/ignitionrobotics/ign-gazebo/pull/426) + * [Pull request #426](https://github.com/gazebosim/gz-sim/pull/426) 1. Expose a test fixture helper class - * [Pull request #926](https://github.com/ignitionrobotics/ign-gazebo/pull/926) + * [Pull request #926](https://github.com/gazebosim/gz-sim/pull/926) 1. Fix logic to disable server default plugins loading - * [Pull request #953](https://github.com/ignitionrobotics/ign-gazebo/pull/953) + * [Pull request #953](https://github.com/gazebosim/gz-sim/pull/953) 1. removed unneeded plugin update - * [Pull request #944](https://github.com/ignitionrobotics/ign-gazebo/pull/944) + * [Pull request #944](https://github.com/gazebosim/gz-sim/pull/944) 1. Functions to enable velocity and acceleration checks on Link - * [Pull request #935](https://github.com/ignitionrobotics/ign-gazebo/pull/935) + * [Pull request #935](https://github.com/gazebosim/gz-sim/pull/935) 1. Support adding systems that don't come from a plugin - * [Pull request #936](https://github.com/ignitionrobotics/ign-gazebo/pull/936) + * [Pull request #936](https://github.com/gazebosim/gz-sim/pull/936) 1. 3D plot GUI plugin - * [Pull request #917](https://github.com/ignitionrobotics/ign-gazebo/pull/917) + * [Pull request #917](https://github.com/gazebosim/gz-sim/pull/917) 1. Add a convenience function for getting possibly non-existing components. - * [Pull request #629](https://github.com/ignitionrobotics/ign-gazebo/pull/629) + * [Pull request #629](https://github.com/gazebosim/gz-sim/pull/629) 1. Fix topLevelModel method - * [Pull request #600](https://github.com/ignitionrobotics/ign-gazebo/pull/600) + * [Pull request #600](https://github.com/gazebosim/gz-sim/pull/600) 1. World exporter - * [Pull request #474](https://github.com/ignitionrobotics/ign-gazebo/pull/474) + * [Pull request #474](https://github.com/gazebosim/gz-sim/pull/474) 1. Fix finding PBR materials - * [Pull request #575](https://github.com/ignitionrobotics/ign-gazebo/pull/575) + * [Pull request #575](https://github.com/gazebosim/gz-sim/pull/575) 1. Handle multiple logical cameras - * [Pull request #539](https://github.com/ignitionrobotics/ign-gazebo/pull/539) + * [Pull request #539](https://github.com/gazebosim/gz-sim/pull/539) 1. Make some tests more robust - * [Pull request #314](https://github.com/ignitionrobotics/ign-gazebo/pull/314) + * [Pull request #314](https://github.com/gazebosim/gz-sim/pull/314) 1. Fix codecheck - * [Pull request #887](https://github.com/ignitionrobotics/ign-gazebo/pull/887) + * [Pull request #887](https://github.com/gazebosim/gz-sim/pull/887) 1. Hello world plugin added - * [Pull request #699](https://github.com/ignitionrobotics/ign-gazebo/pull/699) + * [Pull request #699](https://github.com/gazebosim/gz-sim/pull/699) 1. Model info CLI `ign model` - * [Pull request #893](https://github.com/ignitionrobotics/ign-gazebo/pull/893) + * [Pull request #893](https://github.com/gazebosim/gz-sim/pull/893) 1. Don't create components for entities that don't exist - * [Pull request #927](https://github.com/ignitionrobotics/ign-gazebo/pull/927) + * [Pull request #927](https://github.com/gazebosim/gz-sim/pull/927) 1. Adds Mesh Tutorial - * [Pull request #915](https://github.com/ignitionrobotics/ign-gazebo/pull/915) + * [Pull request #915](https://github.com/gazebosim/gz-sim/pull/915) 1. Fix updating GUI plugin on load - * [Pull request #904](https://github.com/ignitionrobotics/ign-gazebo/pull/904) + * [Pull request #904](https://github.com/gazebosim/gz-sim/pull/904) 1. Fix documentation for the Sensor component - * [Pull request #898](https://github.com/ignitionrobotics/ign-gazebo/pull/898) + * [Pull request #898](https://github.com/gazebosim/gz-sim/pull/898) 1. Use UINT64_MAX for kComponentTpyeIDInvalid instead of relying on underflow - * [Pull request #889](https://github.com/ignitionrobotics/ign-gazebo/pull/889) + * [Pull request #889](https://github.com/gazebosim/gz-sim/pull/889) 1. Fix mouse view control target position - * [Pull request #879](https://github.com/ignitionrobotics/ign-gazebo/pull/879) + * [Pull request #879](https://github.com/gazebosim/gz-sim/pull/879) 1. Set GUI camera pose - * [Pull request #863](https://github.com/ignitionrobotics/ign-gazebo/pull/863) + * [Pull request #863](https://github.com/gazebosim/gz-sim/pull/863) 1. Enables confirmation dialog when closing Gazebo. - * [Pull request #850](https://github.com/ignitionrobotics/ign-gazebo/pull/850) + * [Pull request #850](https://github.com/gazebosim/gz-sim/pull/850) 1. Depend on ign-rendering 3.5 - * [Pull request #867](https://github.com/ignitionrobotics/ign-gazebo/pull/867) + * [Pull request #867](https://github.com/gazebosim/gz-sim/pull/867) 1. Using math::SpeedLimiter on the diff_drive controller. - * [Pull request #833](https://github.com/ignitionrobotics/ign-gazebo/pull/833) + * [Pull request #833](https://github.com/gazebosim/gz-sim/pull/833) 1. New example: get an ECM snapshot from an external program - * [Pull request #859](https://github.com/ignitionrobotics/ign-gazebo/pull/859) + * [Pull request #859](https://github.com/gazebosim/gz-sim/pull/859) 1. Fix WindEffects Plugin bug, not configuring new links - * [Pull request #844](https://github.com/ignitionrobotics/ign-gazebo/pull/844) + * [Pull request #844](https://github.com/gazebosim/gz-sim/pull/844) 1. Fix potentially flaky integration component test case - * [Pull request #848](https://github.com/ignitionrobotics/ign-gazebo/pull/848) + * [Pull request #848](https://github.com/gazebosim/gz-sim/pull/848) 1. Cleanup and alphabetize plugin headers - * [Pull request #838](https://github.com/ignitionrobotics/ign-gazebo/pull/838) + * [Pull request #838](https://github.com/gazebosim/gz-sim/pull/838) 1. Removed duplicated code with rendering::sceneFromFirstRenderEngine - * [Pull request #819](https://github.com/ignitionrobotics/ign-gazebo/pull/819) + * [Pull request #819](https://github.com/gazebosim/gz-sim/pull/819) 1. Remove unused headers in video_recoder plugin - * [Pull request #834](https://github.com/ignitionrobotics/ign-gazebo/pull/834) + * [Pull request #834](https://github.com/gazebosim/gz-sim/pull/834) 1. Use moveToHelper from ign-rendering - * [Pull request #825](https://github.com/ignitionrobotics/ign-gazebo/pull/825) + * [Pull request #825](https://github.com/gazebosim/gz-sim/pull/825) 1. Remove tools/code_check and update codecov - * [Pull request #814](https://github.com/ignitionrobotics/ign-gazebo/pull/814) + * [Pull request #814](https://github.com/gazebosim/gz-sim/pull/814) 1. Add service and GUI to configure physics parameters - * [Pull request #536](https://github.com/ignitionrobotics/ign-gazebo/pull/536) - * [Pull request #812](https://github.com/ignitionrobotics/ign-gazebo/pull/812) + * [Pull request #536](https://github.com/gazebosim/gz-sim/pull/536) + * [Pull request #812](https://github.com/gazebosim/gz-sim/pull/812) 1. Fix documentation for EntityComponentManager::EachNew - * [Pull request #795](https://github.com/ignitionrobotics/ign-gazebo/pull/795) + * [Pull request #795](https://github.com/gazebosim/gz-sim/pull/795) 1. Fix macOS build: components::Name in benchmark - * [Pull request #784](https://github.com/ignitionrobotics/ign-gazebo/pull/784) + * [Pull request #784](https://github.com/gazebosim/gz-sim/pull/784) 1. Don't store duplicate ComponentTypeId in ECM - * [Pull request #751](https://github.com/ignitionrobotics/ign-gazebo/pull/751) + * [Pull request #751](https://github.com/gazebosim/gz-sim/pull/751) 1. [TPE] Support setting individual link velocity - * [Pull request #427](https://github.com/ignitionrobotics/ign-gazebo/pull/427) + * [Pull request #427](https://github.com/gazebosim/gz-sim/pull/427) 1. 👩‍🌾 Enable Focal CI - * [Pull request #646](https://github.com/ignitionrobotics/ign-gazebo/pull/646) + * [Pull request #646](https://github.com/gazebosim/gz-sim/pull/646) 1. Update benchmark comparison instructions - * [Pull request #766](https://github.com/ignitionrobotics/ign-gazebo/pull/766) + * [Pull request #766](https://github.com/gazebosim/gz-sim/pull/766) 1. Use Protobuf_IMPORT_DIRS instead of PROTOBUF_IMPORT_DIRS for compatibility with Protobuf CMake config - * [Pull request #715](https://github.com/ignitionrobotics/ign-gazebo/pull/715) + * [Pull request #715](https://github.com/gazebosim/gz-sim/pull/715) 1. Do not pass -Wno-unused-parameter to MSVC compiler - * [Pull request #716](https://github.com/ignitionrobotics/ign-gazebo/pull/716) + * [Pull request #716](https://github.com/gazebosim/gz-sim/pull/716) 1. Scenebroadcaster sensors - * [Pull request #698](https://github.com/ignitionrobotics/ign-gazebo/pull/698) + * [Pull request #698](https://github.com/gazebosim/gz-sim/pull/698) 1. Make it so joint state publisher is quieter - * [Pull request #696](https://github.com/ignitionrobotics/ign-gazebo/pull/696) + * [Pull request #696](https://github.com/gazebosim/gz-sim/pull/696) ### Ignition Gazebo 3.8.0 (2021-03-17) 1. Add joint position controller GUI, also enable tests for GUI plugins - * [Pull request #534](https://github.com/ignitionrobotics/ign-gazebo/pull/534) + * [Pull request #534](https://github.com/gazebosim/gz-sim/pull/534) 1. Remove visibility from headers that are not installed - * [Pull request #665](https://github.com/ignitionrobotics/ign-gazebo/pull/665) + * [Pull request #665](https://github.com/gazebosim/gz-sim/pull/665) 1. Added screenshot to toolbar - * [Pull request #588](https://github.com/ignitionrobotics/ign-gazebo/pull/588) + * [Pull request #588](https://github.com/gazebosim/gz-sim/pull/588) 1. Improve ign tool support on macOS - * [Pull request #477](https://github.com/ignitionrobotics/ign-gazebo/pull/477) + * [Pull request #477](https://github.com/gazebosim/gz-sim/pull/477) 1. change nullptr to a int ptr for qt 5.15.2 bug - * [Pull request #527](https://github.com/ignitionrobotics/ign-gazebo/pull/527) + * [Pull request #527](https://github.com/gazebosim/gz-sim/pull/527) 1. Kinetic energy monitor plugin - * [Pull request #492](https://github.com/ignitionrobotics/ign-gazebo/pull/492) + * [Pull request #492](https://github.com/gazebosim/gz-sim/pull/492) 1. Use a std::promise/std::future to avoid busy waiting the step ack messages in NetworkManagerPrimary - * [Pull request #470](https://github.com/ignitionrobotics/ign-gazebo/pull/470) + * [Pull request #470](https://github.com/gazebosim/gz-sim/pull/470) 1. clarified performer example - * [Pull request #390](https://github.com/ignitionrobotics/ign-gazebo/pull/390) + * [Pull request #390](https://github.com/gazebosim/gz-sim/pull/390) 1. Add tutorial tweaks - * [Pull request #380](https://github.com/ignitionrobotics/ign-gazebo/pull/380) + * [Pull request #380](https://github.com/gazebosim/gz-sim/pull/380) 1. Fix Qt5 warnings for using anchors - * [Pull request #363](https://github.com/ignitionrobotics/ign-gazebo/pull/363) + * [Pull request #363](https://github.com/gazebosim/gz-sim/pull/363) 1. Update codeowners - * [Pull request #305](https://github.com/ignitionrobotics/ign-gazebo/pull/305) + * [Pull request #305](https://github.com/gazebosim/gz-sim/pull/305) 1. Qt auto scale factor for HiDPI displays - * [Pull request #291](https://github.com/ignitionrobotics/ign-gazebo/pull/291) + * [Pull request #291](https://github.com/gazebosim/gz-sim/pull/291) 1. Fix yaw units - * [Pull request #238](https://github.com/ignitionrobotics/ign-gazebo/pull/238) + * [Pull request #238](https://github.com/gazebosim/gz-sim/pull/238) 1. Fixed docblock showGrid - * [Pull request #152](https://github.com/ignitionrobotics/ign-gazebo/pull/152) + * [Pull request #152](https://github.com/gazebosim/gz-sim/pull/152) 1. Fix entity tree for large worlds - * [Pull request #673](https://github.com/ignitionrobotics/ign-gazebo/pull/673) + * [Pull request #673](https://github.com/gazebosim/gz-sim/pull/673) 1. Master branch updates - * [Pull request #672](https://github.com/ignitionrobotics/ign-gazebo/pull/672) + * [Pull request #672](https://github.com/gazebosim/gz-sim/pull/672) 1. Backport #561: Use common::setenv - * [Pull request #666](https://github.com/ignitionrobotics/ign-gazebo/pull/666) + * [Pull request #666](https://github.com/gazebosim/gz-sim/pull/666) 1. Use a custom data structure to manage entity feature maps - * [Pull request #586](https://github.com/ignitionrobotics/ign-gazebo/pull/586) + * [Pull request #586](https://github.com/gazebosim/gz-sim/pull/586) 1. Limit scene broadcast publications when paused - * [Pull request #497](https://github.com/ignitionrobotics/ign-gazebo/pull/497) + * [Pull request #497](https://github.com/gazebosim/gz-sim/pull/497) 1. Fix flaky SceneBoradcaster test - * [Pull request #641](https://github.com/ignitionrobotics/ign-gazebo/pull/641) + * [Pull request #641](https://github.com/gazebosim/gz-sim/pull/641) 1. Add TF/Pose_V publisher in DiffDrive - * [Pull request #548](https://github.com/ignitionrobotics/ign-gazebo/pull/548) + * [Pull request #548](https://github.com/gazebosim/gz-sim/pull/548) 1. 👩‍🌾 Relax performance test - * [Pull request #640](https://github.com/ignitionrobotics/ign-gazebo/pull/640) + * [Pull request #640](https://github.com/gazebosim/gz-sim/pull/640) 1. 👩‍🌾 Improve velocity control test - * [Pull request #642](https://github.com/ignitionrobotics/ign-gazebo/pull/642) + * [Pull request #642](https://github.com/gazebosim/gz-sim/pull/642) 1. Add `laser_retro` support - * [Pull request #603](https://github.com/ignitionrobotics/ign-gazebo/pull/603) + * [Pull request #603](https://github.com/gazebosim/gz-sim/pull/603) 1. Fix pose of plane visual with non-default normal vector - * [Pull request #574](https://github.com/ignitionrobotics/ign-gazebo/pull/574) + * [Pull request #574](https://github.com/gazebosim/gz-sim/pull/574) 1. Add About dialog - * [Pull request #609](https://github.com/ignitionrobotics/ign-gazebo/pull/609) + * [Pull request #609](https://github.com/gazebosim/gz-sim/pull/609) 1. Make topics configurable for joint controllers - * [Pull request #584](https://github.com/ignitionrobotics/ign-gazebo/pull/584) + * [Pull request #584](https://github.com/gazebosim/gz-sim/pull/584) 1. Also use Ignition GUI render event - * [Pull request #598](https://github.com/ignitionrobotics/ign-gazebo/pull/598) + * [Pull request #598](https://github.com/gazebosim/gz-sim/pull/598) 1. Tutorial on migrating SDF files from Gazebo classic - * [Pull request #400](https://github.com/ignitionrobotics/ign-gazebo/pull/400) + * [Pull request #400](https://github.com/gazebosim/gz-sim/pull/400) 1. Visualize collisions - * [Pull request #531](https://github.com/ignitionrobotics/ign-gazebo/pull/531) + * [Pull request #531](https://github.com/gazebosim/gz-sim/pull/531) 1. Backport state update changes from pull request #486 - * [Pull request #583](https://github.com/ignitionrobotics/ign-gazebo/pull/583) + * [Pull request #583](https://github.com/gazebosim/gz-sim/pull/583) 1. Publish all periodic change components in Scene Broadcaster - * [Pull request #544](https://github.com/ignitionrobotics/ign-gazebo/pull/544) + * [Pull request #544](https://github.com/gazebosim/gz-sim/pull/544) 1. added size to `ground_plane` in examples - * [Pull request #573](https://github.com/ignitionrobotics/ign-gazebo/pull/573) + * [Pull request #573](https://github.com/gazebosim/gz-sim/pull/573) 1. Parallelize State call in ECM - * [Pull request #451](https://github.com/ignitionrobotics/ign-gazebo/pull/451) + * [Pull request #451](https://github.com/gazebosim/gz-sim/pull/451) 1. Non-blocking paths request - * [Pull request #555](https://github.com/ignitionrobotics/ign-gazebo/pull/555) + * [Pull request #555](https://github.com/gazebosim/gz-sim/pull/555) ### Ignition Gazebo 3.7.0 (2021-01-13) 1. Fix examples in migration plugins tutorial. - * [Pull Request 543](https://github.com/ignitionrobotics/ign-gazebo/pull/543) + * [Pull Request 543](https://github.com/gazebosim/gz-sim/pull/543) 1. Added missing namespace in `detail/EntityComponentManager.hh`. - * [Pull Request 541](https://github.com/ignitionrobotics/ign-gazebo/pull/541) + * [Pull Request 541](https://github.com/gazebosim/gz-sim/pull/541) 1. Automatically load a subset of world plugins. - * [Pull Request 281](https://github.com/ignitionrobotics/ign-gazebo/pull/281) + * [Pull Request 281](https://github.com/gazebosim/gz-sim/pull/281) 1. Update gtest to 1.10.0 for Windows compilation. - * [Pull Request 506](https://github.com/ignitionrobotics/ign-gazebo/pull/506) + * [Pull Request 506](https://github.com/gazebosim/gz-sim/pull/506) 1. Updates to ardupilot migration tutorial. - * [Pull Request 525](https://github.com/ignitionrobotics/ign-gazebo/pull/525) + * [Pull Request 525](https://github.com/gazebosim/gz-sim/pull/525) 1. Don't make docs on macOS. - * [Pull Request 528](https://github.com/ignitionrobotics/ign-gazebo/pull/528) + * [Pull Request 528](https://github.com/gazebosim/gz-sim/pull/528) ### Ignition Gazebo 3.6.0 (2020-12-30) 1. Fix pose msg conversion when msg is missing orientation - * [Pull Request 450](https://github.com/ignitionrobotics/ign-gazebo/pull/450) + * [Pull Request 450](https://github.com/gazebosim/gz-sim/pull/450) 1. Address code checker warnings - * [Pull Request 443](https://github.com/ignitionrobotics/ign-gazebo/pull/443) - * [Pull Request 491](https://github.com/ignitionrobotics/ign-gazebo/pull/491) - * [Pull Request 499](https://github.com/ignitionrobotics/ign-gazebo/pull/499) - * [Pull Request 502](https://github.com/ignitionrobotics/ign-gazebo/pull/502) + * [Pull Request 443](https://github.com/gazebosim/gz-sim/pull/443) + * [Pull Request 491](https://github.com/gazebosim/gz-sim/pull/491) + * [Pull Request 499](https://github.com/gazebosim/gz-sim/pull/499) + * [Pull Request 502](https://github.com/gazebosim/gz-sim/pull/502) 1. Test fixes - * [Pull Request 455](https://github.com/ignitionrobotics/ign-gazebo/pull/455) - * [Pull Request 463](https://github.com/ignitionrobotics/ign-gazebo/pull/463) - * [Pull Request 452](https://github.com/ignitionrobotics/ign-gazebo/pull/452) - * [Pull Request 480](https://github.com/ignitionrobotics/ign-gazebo/pull/480) + * [Pull Request 455](https://github.com/gazebosim/gz-sim/pull/455) + * [Pull Request 463](https://github.com/gazebosim/gz-sim/pull/463) + * [Pull Request 452](https://github.com/gazebosim/gz-sim/pull/452) + * [Pull Request 480](https://github.com/gazebosim/gz-sim/pull/480) 1. Documentation updates - * [Pull Request 472](https://github.com/ignitionrobotics/ign-gazebo/pull/472) + * [Pull Request 472](https://github.com/gazebosim/gz-sim/pull/472) 1. Fix segfault in the Breadcrumb system when associated model is unloaded - * [Pull Request 454](https://github.com/ignitionrobotics/ign-gazebo/pull/454) + * [Pull Request 454](https://github.com/gazebosim/gz-sim/pull/454) 1. Added user commands to example thermal camera world - * [Pull Request 442](https://github.com/ignitionrobotics/ign-gazebo/pull/442) + * [Pull Request 442](https://github.com/gazebosim/gz-sim/pull/442) 1. Helper function to set component data - * [Pull Request 436](https://github.com/ignitionrobotics/ign-gazebo/pull/436) + * [Pull Request 436](https://github.com/gazebosim/gz-sim/pull/436) 1. Remove unneeded if statement in EntityComponentManager - * [Pull Request 432](https://github.com/ignitionrobotics/ign-gazebo/pull/432) + * [Pull Request 432](https://github.com/gazebosim/gz-sim/pull/432) 1. Clarify how time is represented in each phase of a System step - * [Pull Request 467](https://github.com/ignitionrobotics/ign-gazebo/pull/467) + * [Pull Request 467](https://github.com/gazebosim/gz-sim/pull/467) 1. Switch to async state service request - * [Pull Request 461](https://github.com/ignitionrobotics/ign-gazebo/pull/461) + * [Pull Request 461](https://github.com/gazebosim/gz-sim/pull/461) 1. Update key event handling - * [Pull Request 466](https://github.com/ignitionrobotics/ign-gazebo/pull/466) + * [Pull Request 466](https://github.com/gazebosim/gz-sim/pull/466) 1. Tape Measure Plugin - * [Pull Request 456](https://github.com/ignitionrobotics/ign-gazebo/pull/456) + * [Pull Request 456](https://github.com/gazebosim/gz-sim/pull/456) 1. Move deselect and preview termination to render thread - * [Pull Request 493](https://github.com/ignitionrobotics/ign-gazebo/pull/493) + * [Pull Request 493](https://github.com/gazebosim/gz-sim/pull/493) 1. Logical audio sensor plugin - * [Pull Request 401](https://github.com/ignitionrobotics/ign-gazebo/pull/401) + * [Pull Request 401](https://github.com/gazebosim/gz-sim/pull/401) 1. add frame_id and child_frame_id attribute support for DiffDrive - * [Pull Request 361](https://github.com/ignitionrobotics/ign-gazebo/pull/361) + * [Pull Request 361](https://github.com/gazebosim/gz-sim/pull/361) 1. Add ability to record video based on sim time - * [Pull Request 414](https://github.com/ignitionrobotics/ign-gazebo/pull/414) + * [Pull Request 414](https://github.com/gazebosim/gz-sim/pull/414) 1. Add lockstep mode to video recording - * [Pull Request 419](https://github.com/ignitionrobotics/ign-gazebo/pull/419) + * [Pull Request 419](https://github.com/gazebosim/gz-sim/pull/419) 1. Disable right click menu when using measuring tool - * [Pull Request 458](https://github.com/ignitionrobotics/ign-gazebo/pull/458) + * [Pull Request 458](https://github.com/gazebosim/gz-sim/pull/458) ### Ignition Gazebo 3.5.0 (2020-11-03) 1. Updated source build instructions - * [Pull Request 403](https://github.com/ignitionrobotics/ign-gazebo/pull/403) + * [Pull Request 403](https://github.com/gazebosim/gz-sim/pull/403) 1. More world APIs, helper function ComponentData - * [Pull Request 378](https://github.com/ignitionrobotics/ign-gazebo/pull/378) + * [Pull Request 378](https://github.com/gazebosim/gz-sim/pull/378) 1. Improve fork experience - * [Pull Request 411](https://github.com/ignitionrobotics/ign-gazebo/pull/411) + * [Pull Request 411](https://github.com/gazebosim/gz-sim/pull/411) 1. Fix a crash in the grid config plugin, set grid material - * [Pull Request 412](https://github.com/ignitionrobotics/ign-gazebo/pull/412) + * [Pull Request 412](https://github.com/gazebosim/gz-sim/pull/412) 1. Document deprecation of log playback `` SDF param - * [Pull Request 424](https://github.com/ignitionrobotics/ign-gazebo/pull/424) - * [Pull Request 425](https://github.com/ignitionrobotics/ign-gazebo/pull/425) + * [Pull Request 424](https://github.com/gazebosim/gz-sim/pull/424) + * [Pull Request 425](https://github.com/gazebosim/gz-sim/pull/425) 1. Enable mouse highlighting selection on resource spawner - * [Pull Request 402](https://github.com/ignitionrobotics/ign-gazebo/pull/402) + * [Pull Request 402](https://github.com/gazebosim/gz-sim/pull/402) 1. Add support for custom render engines - * [Pull Request 373](https://github.com/ignitionrobotics/ign-gazebo/pull/373) + * [Pull Request 373](https://github.com/gazebosim/gz-sim/pull/373) 1. Component Vector -> Map ECM Optimization - * [Pull Request 416](https://github.com/ignitionrobotics/ign-gazebo/pull/416) + * [Pull Request 416](https://github.com/gazebosim/gz-sim/pull/416) ### Ignition Gazebo 3.4.0 (2020-10-14) 1. Fix gui sendEvent memory leaks - * [Pull Request 365](https://github.com/ignitionrobotics/ign-gazebo/pull/365) + * [Pull Request 365](https://github.com/gazebosim/gz-sim/pull/365) 1. Support nested models - * [Pull Request 258](https://github.com/ignitionrobotics/ign-gazebo/pull/258) + * [Pull Request 258](https://github.com/gazebosim/gz-sim/pull/258) 1. Generalize actor count and pose in actor population erb SDF - * [Pull Request 336](https://github.com/ignitionrobotics/ign-gazebo/pull/336) + * [Pull Request 336](https://github.com/gazebosim/gz-sim/pull/336) 1. Add more link APIs, with tutorial - * [Pull Request 375](https://github.com/ignitionrobotics/ign-gazebo/pull/375) + * [Pull Request 375](https://github.com/gazebosim/gz-sim/pull/375) 1. Add screenshots to GUI config tutorial - * [Pull Request 406](https://github.com/ignitionrobotics/ign-gazebo/pull/406) + * [Pull Request 406](https://github.com/gazebosim/gz-sim/pull/406) 1. Fix adding performers to entity tree - * [Pull Request 374](https://github.com/ignitionrobotics/ign-gazebo/pull/374) + * [Pull Request 374](https://github.com/gazebosim/gz-sim/pull/374) 1. Remove sidebar and put world control in bottom left for joint controller examples - * [Pull Request 384](https://github.com/ignitionrobotics/ign-gazebo/pull/384) + * [Pull Request 384](https://github.com/gazebosim/gz-sim/pull/384) 1. Allow executing a blocking single Server run in both paused and unpaused states - * [Pull Request 297](https://github.com/ignitionrobotics/ign-gazebo/pull/297) + * [Pull Request 297](https://github.com/gazebosim/gz-sim/pull/297) 1. Add camera video recorder system - * [Pull Request 316](https://github.com/ignitionrobotics/ign-gazebo/pull/316) + * [Pull Request 316](https://github.com/gazebosim/gz-sim/pull/316) 1. Decrease time step for quadcopter world - * [Pull Request 372](https://github.com/ignitionrobotics/ign-gazebo/pull/372) + * [Pull Request 372](https://github.com/gazebosim/gz-sim/pull/372) 1. Add support for moving the GUI camera to a pose - * [Pull Request 352](https://github.com/ignitionrobotics/ign-gazebo/pull/352) + * [Pull Request 352](https://github.com/gazebosim/gz-sim/pull/352) 1. Remove `lib`+`.so` from plugin's name - * [Pull Request 279](https://github.com/ignitionrobotics/ign-gazebo/pull/279) - * [Pull Request 335](https://github.com/ignitionrobotics/ign-gazebo/pull/335) + * [Pull Request 279](https://github.com/gazebosim/gz-sim/pull/279) + * [Pull Request 335](https://github.com/gazebosim/gz-sim/pull/335) 1. EntityComponentManager::EachRemoved documentation fix. - * [Pull Request 348](https://github.com/ignitionrobotics/ign-gazebo/pull/348) + * [Pull Request 348](https://github.com/gazebosim/gz-sim/pull/348) 1. Add more model APIs. - * [Pull Request 349](https://github.com/ignitionrobotics/ign-gazebo/pull/349) + * [Pull Request 349](https://github.com/gazebosim/gz-sim/pull/349) 1. Update dimensions of the grid config. - * [Pull Request 383](https://github.com/ignitionrobotics/ign-gazebo/pull/383) + * [Pull Request 383](https://github.com/gazebosim/gz-sim/pull/383) 1. Fix top-left toolbar layout so magnet shows. - * [Pull Request 381](https://github.com/ignitionrobotics/ign-gazebo/pull/381) + * [Pull Request 381](https://github.com/gazebosim/gz-sim/pull/381) 1. Add instructions to bitmask world. - * [Pull Request 377](https://github.com/ignitionrobotics/ign-gazebo/pull/377) + * [Pull Request 377](https://github.com/gazebosim/gz-sim/pull/377) 1. Add search and sort for resource spawner. - * [Pull Request 359](https://github.com/ignitionrobotics/ign-gazebo/pull/359) + * [Pull Request 359](https://github.com/gazebosim/gz-sim/pull/359) 1. Fix source build instructions for ign-gazebo3. - * [Pull Request 395](https://github.com/ignitionrobotics/ign-gazebo/pull/395) + * [Pull Request 395](https://github.com/gazebosim/gz-sim/pull/395) 1. Added playback scrubber GUI - * [Pull Request 299](https://github.com/ignitionrobotics/ign-gazebo/pull/299) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 299](https://github.com/gazebosim/gz-sim/pull/299) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Added wheel slip system plugin. - * [Pull Request 134](https://github.com/ignitionrobotics/ign-gazebo/pull/134) - * [Pull Request 357](https://github.com/ignitionrobotics/ign-gazebo/pull/357) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 134](https://github.com/gazebosim/gz-sim/pull/134) + * [Pull Request 357](https://github.com/gazebosim/gz-sim/pull/357) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Enhanced log playback performance. - * [Pull Request 351](https://github.com/ignitionrobotics/ign-gazebo/pull/351) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 351](https://github.com/gazebosim/gz-sim/pull/351) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Tests & Warnings: Qt 5.14, breadcrumbs, Gui, ign_TEST - * [Pull Request 327](https://github.com/ignitionrobotics/ign-gazebo/pull/327) + * [Pull Request 327](https://github.com/gazebosim/gz-sim/pull/327) 1. Added support for specifying topics to record. - * [Pull Request 315](https://github.com/ignitionrobotics/ign-gazebo/pull/315) + * [Pull Request 315](https://github.com/gazebosim/gz-sim/pull/315) 1. Make sure OpenGL core profile context is used by GzScene3D. - * [Pull Request 339](https://github.com/ignitionrobotics/ign-gazebo/pull/339) + * [Pull Request 339](https://github.com/gazebosim/gz-sim/pull/339) 1. Support relative paths for PBR materials - * [Pull Request 328](https://github.com/ignitionrobotics/ign-gazebo/pull/328) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 328](https://github.com/gazebosim/gz-sim/pull/328) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Add file extension automatically for record plugin. - * [Pull Request 303](https://github.com/ignitionrobotics/ign-gazebo/pull/303) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 303](https://github.com/gazebosim/gz-sim/pull/303) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Support spawning during log playback. - * [Pull Request 346](https://github.com/ignitionrobotics/ign-gazebo/pull/346) + * [Pull Request 346](https://github.com/gazebosim/gz-sim/pull/346) + +1. Added wheel slip system plugin. + * [Pull Request 134](https://github.com/gazebosim/gz-sim/pull/134) + * [Pull Request 357](https://github.com/gazebosim/gz-sim/pull/357) 1. Add Render Engine Cmd Line option - * [Pull Request 331](https://github.com/ignitionrobotics/ign-gazebo/pull/331) + * [Pull Request 331](https://github.com/gazebosim/gz-sim/pull/331) ### Ignition Gazebo 3.3.0 (2020-08-31) 1. Added marker array service. - * [pull request 302](https://github.com/ignitionrobotics/ign-gazebo/pull/302) + * [pull request 302](https://github.com/gazebosim/gz-sim/pull/302) 1. Introduced a new parameter in the scene3D plugin to launch in fullscreen. - * [pull request 254](https://github.com/ignitionrobotics/ign-gazebo/pull/254) + * [pull request 254](https://github.com/gazebosim/gz-sim/pull/254) 1. Fix issue #285 by adding checks for a marker's parent. - * [pull request 290](https://github.com/ignitionrobotics/ign-gazebo/pull/290) + * [pull request 290](https://github.com/gazebosim/gz-sim/pull/290) 1. Fix non-specified material error. - * [pull request 292](https://github.com/ignitionrobotics/ign-gazebo/pull/292) + * [pull request 292](https://github.com/gazebosim/gz-sim/pull/292) 1. Added simulation world with large number of entities. - * [pull request 283](https://github.com/ignitionrobotics/ign-gazebo/pull/283) + * [pull request 283](https://github.com/gazebosim/gz-sim/pull/283) 1. Fixed parsing of the touch plugin' enabled flag. - * [pull request 275](https://github.com/ignitionrobotics/ign-gazebo/pull/275) + * [pull request 275](https://github.com/gazebosim/gz-sim/pull/275) 1. Added buoyancy system plugin. - * [pull request 252](https://github.com/ignitionrobotics/ign-gazebo/pull/252) + * [pull request 252](https://github.com/gazebosim/gz-sim/pull/252) 1. Implemented shift + drag = rotate in the GUI. - * [pull request 247](https://github.com/ignitionrobotics/ign-gazebo/pull/247) + * [pull request 247](https://github.com/gazebosim/gz-sim/pull/247) 1. Backport collision bitmask changes - * [pull request 223](https://github.com/ignitionrobotics/ign-gazebo/pull/223) + * [pull request 223](https://github.com/gazebosim/gz-sim/pull/223) 1. Added velocity command to TPE. - * [pull request 169](https://github.com/ignitionrobotics/ign-gazebo/pull/169) + * [pull request 169](https://github.com/gazebosim/gz-sim/pull/169) 1. This version includes all features in Gazebo 2.23.0 ### Ignition Gazebo 3.2.0 (2020-05-20) 1. Merge ign-gazebo2 to ign-gazebo3 - * [pull request 149](https://github.com/ignitionrobotics/ign-gazebo/pull/149) + * [pull request 149](https://github.com/gazebosim/gz-sim/pull/149) ### Ignition Gazebo 3.1.0 (2020-05-19) 1. Port support for computing model bounding box in physics system - * [pull request 127](https://github.com/ignitionrobotics/ign-gazebo/pull/127) + * [pull request 127](https://github.com/gazebosim/gz-sim/pull/127) 1. Add DetachableJoint: A system that initially attaches two models via a fixed joint and allows for the models to get detached during simulation via a topic. * [BitBucket pull request 440](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/440) @@ -2812,7 +2865,7 @@ * [BitBucket pull request 514](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/514) 1. Add window focus upon mouse entering the render window - * [Github pull request 96](https://github.com/ignitionrobotics/ign-gazebo/pull/96) + * [Github pull request 96](https://github.com/gazebosim/gz-sim/pull/96) ### Ignition Gazebo 3.0.0 (2019-12-10) @@ -2853,154 +2906,154 @@ ### Ignition Gazebo 2.25.0 (2020-09-17) 1. Added wheel slip system plugin. - * [Pull Request 134](https://github.com/ignitionrobotics/ign-gazebo/pull/134) - * [Pull Request 357](https://github.com/ignitionrobotics/ign-gazebo/pull/357) + * [Pull Request 134](https://github.com/gazebosim/gz-sim/pull/134) + * [Pull Request 357](https://github.com/gazebosim/gz-sim/pull/357) 1. Enhanced log playback performance. - * [Pull Request 351](https://github.com/ignitionrobotics/ign-gazebo/pull/351) + * [Pull Request 351](https://github.com/gazebosim/gz-sim/pull/351) 1. Tests & Warnings: Qt 5.14, breadcrumbs, Gui, ign_TEST - * [Pull Request 327](https://github.com/ignitionrobotics/ign-gazebo/pull/327) + * [Pull Request 327](https://github.com/gazebosim/gz-sim/pull/327) 1. Added support for specifying topics to record. - * [Pull Request 315](https://github.com/ignitionrobotics/ign-gazebo/pull/315) + * [Pull Request 315](https://github.com/gazebosim/gz-sim/pull/315) 1. Make sure OpenGL core profile context is used by GzScene3D. - * [Pull Request 339](https://github.com/ignitionrobotics/ign-gazebo/pull/339) + * [Pull Request 339](https://github.com/gazebosim/gz-sim/pull/339) 1. Support relative paths for PBR materials - * [Pull Request 328](https://github.com/ignitionrobotics/ign-gazebo/pull/328) + * [Pull Request 328](https://github.com/gazebosim/gz-sim/pull/328) 1. Add file extension automatically for record plugin. - * [Pull Request 303](https://github.com/ignitionrobotics/ign-gazebo/pull/303) + * [Pull Request 303](https://github.com/gazebosim/gz-sim/pull/303) 1. Support spawning during log playback. - * [Pull Request 346](https://github.com/ignitionrobotics/ign-gazebo/pull/346) + * [Pull Request 346](https://github.com/gazebosim/gz-sim/pull/346) ### Ignition Gazebo 2.24.0 (2020-09-03) 1. Resource env var, with transport interface. - * [Pull Request 172](https://github.com/ignitionrobotics/ign-gazebo/pull/172) + * [Pull Request 172](https://github.com/gazebosim/gz-sim/pull/172) 1. Save http URIs (fix tests) - * [Pull Request 271](https://github.com/ignitionrobotics/ign-gazebo/pull/271) + * [Pull Request 271](https://github.com/gazebosim/gz-sim/pull/271) 1. Insert Local Models. - * [Pull Request 173](https://github.com/ignitionrobotics/ign-gazebo/pull/173) + * [Pull Request 173](https://github.com/gazebosim/gz-sim/pull/173) 1. Modernize actions CI. - * [Pull Request 269](https://github.com/ignitionrobotics/ign-gazebo/pull/269) + * [Pull Request 269](https://github.com/gazebosim/gz-sim/pull/269) 1. Sensor topics available through components and GUI. - * [Pull Request 266](https://github.com/ignitionrobotics/ign-gazebo/pull/266) + * [Pull Request 266](https://github.com/gazebosim/gz-sim/pull/266) 1. Customizable layouts - fully functional. - * [Pull Request 278](https://github.com/ignitionrobotics/ign-gazebo/pull/278) + * [Pull Request 278](https://github.com/gazebosim/gz-sim/pull/278) 1. Add Fuel World Support. - * [Pull Request 274](https://github.com/ignitionrobotics/ign-gazebo/pull/274) + * [Pull Request 274](https://github.com/gazebosim/gz-sim/pull/274) 1. Insert Fuel Models. - * [Pull Request 263](https://github.com/ignitionrobotics/ign-gazebo/pull/263) + * [Pull Request 263](https://github.com/gazebosim/gz-sim/pull/263) 1. Disable rendering tests on macOS that are known to fail. - * [Pull Request 209](https://github.com/ignitionrobotics/ign-gazebo/pull/209) + * [Pull Request 209](https://github.com/gazebosim/gz-sim/pull/209) 1. Fix tests on Blueprint. - * [Pull Request 295](https://github.com/ignitionrobotics/ign-gazebo/pull/295) + * [Pull Request 295](https://github.com/gazebosim/gz-sim/pull/295) 1. Publish remaining breadcrumb deployments. - * [Pull Request 308](https://github.com/ignitionrobotics/ign-gazebo/pull/308) + * [Pull Request 308](https://github.com/gazebosim/gz-sim/pull/308) ### Ignition Gazebo 2.23.0 (2020-07-28) 1. Deactivate PerformerDetector if its parent model gets removed. - * [Pull Request 260](https://github.com/ignitionrobotics/ign-gazebo/pull/260) + * [Pull Request 260](https://github.com/gazebosim/gz-sim/pull/260) 1. Backport support for s from Fuel #255 - * [Pull Request 255](https://github.com/ignitionrobotics/ign-gazebo/pull/255) + * [Pull Request 255](https://github.com/gazebosim/gz-sim/pull/255) ### Ignition Gazebo 2.22.0 (2020-07-22) 1. Allow zero or more key/value pairs to be added to detection header information. - * [Pull Request 257](https://github.com/ignitionrobotics/ign-gazebo/pull/257) + * [Pull Request 257](https://github.com/gazebosim/gz-sim/pull/257) ### 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) + * [Pull Request 222](https://github.com/gazebosim/gz-sim/pull/222) 1. Added an additional pose offset for the performer detector plugin. - * [Pull Request 236](https://github.com/ignitionrobotics/ign-gazebo/pull/236) + * [Pull Request 236](https://github.com/gazebosim/gz-sim/pull/236) 1. Fixed battery issues and updated tutorial. - * [Pull Request 230](https://github.com/ignitionrobotics/ign-gazebo/pull/230) + * [Pull Request 230](https://github.com/gazebosim/gz-sim/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) + * [Pull Request 212](https://github.com/gazebosim/gz-sim/pull/212) ### Ignition Gazebo 2.20.0 (2020-06-09) 1. Updated battery model to stop battery drain when there is no joint velocity/force command, and added a recharging trigger. - * [Pull Request 183](https://github.com/ignitionrobotics/ign-gazebo/pull/183) + * [Pull Request 183](https://github.com/gazebosim/gz-sim/pull/183) 1. Fix segfault in the Breadcrumbs system - * [Pull Request 180](https://github.com/ignitionrobotics/ign-gazebo/pull/180) + * [Pull Request 180](https://github.com/gazebosim/gz-sim/pull/180) 1. Added an `` element to the DiffDrive system so that a custom odometry topic can be used. - * [Pull Request 179](https://github.com/ignitionrobotics/ign-gazebo/pull/179) + * [Pull Request 179](https://github.com/gazebosim/gz-sim/pull/179) ### Ignition Gazebo 2.19.0 (2020-06-02) 1. Use updated model names for spawned models when generating SDFormat - * [Pull Request 166](https://github.com/ignitionrobotics/ign-gazebo/pull/166) + * [Pull Request 166](https://github.com/gazebosim/gz-sim/pull/166) 1. Allow joint force commands (JointForceCmd) to dscharge a battery. - * [Pull Request 165](https://github.com/ignitionrobotics/ign-gazebo/pull/165) + * [Pull Request 165](https://github.com/gazebosim/gz-sim/pull/165) 1. Allow renaming breadcrumb models if there is a name conflict - * [Pull Request 155](https://github.com/ignitionrobotics/ign-gazebo/pull/155) + * [Pull Request 155](https://github.com/gazebosim/gz-sim/pull/155) 1. Add TriggeredPublisher system - * [Pull Request 139](https://github.com/ignitionrobotics/ign-gazebo/pull/139) + * [Pull Request 139](https://github.com/gazebosim/gz-sim/pull/139) 1. Add PerformerDetector, a system for detecting when performers enter a specified region - * [Pull Request 125](https://github.com/ignitionrobotics/ign-gazebo/pull/125) + * [Pull Request 125](https://github.com/gazebosim/gz-sim/pull/125) ### Ignition Gazebo 2.18.0 (2020-05-20) 1. Added a `/world//create_multiple` service that parallels the current `/world//create` service. The `create_multiple` service can handle an `ignition::msgs::EntityFactory_V` message that may contain one or more entities to spawn. - * [Pull Request 146](https://github.com/ignitionrobotics/ign-gazebo/pull/146) + * [Pull Request 146](https://github.com/gazebosim/gz-sim/pull/146) 1. DetachableJoint system: Add option to suppress warning about missing child model - * [Pull Request 132](https://github.com/ignitionrobotics/ign-gazebo/pull/132) + * [Pull Request 132](https://github.com/gazebosim/gz-sim/pull/132) ### Ignition Gazebo 2.17.0 (2020-05-13) 1. Allow battery plugin to work with joint force systems. - * [Pull Request 120](https://github.com/ignitionrobotics/ign-gazebo/pull/120) + * [Pull Request 120](https://github.com/gazebosim/gz-sim/pull/120) 1. Make breadcrumb static after specified time - * [Pull Request 90](https://github.com/ignitionrobotics/ign-gazebo/pull/90) + * [Pull Request 90](https://github.com/gazebosim/gz-sim/pull/90) 1. Disable breadcrumbs if the `max_deployments` == 0. - * [Pull Request 88](https://github.com/ignitionrobotics/ign-gazebo/pull/88) + * [Pull Request 88](https://github.com/gazebosim/gz-sim/pull/88) 1. Add static pose publisher and support pose\_v msg type in pose publisher system - * [Pull Request 65](https://github.com/ignitionrobotics/ign-gazebo/pull/65) + * [Pull Request 65](https://github.com/gazebosim/gz-sim/pull/65) 1. Refactor Gui.hh so that the Gazebo GUI can be ran from other packages - * [Pull Request 79](https://github.com/ignitionrobotics/ign-gazebo/pull/79) + * [Pull Request 79](https://github.com/gazebosim/gz-sim/pull/79) 1. Add ability to save worlds to SDFormat * [BitBucket pull request 545](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/545) 1. Add window focus upon mouse entering the render window - * [Github pull request 95](https://github.com/ignitionrobotics/ign-gazebo/pull/95) + * [Github pull request 95](https://github.com/gazebosim/gz-sim/pull/95) ### Ignition Gazebo 2.16.0 (2020-03-24) diff --git a/NEWS b/NEWS index 604eba6656..a73d9b7c1a 100644 --- a/NEWS +++ b/NEWS @@ -1 +1 @@ -http://ignitionrobotics.org +http://gazebosim.org diff --git a/docker/README.md b/docker/README.md index 052ad65f2b..8a9e390c72 100644 --- a/docker/README.md +++ b/docker/README.md @@ -10,7 +10,7 @@ section below for usage information about This section describes how to build and run a docker image based on nightly builds of downstream -[Ignition libraries](https://ignitionrobotics.org/libs). The Docker image will +[Ignition libraries](https://gazebosim.org/libs). The Docker image will use the Ignition Gazebo code found in the current source tree. **Requirements** diff --git a/docker/scripts/build_ign.sh b/docker/scripts/build_ign.sh index dd12c6479d..b98e5d6133 100755 --- a/docker/scripts/build_ign.sh +++ b/docker/scripts/build_ign.sh @@ -1,8 +1,8 @@ #!/bin/bash # Command line parameters: -# 1 - github organization name. For example ignitionrobotics or osrf. -# 2 - the name of the ignition repository. For example ign-math. -# 3 - the name of the branch. For example ign-math6 +# 1 - github organization name. For example gazebosim or osrf. +# 2 - the name of the ignition repository. For example gz-sim. +# 3 - the name of the branch. For example gz-math7 set -o errexit set -o verbose diff --git a/docker/scripts/upload_json_benchmark.sh b/docker/scripts/upload_json_benchmark.sh index 528b7afa95..9376494c56 100755 --- a/docker/scripts/upload_json_benchmark.sh +++ b/docker/scripts/upload_json_benchmark.sh @@ -1,12 +1,12 @@ #!/bin/bash # Command line parameters: -# 1 - github organization name. For example ignitionrobotics or osrf. -# 2 - the name of the ignition repository. For example ign-math. -# 3 - the name of the branch. For example ign-math6 +# 1 - github organization name. For example gazebosim or osrf. +# 2 - the name of the ignition repository. For example gz-math. +# 3 - the name of the branch. For example gz-math7 set -o errexit set -o verbose # todo(nkoenig) Update the database to handle templated names. # todo(nkoenig) Use application tokens instead of jwt, which can expire. -curl -k -X POST -d @$1 https://api.ignitionrobotics.org/1.0/benchmarks/gazebo --header 'authorization: Bearer '$AUTH0_JWT_TOKEN +curl -k -X POST -d @$1 https://api.gazebosim.org/1.0/benchmarks/gazebo --header 'authorization: Bearer '$AUTH0_JWT_TOKEN diff --git a/examples/standalone/joy_to_twist/README.md b/examples/standalone/joy_to_twist/README.md index 893bdeed1d..1dbc40f6a4 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 -[ignition::msgs::Joy](https://ignitionrobotics.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) +[ignition::msgs::Joy](https://gazebosim.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) messages and converts publishes -[ignition::msgs::Twist](https://ignitionrobotics.org/api/msgs/5.6/classignition_1_1msgs_1_1Twist.html) +[ignition::msgs::Twist](https://gazebosim.org/api/msgs/5.6/classignition_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 9e05e2e172..9292b6bd9e 100644 --- a/examples/standalone/joystick/README.md +++ b/examples/standalone/joystick/README.md @@ -1,7 +1,7 @@ # Joystick Standalone program that publishes -[ignition::msgs::Joy](https://ignitionrobotics.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) +[ignition::msgs::Joy](https://gazebosim.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) messages from a joystick device using Ignition 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 fc6af99daa..5c50c7b501 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 diff --git a/examples/worlds/actors_population.sdf.erb b/examples/worlds/actors_population.sdf.erb index c885588bde..620677263d 100644 --- a/examples/worlds/actors_population.sdf.erb +++ b/examples/worlds/actors_population.sdf.erb @@ -84,11 +84,11 @@ - 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 diff --git a/examples/worlds/breadcrumbs.sdf b/examples/worlds/breadcrumbs.sdf index b3ade84636..79cccff819 100644 --- a/examples/worlds/breadcrumbs.sdf +++ b/examples/worlds/breadcrumbs.sdf @@ -404,7 +404,7 @@ -2 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/X2 Config 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/X2 Config 1 diff --git a/examples/worlds/camera_sensor.sdf b/examples/worlds/camera_sensor.sdf index 8e8c090728..443321eebc 100644 --- a/examples/worlds/camera_sensor.sdf +++ b/examples/worlds/camera_sensor.sdf @@ -307,7 +307,7 @@ 0 1 3 0.0 0.0 1.57 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Cone + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Construction Cone diff --git a/examples/worlds/depth_camera_sensor.sdf b/examples/worlds/depth_camera_sensor.sdf index 80ce0abf93..2c0560063e 100644 --- a/examples/worlds/depth_camera_sensor.sdf +++ b/examples/worlds/depth_camera_sensor.sdf @@ -216,7 +216,7 @@ 0 1 3 0.0 0.0 1.57 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Barrel + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Construction Barrel diff --git a/examples/worlds/elevator.sdf b/examples/worlds/elevator.sdf index d2b1238e6b..77d01899cb 100644 --- a/examples/worlds/elevator.sdf +++ b/examples/worlds/elevator.sdf @@ -73,7 +73,7 @@ - https://fuel.ignitionrobotics.org/1.0/nlamprian/models/Elevator + https://fuel.gazebosim.org/1.0/nlamprian/models/Elevator diff --git a/examples/worlds/fuel.sdf b/examples/worlds/fuel.sdf index 4d50302e1a..69e856b847 100644 --- a/examples/worlds/fuel.sdf +++ b/examples/worlds/fuel.sdf @@ -1,6 +1,6 @@ @@ -62,27 +62,27 @@ Double pendulum -3 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Double pendulum with base + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Double pendulum with base 3 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack Gazebo (relative paths) 2 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Gazebo - relative paths + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Gazebo - relative paths Actor Test 0 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/actor - relative paths + https://fuel.gazebosim.org/1.0/OpenRobotics/models/actor - relative paths @@ -93,14 +93,14 @@ - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Radio/4/files/meshes/Radio.dae + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Radio/4/files/meshes/Radio.dae - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Radio/4/files/meshes/Radio.dae + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Radio/4/files/meshes/Radio.dae diff --git a/examples/worlds/fuel_textured_mesh.sdf b/examples/worlds/fuel_textured_mesh.sdf index 2f42cf7608..b4955a4e52 100644 --- a/examples/worlds/fuel_textured_mesh.sdf +++ b/examples/worlds/fuel_textured_mesh.sdf @@ -202,7 +202,7 @@ true Rescue Randy 0 0 0 0 0 1.57 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Rescue Randy + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Rescue Randy @@ -210,7 +210,7 @@ true Tube Light 1.5 0 3 0 0.78 0 - https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Tube Light + https://fuel.gazebosim.org/1.0/openrobotics/models/Tube Light diff --git a/examples/worlds/gpu_lidar_sensor.sdf b/examples/worlds/gpu_lidar_sensor.sdf index 07020dda9b..c8efaaefda 100644 --- a/examples/worlds/gpu_lidar_sensor.sdf +++ b/examples/worlds/gpu_lidar_sensor.sdf @@ -169,7 +169,7 @@ 0 0 0 0 0 1.57 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Playground + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Playground diff --git a/examples/worlds/import_mesh.sdf b/examples/worlds/import_mesh.sdf index 685bace5d0..720f830789 100644 --- a/examples/worlds/import_mesh.sdf +++ b/examples/worlds/import_mesh.sdf @@ -75,7 +75,7 @@ true Electrical Box 0 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Electrical Box + https://fuel.gazebosim.org/1.0/openrobotics/models/Electrical Box diff --git a/examples/worlds/log_record_resources.sdf b/examples/worlds/log_record_resources.sdf index 222181127e..cd1d3f73aa 100644 --- a/examples/worlds/log_record_resources.sdf +++ b/examples/worlds/log_record_resources.sdf @@ -55,7 +55,7 @@ false staging_area 0 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/X2 Config 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/X2 Config 1 diff --git a/examples/worlds/multicopter_velocity_control.sdf b/examples/worlds/multicopter_velocity_control.sdf index 33d45db9d0..a238cce704 100644 --- a/examples/worlds/multicopter_velocity_control.sdf +++ b/examples/worlds/multicopter_velocity_control.sdf @@ -102,7 +102,7 @@ You can use the velocity controller and command linear velocity and yaw angular - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/X3 UAV/4 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/X3 UAV/4 0 3 1 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/X4 UAV Config 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/X4 UAV Config 1 Double_pendulum - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Double pendulum with base + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Double pendulum with base diff --git a/examples/worlds/quadcopter.sdf b/examples/worlds/quadcopter.sdf index 224a11cda9..89a507d1ff 100644 --- a/examples/worlds/quadcopter.sdf +++ b/examples/worlds/quadcopter.sdf @@ -78,7 +78,7 @@ - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/X3 UAV/4 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/X3 UAV/4 0 1 3 0.0 0.0 1.57 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Cone + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Construction Cone diff --git a/examples/worlds/tracked_vehicle_simple.sdf b/examples/worlds/tracked_vehicle_simple.sdf index cf9cd29acc..fbc77a7d0d 100644 --- a/examples/worlds/tracked_vehicle_simple.sdf +++ b/examples/worlds/tracked_vehicle_simple.sdf @@ -1719,7 +1719,7 @@ pallet 2 -2 0.1 0 0 0 - https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Euro pallet + https://fuel.gazebosim.org/1.0/openrobotics/models/Euro pallet diff --git a/examples/worlds/tunnel.sdf b/examples/worlds/tunnel.sdf index 583b313641..ffd0b99437 100644 --- a/examples/worlds/tunnel.sdf +++ b/examples/worlds/tunnel.sdf @@ -1,11 +1,6 @@ @@ -216,7 +211,7 @@ true staging_area 0 0 -0.005 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/subt_tunnel_staging_area + https://fuel.gazebosim.org/1.0/OpenRobotics/models/subt_tunnel_staging_area @@ -248,168 +243,168 @@ tile_0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 240.000000 240.000000 -15.000000 0 0 0.000000 tile_1 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 260.000000 240.000000 -15.000000 0 0 1.570796 tile_2 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Constrained Tunnel Tile Tall + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Constrained Tunnel Tile Tall 280.000000 240.000000 -15.000000 0 0 1.570796 tile_3 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 300.000000 240.000000 -15.000000 0 0 4.712389 tile_4 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 160.000000 211.000000 -15.000000 0 0 0.000000 tile_5 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 240.000000 220.000000 -15.000000 0 0 0.000000 radio_1 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Radio + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Radio 241.500000 220.000000 -15.000000 0 0 0.000000 tile_6 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 300.000000 220.000000 -15.000000 0 0 0.000000 tile_7 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 69.000000 200.000000 -15.000000 0 0 0.000000 tile_8 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 80.000000 200.000000 -15.000000 0 0 1.570796 tile_9 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 100.000000 200.000000 -15.000000 0 0 1.570796 tile_10 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 120.000000 200.000000 -15.000000 0 0 1.570796 tile_11 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 140.000000 200.000000 -15.000000 0 0 1.570796 tile_12 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 1 160.000000 200.000000 -15.000000 0 0 0.000000 tile_13 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 180.000000 200.000000 -15.000000 0 0 1.570796 tile_14 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 200.000000 200.000000 -15.000000 0 0 1.570796 tile_15 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 220.000000 200.000000 -15.000000 0 0 1.570796 tile_16 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 240.000000 200.000000 -15.000000 0 0 3.141593 tile_17 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 300.000000 200.000000 -15.000000 0 0 0.000000 tile_18 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 160.000000 180.000000 -15.000000 0 0 0.000000 backpack_1 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack 219.000000 202.000000 -15.000000 0 0 0.000000 tile_19 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 260.000000 180.000000 -15.000000 0 0 0.000000 tile_20 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 180.000000 -15.000000 0 0 1.570796 tile_21 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 1 300.000000 180.000000 -15.000000 0 0 0.000000 tile_22 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 320.000000 180.000000 -15.000000 0 0 1.570796 tile_23 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 340.000000 180.000000 -15.000000 0 0 4.712389 tile_24 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Constrained Tunnel Tile Tall + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Constrained Tunnel Tile Tall 160.000000 160.000000 -15.000000 0 0 0.000000 @@ -417,509 +412,509 @@ phone_1 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Phone + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Phone 260.000000 160.000000 -14.996000 -1.570796 0 0.000000 tile_25 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 260.000000 160.000000 -15.000000 0 0 0.000000 tile_26 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 300.000000 169.000000 -15.000000 0 0 0.000000 tile_27 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 340.000000 160.000000 -15.000000 0 0 0.000000 toolbox_1 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Toolbox + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Toolbox 342.000000 160.000000 -15.000000 0 0 0.000000 tile_28 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 60.000000 131.000000 -15.000000 0 0 0.000000 tile_29 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 80.000000 131.000000 -15.000000 0 0 0.000000 tile_30 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 160.000000 140.000000 -15.000000 0 0 0.000000 extinguisher_1 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Extinguisher + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Extinguisher 158.000000 140.000000 -15.000000 0 0 0.000000 tile_31 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 260.000000 149.000000 -15.000000 0 0 0.000000 tile_32 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 340.000000 149.000000 -15.000000 0 0 0.000000 tile_33 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 60.000000 120.000000 -15.000000 0 0 1.570796 tile_34 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 1 80.000000 120.000000 -15.000000 0 0 0.000000 tile_35 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 100.000000 120.000000 -15.000000 0 0 1.570796 tile_36 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 120.000000 120.000000 -15.000000 0 0 1.570796 tile_37 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 140.000000 120.000000 -15.000000 0 0 1.570796 tile_38 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 160.000000 120.000000 -15.000000 0 0 3.141593 tile_39 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 80.000000 100.000000 -15.000000 0 0 0.000000 tile_40 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 200.000000 100.000000 -15.000000 0 0 0.000000 tile_41 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 220.000000 100.000000 -15.000000 0 0 1.570796 tile_42 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 240.000000 100.000000 -15.000000 0 0 1.570796 tile_43 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 260.000000 100.000000 -15.000000 0 0 4.712389 radio_2 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Radio + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Radio 260.000000 82.300000 -15.000000 0 0 0.000000 tile_44 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 80.000000 80.000000 -15.000000 0 0 0.000000 tile_45 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 200.000000 80.000000 -15.000000 0 0 0.000000 tile_46 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 260.000000 80.000000 -15.000000 0 0 1.570796 tile_47 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 280.000000 80.000000 -15.000000 0 0 4.712389 tile_48 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 6 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 6 80.000000 60.000000 -15.000000 0 0 3.141593 tile_49 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 200.000000 60.000000 -15.000000 0 0 0.000000 tile_50 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 60.000000 -15.000000 0 0 0.000000 toolbox_2 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Toolbox + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Toolbox 278.000000 60.000000 -15.000000 0 0 0.000000 tile_51 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 80.000000 40.000000 -10.000000 0 0 0.000000 tile_52 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 200.000000 40.000000 -15.000000 0 0 0.000000 tile_53 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 40.000000 -15.000000 0 0 0.000000 tile_54 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 80.000000 20.000000 -10.000000 0 0 0.000000 tile_55 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 200.000000 20.000000 -15.000000 0 0 0.000000 phone_2 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Phone + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Phone 201.800000 20.000000 -14.996000 -1.570796 0 0.000000 tile_56 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 20.000000 -15.000000 0 0 0.000000 tile_57 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 320.000000 20.000000 -20.000000 0 0 0.000000 tile_58 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 340.000000 20.000000 -20.000000 0 0 1.570796 tile_59 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 360.000000 20.000000 -20.000000 0 0 4.712389 electrical_box_1 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Electrical Box + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Electrical Box 400.000000 -1.000000 -20.000000 0 0 0.000000 tile_60 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 20.000000 0.000000 0.000000 0 0 1.570796 tile_61 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 6 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 6 40.000000 0.000000 -5.000000 0 0 1.570796 tile_62 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 6 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 6 60.000000 0.000000 -10.000000 0 0 1.570796 tile_63 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 1 80.000000 0.000000 -10.000000 0 0 0.000000 tile_64 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 100.000000 0.000000 -10.000000 0 0 1.570796 tile_65 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 120.000000 0.000000 -10.000000 0 0 1.570796 tile_66 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 140.000000 0.000000 -10.000000 0 0 1.570796 tile_67 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 6 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 6 160.000000 0.000000 -15.000000 0 0 1.570796 tile_68 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 180.000000 0.000000 -15.000000 0 0 1.570796 tile_69 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 1 200.000000 0.000000 -15.000000 0 0 0.000000 tile_70 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 211.000000 0.000000 -15.000000 0 0 0.000000 tile_71 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 269.000000 0.000000 -15.000000 0 0 0.000000 tile_72 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 1 280.000000 0.000000 -15.000000 0 0 0.000000 tile_73 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 6 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 6 300.000000 0.000000 -20.000000 0 0 1.570796 tile_74 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 1 320.000000 0.000000 -20.000000 0 0 0.000000 tile_75 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 340.000000 0.000000 -20.000000 0 0 1.570796 tile_76 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 1 360.000000 0.000000 -20.000000 0 0 0.000000 tile_77 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 380.000000 0.000000 -20.000000 0 0 1.570796 tile_78 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 400.000000 0.000000 -20.000000 0 0 1.570796 tile_79 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 411.000000 0.000000 -20.000000 0 0 0.000000 tile_80 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 7 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 7 80.000000 -20.000000 -10.000000 0 0 3.141593 tile_81 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 200.000000 -20.000000 -15.000000 0 0 0.000000 tile_82 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 -20.000000 -15.000000 0 0 0.000000 tile_83 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 320.000000 -20.000000 -20.000000 0 0 1.570796 tile_84 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 340.000000 -20.000000 -20.000000 0 0 1.570796 tile_85 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 360.000000 -20.000000 -20.000000 0 0 3.141593 tile_86 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 80.000000 -40.000000 -5.000000 0 0 0.000000 tile_87 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 200.000000 -40.000000 -15.000000 0 0 0.000000 tile_88 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 -40.000000 -15.000000 0 0 0.000000 backpack_2 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack 340.000000 -22.000000 -20.000000 0 0 0.000000 tile_89 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 80.000000 -60.000000 -5.000000 0 0 0.000000 tile_90 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 200.000000 -60.000000 -15.000000 0 0 1.570796 tile_91 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 220.000000 -60.000000 -15.000000 0 0 1.570796 tile_92 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 240.000000 -60.000000 -15.000000 0 0 1.570796 tile_93 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 260.000000 -60.000000 -15.000000 0 0 1.570796 tile_94 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 280.000000 -60.000000 -15.000000 0 0 3.141593 tile_95 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 80.000000 -80.000000 -5.000000 0 0 1.570796 tile_96 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 7 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 7 100.000000 -80.000000 -10.000000 0 0 1.570796 tile_97 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 120.000000 -80.000000 -10.000000 0 0 4.712389 phone_3 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Phone + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Phone 120.800000 -98.400000 -9.996000 1.570796 0 0.000000 @@ -927,174 +922,174 @@ valve_1 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Valve + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Valve 240.000000 -58.000000 -15.000000 0 0 0.000000 tile_98 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 120.000000 -100.000000 -10.000000 0 0 1.570796 tile_99 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 140.000000 -100.000000 -10.000000 0 0 4.712389 tile_100 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 140.000000 -120.000000 -10.000000 0 0 0.000000 valve_2 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Valve + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Valve 141.750000 -119.000000 -10.000000 0 0 0.000000 tile_101 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 140.000000 -140.000000 -10.000000 0 0 0.000000 tile_102 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Constrained Tunnel Tile Short + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Constrained Tunnel Tile Short 140.000000 -160.000000 -10.000000 0 0 0.000000 tile_103 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 280.000000 -169.000000 -10.000000 0 0 0.000000 electrical_box_2 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Electrical Box + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Electrical Box 138.000000 -180.000000 -10.000000 0 0 0.000000 tile_104 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 140.000000 -180.000000 -10.000000 0 0 0.000000 backpack_3 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack 180.000000 -198.000000 -10.000000 0 0 0.000000 tile_105 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 -180.000000 -10.000000 0 0 0.000000 tile_106 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 140.000000 -200.000000 -10.000000 0 0 0.000000 tile_107 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 160.000000 -200.000000 -10.000000 0 0 0.000000 tile_108 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 180.000000 -200.000000 -10.000000 0 0 1.570796 tile_109 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 200.000000 -200.000000 -10.000000 0 0 1.570796 tile_110 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 220.000000 -200.000000 -10.000000 0 0 4.712389 tile_111 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 -200.000000 -10.000000 0 0 0.000000 tile_112 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 140.000000 -220.000000 -10.000000 0 0 1.570796 tile_113 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 160.000000 -220.000000 -10.000000 0 0 3.141593 tile_114 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 220.000000 -220.000000 -10.000000 0 0 0.000000 tile_115 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 -220.000000 -10.000000 0 0 0.000000 extinguisher_2 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Extinguisher + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Extinguisher 278.000000 -220.000000 -10.000000 0 0 0.000000 tile_116 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 220.000000 -240.000000 -10.000000 0 0 1.570796 tile_117 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 240.000000 -240.000000 -10.000000 0 0 1.570796 tile_118 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 260.000000 -240.000000 -10.000000 0 0 1.570796 tile_119 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 280.000000 -240.000000 -10.000000 0 0 3.141593 diff --git a/include/ignition/gazebo/Entity.hh b/include/ignition/gazebo/Entity.hh index 4ac16e82de..0db6365417 100644 --- a/include/ignition/gazebo/Entity.hh +++ b/include/ignition/gazebo/Entity.hh @@ -21,8 +21,7 @@ #include #include -/// \brief This library is part of the [Ignition -/// Robotics](https://ignitionrobotics.org) project. +/// \brief This library is part of the [Gazebo](https://gazebosim.org) project. namespace ignition { /// \brief Gazebo is a leading open source robotics simulator, that diff --git a/include/ignition/gazebo/ServerConfig.hh b/include/ignition/gazebo/ServerConfig.hh index ff4941b41d..7116029009 100644 --- a/include/ignition/gazebo/ServerConfig.hh +++ b/include/ignition/gazebo/ServerConfig.hh @@ -374,14 +374,14 @@ namespace ignition UpdatePeriod() const; /// \brief Path to where simulation resources, such as models downloaded - /// from fuel.ignitionrobotics.org, should be stored. + /// from fuel.gazebosim.org, should be stored. /// \return Path to a location on disk. An empty string indicates that /// the default value will be used, which is currently /// ~/.ignition/fuel. public: const std::string &ResourceCache() const; /// \brief Set the path to where simulation resources, such as models - /// downloaded from fuel.ignitionrobotics.org, should be stored. + /// downloaded from fuel.gazebosim.org, should be stored. /// \param[in] _path Path to a location on disk. An empty string /// indicates that the default value will be used, which is currently /// ~/.ignition/fuel. diff --git a/src/Component_TEST.cc b/src/Component_TEST.cc index 7e6864710d..6d7a664a7f 100644 --- a/src/Component_TEST.cc +++ b/src/Component_TEST.cc @@ -332,7 +332,7 @@ TEST_F(ComponentTest, OStream) EXPECT_EQ("Mass: 0", ostr.str()); } - // Component with a ignition::msgs type that gets serialized by the default + // Component with a msgs type that gets serialized by the default // serializer { using Custom = components::ComponentMassMatrix().Mass()); } - // Component with a ignition::msgs type that gets deserialized by the message + // Component with a msgs type that gets deserialized by the message // deserializer { using Custom = components::Component IGNITION_GAZEBO_VISIBLE -msgs::Entity_Type ignition::gazebo::convert(const std::string &_in) +msgs::Entity_Type gazebo::convert(const std::string &_in) { msgs::Entity_Type out = msgs::Entity_Type_NONE; @@ -117,7 +117,7 @@ msgs::Entity_Type ignition::gazebo::convert(const std::string &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -math::Pose3d ignition::gazebo::convert(const msgs::Pose &_in) +math::Pose3d gazebo::convert(const msgs::Pose &_in) { math::Pose3d out(_in.position().x(), _in.position().y(), @@ -134,7 +134,7 @@ math::Pose3d ignition::gazebo::convert(const msgs::Pose &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Collision ignition::gazebo::convert(const sdf::Collision &_in) +msgs::Collision gazebo::convert(const sdf::Collision &_in) { msgs::Collision out; out.set_name(_in.Name()); @@ -147,7 +147,7 @@ msgs::Collision ignition::gazebo::convert(const sdf::Collision &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Collision ignition::gazebo::convert(const msgs::Collision &_in) +sdf::Collision gazebo::convert(const msgs::Collision &_in) { sdf::Collision out; out.SetName(_in.name()); @@ -159,7 +159,7 @@ sdf::Collision ignition::gazebo::convert(const msgs::Collision &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Geometry ignition::gazebo::convert(const sdf::Geometry &_in) +msgs::Geometry gazebo::convert(const sdf::Geometry &_in) { msgs::Geometry out; if (_in.Type() == sdf::GeometryType::BOX && _in.BoxShape()) @@ -268,7 +268,7 @@ msgs::Geometry ignition::gazebo::convert(const sdf::Geometry &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Geometry ignition::gazebo::convert(const msgs::Geometry &_in) +sdf::Geometry gazebo::convert(const msgs::Geometry &_in) { sdf::Geometry out; if (_in.type() == msgs::Geometry::BOX && _in.has_box()) @@ -405,7 +405,7 @@ sdf::Geometry ignition::gazebo::convert(const msgs::Geometry &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Material ignition::gazebo::convert(const sdf::Material &_in) +msgs::Material gazebo::convert(const sdf::Material &_in) { msgs::Material out; msgs::Set(out.mutable_ambient(), _in.Ambient()); @@ -464,7 +464,7 @@ msgs::Material ignition::gazebo::convert(const sdf::Material &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Material ignition::gazebo::convert(const msgs::Material &_in) +sdf::Material gazebo::convert(const msgs::Material &_in) { sdf::Material out; out.SetAmbient(msgs::Convert(_in.ambient())); @@ -507,7 +507,7 @@ sdf::Material ignition::gazebo::convert(const msgs::Material &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Actor ignition::gazebo::convert(const sdf::Actor &_in) +msgs::Actor gazebo::convert(const sdf::Actor &_in) { msgs::Actor out; out.mutable_entity()->set_name(_in.Name()); @@ -547,7 +547,7 @@ msgs::Actor ignition::gazebo::convert(const sdf::Actor &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Actor ignition::gazebo::convert(const msgs::Actor &_in) +sdf::Actor gazebo::convert(const msgs::Actor &_in) { sdf::Actor out; out.SetName(_in.entity().name()); @@ -590,7 +590,7 @@ sdf::Actor ignition::gazebo::convert(const msgs::Actor &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Light ignition::gazebo::convert(const sdf::Light &_in) +msgs::Light gazebo::convert(const sdf::Light &_in) { msgs::Light out; out.set_name(_in.Name()); @@ -638,7 +638,7 @@ msgs::Light ignition::gazebo::convert(const sdf::Light &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Light ignition::gazebo::convert(const msgs::Light &_in) +sdf::Light gazebo::convert(const msgs::Light &_in) { sdf::Light out; out.SetName(_in.name()); @@ -704,7 +704,7 @@ sdf::Light ignition::gazebo::convert(const msgs::Light &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::GUI ignition::gazebo::convert(const sdf::Gui &_in) +msgs::GUI gazebo::convert(const sdf::Gui &_in) { msgs::GUI out; @@ -728,12 +728,12 @@ msgs::GUI ignition::gazebo::convert(const sdf::Gui &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Time ignition::gazebo::convert( +msgs::Time gazebo::convert( const std::chrono::steady_clock::duration &_in) { msgs::Time out; - auto secNsec = ignition::math::durationToSecNsec(_in); + auto secNsec = math::durationToSecNsec(_in); out.set_sec(secNsec.first); out.set_nsec(secNsec.second); @@ -744,7 +744,7 @@ msgs::Time ignition::gazebo::convert( ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -std::chrono::steady_clock::duration ignition::gazebo::convert( +std::chrono::steady_clock::duration gazebo::convert( const msgs::Time &_in) { return std::chrono::seconds(_in.sec()) + std::chrono::nanoseconds(_in.nsec()); @@ -753,7 +753,7 @@ std::chrono::steady_clock::duration ignition::gazebo::convert( ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Inertial ignition::gazebo::convert(const math::Inertiald &_in) +msgs::Inertial gazebo::convert(const math::Inertiald &_in) { msgs::Inertial out; msgs::Set(out.mutable_pose(), _in.Pose()); @@ -770,7 +770,7 @@ msgs::Inertial ignition::gazebo::convert(const math::Inertiald &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -math::Inertiald ignition::gazebo::convert(const msgs::Inertial &_in) +math::Inertiald gazebo::convert(const msgs::Inertial &_in) { math::MassMatrix3d massMatrix; massMatrix.SetMass(_in.mass()); @@ -790,7 +790,7 @@ math::Inertiald ignition::gazebo::convert(const msgs::Inertial &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Axis ignition::gazebo::convert(const sdf::JointAxis &_in) +msgs::Axis gazebo::convert(const sdf::JointAxis &_in) { msgs::Axis out; msgs::Set(out.mutable_xyz(), _in.Xyz()); @@ -820,7 +820,7 @@ msgs::Axis ignition::gazebo::convert(const sdf::JointAxis &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::JointAxis ignition::gazebo::convert(const msgs::Axis &_in) +sdf::JointAxis gazebo::convert(const msgs::Axis &_in) { sdf::JointAxis out; sdf::Errors errors = out.SetXyz(msgs::Convert(_in.xyz())); @@ -840,7 +840,7 @@ sdf::JointAxis ignition::gazebo::convert(const msgs::Axis &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Scene ignition::gazebo::convert(const sdf::Scene &_in) +msgs::Scene gazebo::convert(const sdf::Scene &_in) { msgs::Scene out; // todo(anyone) add Name to sdf::Scene? @@ -878,7 +878,7 @@ msgs::Scene ignition::gazebo::convert(const sdf::Scene &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Scene ignition::gazebo::convert(const msgs::Scene &_in) +sdf::Scene gazebo::convert(const msgs::Scene &_in) { sdf::Scene out; // todo(anyone) add SetName to sdf::Scene? @@ -918,7 +918,7 @@ sdf::Scene ignition::gazebo::convert(const msgs::Scene &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Atmosphere ignition::gazebo::convert(const sdf::Atmosphere &_in) +msgs::Atmosphere gazebo::convert(const sdf::Atmosphere &_in) { msgs::Atmosphere out; out.set_temperature(_in.Temperature().Kelvin()); @@ -936,7 +936,7 @@ msgs::Atmosphere ignition::gazebo::convert(const sdf::Atmosphere &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Atmosphere ignition::gazebo::convert(const msgs::Atmosphere &_in) +sdf::Atmosphere gazebo::convert(const msgs::Atmosphere &_in) { sdf::Atmosphere out; out.SetTemperature(math::Temperature(_in.temperature())); @@ -952,16 +952,16 @@ sdf::Atmosphere ignition::gazebo::convert(const msgs::Atmosphere &_in) } ////////////////////////////////////////////////// -void ignition::gazebo::set(msgs::Time *_msg, +void gazebo::set(msgs::Time *_msg, const std::chrono::steady_clock::duration &_in) { - auto secNsec = ignition::math::durationToSecNsec(_in); + auto secNsec = math::durationToSecNsec(_in); _msg->set_sec(secNsec.first); _msg->set_nsec(secNsec.second); } ////////////////////////////////////////////////// -void ignition::gazebo::set(msgs::WorldStatistics *_msg, +void gazebo::set(msgs::WorldStatistics *_msg, const gazebo::UpdateInfo &_in) { set(_msg->mutable_sim_time(), _in.simTime); @@ -974,7 +974,7 @@ void ignition::gazebo::set(msgs::WorldStatistics *_msg, ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Physics ignition::gazebo::convert(const sdf::Physics &_in) +msgs::Physics gazebo::convert(const sdf::Physics &_in) { msgs::Physics out; out.set_max_step_size(_in.MaxStepSize()); @@ -985,7 +985,7 @@ msgs::Physics ignition::gazebo::convert(const sdf::Physics &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Physics ignition::gazebo::convert(const msgs::Physics &_in) +sdf::Physics gazebo::convert(const msgs::Physics &_in) { sdf::Physics out; out.SetRealTimeFactor(_in.real_time_factor()); @@ -994,7 +994,7 @@ sdf::Physics ignition::gazebo::convert(const msgs::Physics &_in) } ////////////////////////////////////////////////// -void ignition::gazebo::set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf) +void gazebo::set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf) { switch (_sdf.Type()) { @@ -1061,7 +1061,7 @@ sdf::LightType ignition::gazebo::convert(const std::string &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Noise ignition::gazebo::convert(const msgs::SensorNoise &_in) +sdf::Noise gazebo::convert(const msgs::SensorNoise &_in) { sdf::Noise out; @@ -1094,7 +1094,7 @@ sdf::Noise ignition::gazebo::convert(const msgs::SensorNoise &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) +msgs::Sensor gazebo::convert(const sdf::Sensor &_in) { msgs::Sensor out; out.set_name(_in.Name()); @@ -1110,17 +1110,17 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) msgs::MagnetometerSensor *sensor = out.mutable_magnetometer(); if (_in.MagnetometerSensor()->XNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_x_noise(), + gazebo::set(sensor->mutable_x_noise(), _in.MagnetometerSensor()->XNoise()); } if (_in.MagnetometerSensor()->YNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_y_noise(), + gazebo::set(sensor->mutable_y_noise(), _in.MagnetometerSensor()->YNoise()); } if (_in.MagnetometerSensor()->ZNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_z_noise(), + gazebo::set(sensor->mutable_z_noise(), _in.MagnetometerSensor()->ZNoise()); } } @@ -1208,13 +1208,13 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) if (_in.AltimeterSensor()->VerticalPositionNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_vertical_position_noise(), + gazebo::set(sensor->mutable_vertical_position_noise(), _in.AltimeterSensor()->VerticalPositionNoise()); } if (_in.AltimeterSensor()->VerticalVelocityNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_vertical_velocity_noise(), + gazebo::set(sensor->mutable_vertical_velocity_noise(), _in.AltimeterSensor()->VerticalVelocityNoise()); } } @@ -1233,7 +1233,7 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) if (_in.AirPressureSensor()->PressureNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_pressure_noise(), + gazebo::set(sensor->mutable_pressure_noise(), _in.AirPressureSensor()->PressureNoise()); } sensor->set_reference_altitude( @@ -1254,38 +1254,38 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) if (sdfImu->LinearAccelerationXNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gazebo::set( sensor->mutable_linear_acceleration()->mutable_x_noise(), sdfImu->LinearAccelerationXNoise()); } if (sdfImu->LinearAccelerationYNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gazebo::set( sensor->mutable_linear_acceleration()->mutable_y_noise(), sdfImu->LinearAccelerationYNoise()); } if (sdfImu->LinearAccelerationZNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gazebo::set( sensor->mutable_linear_acceleration()->mutable_z_noise(), sdfImu->LinearAccelerationZNoise()); } if (sdfImu->AngularVelocityXNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gazebo::set( sensor->mutable_angular_velocity()->mutable_x_noise(), sdfImu->AngularVelocityXNoise()); } if (sdfImu->AngularVelocityYNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gazebo::set( sensor->mutable_angular_velocity()->mutable_y_noise(), sdfImu->AngularVelocityYNoise()); } if (sdfImu->AngularVelocityZNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gazebo::set( sensor->mutable_angular_velocity()->mutable_z_noise(), sdfImu->AngularVelocityZNoise()); } @@ -1319,7 +1319,7 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) if (sdfLidar->LidarNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_noise(), sdfLidar->LidarNoise()); + gazebo::set(sensor->mutable_noise(), sdfLidar->LidarNoise()); } sensor->set_horizontal_samples(sdfLidar->HorizontalScanSamples()); sensor->set_horizontal_resolution(sdfLidar->HorizontalScanResolution()); @@ -1349,7 +1349,7 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) +sdf::Sensor gazebo::convert(const msgs::Sensor &_in) { sdf::Sensor out; out.SetName(_in.name()); @@ -1366,17 +1366,17 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) { if (_in.magnetometer().has_x_noise()) { - sensor.SetXNoise(ignition::gazebo::convert( + sensor.SetXNoise(gazebo::convert( _in.magnetometer().x_noise())); } if (_in.magnetometer().has_y_noise()) { - sensor.SetYNoise(ignition::gazebo::convert( + sensor.SetYNoise(gazebo::convert( _in.magnetometer().y_noise())); } if (_in.magnetometer().has_z_noise()) { - sensor.SetZNoise(ignition::gazebo::convert( + sensor.SetZNoise(gazebo::convert( _in.magnetometer().z_noise())); } } @@ -1431,13 +1431,13 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) { if (_in.altimeter().has_vertical_position_noise()) { - sensor.SetVerticalPositionNoise(ignition::gazebo::convert( + sensor.SetVerticalPositionNoise(gazebo::convert( _in.altimeter().vertical_position_noise())); } if (_in.altimeter().has_vertical_velocity_noise()) { - sensor.SetVerticalVelocityNoise(ignition::gazebo::convert( + sensor.SetVerticalVelocityNoise(gazebo::convert( _in.altimeter().vertical_velocity_noise())); } } @@ -1456,7 +1456,7 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) { if (_in.air_pressure().has_pressure_noise()) { - sensor.SetPressureNoise(ignition::gazebo::convert( + sensor.SetPressureNoise(gazebo::convert( _in.air_pressure().pressure_noise())); } @@ -1480,19 +1480,19 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) if (_in.imu().linear_acceleration().has_x_noise()) { sensor.SetLinearAccelerationXNoise( - ignition::gazebo::convert( + gazebo::convert( _in.imu().linear_acceleration().x_noise())); } if (_in.imu().linear_acceleration().has_y_noise()) { sensor.SetLinearAccelerationYNoise( - ignition::gazebo::convert( + gazebo::convert( _in.imu().linear_acceleration().y_noise())); } if (_in.imu().linear_acceleration().has_z_noise()) { sensor.SetLinearAccelerationZNoise( - ignition::gazebo::convert( + gazebo::convert( _in.imu().linear_acceleration().z_noise())); } } @@ -1502,19 +1502,19 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) if (_in.imu().angular_velocity().has_x_noise()) { sensor.SetAngularVelocityXNoise( - ignition::gazebo::convert( + gazebo::convert( _in.imu().angular_velocity().x_noise())); } if (_in.imu().angular_velocity().has_y_noise()) { sensor.SetAngularVelocityYNoise( - ignition::gazebo::convert( + gazebo::convert( _in.imu().angular_velocity().y_noise())); } if (_in.imu().angular_velocity().has_z_noise()) { sensor.SetAngularVelocityZNoise( - ignition::gazebo::convert( + gazebo::convert( _in.imu().angular_velocity().z_noise())); } } @@ -1571,7 +1571,7 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) if (_in.lidar().has_noise()) { - sensor.SetLidarNoise(ignition::gazebo::convert( + sensor.SetLidarNoise(gazebo::convert( _in.lidar().noise())); } } @@ -1589,7 +1589,7 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::WorldStatistics ignition::gazebo::convert(const gazebo::UpdateInfo &_in) +msgs::WorldStatistics gazebo::convert(const gazebo::UpdateInfo &_in) { msgs::WorldStatistics out; set(&out, _in); @@ -1599,7 +1599,7 @@ msgs::WorldStatistics ignition::gazebo::convert(const gazebo::UpdateInfo &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -gazebo::UpdateInfo ignition::gazebo::convert(const msgs::WorldStatistics &_in) +gazebo::UpdateInfo gazebo::convert(const msgs::WorldStatistics &_in) { gazebo::UpdateInfo out; out.iterations = _in.iterations(); @@ -1613,7 +1613,7 @@ gazebo::UpdateInfo ignition::gazebo::convert(const msgs::WorldStatistics &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::AxisAlignedBox ignition::gazebo::convert(const math::AxisAlignedBox &_in) +msgs::AxisAlignedBox gazebo::convert(const math::AxisAlignedBox &_in) { msgs::AxisAlignedBox out; msgs::Set(out.mutable_min_corner(), _in.Min()); @@ -1624,7 +1624,7 @@ msgs::AxisAlignedBox ignition::gazebo::convert(const math::AxisAlignedBox &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -math::AxisAlignedBox ignition::gazebo::convert(const msgs::AxisAlignedBox &_in) +math::AxisAlignedBox gazebo::convert(const msgs::AxisAlignedBox &_in) { math::AxisAlignedBox out; out.Min() = msgs::Convert(_in.min_corner()); diff --git a/src/Conversions_TEST.cc b/src/Conversions_TEST.cc index 9033949c9d..f1a3809381 100644 --- a/src/Conversions_TEST.cc +++ b/src/Conversions_TEST.cc @@ -57,8 +57,8 @@ TEST(Conversions, Light) light.SetRawPose({3, 2, 1, 0, IGN_PI, 0}); light.SetPoseRelativeTo("world"); light.SetCastShadows(true); - light.SetDiffuse(ignition::math::Color(0.4f, 0.5f, 0.6f, 1.0)); - light.SetSpecular(ignition::math::Color(0.8f, 0.9f, 0.1f, 1.0)); + light.SetDiffuse(math::Color(0.4f, 0.5f, 0.6f, 1.0)); + light.SetSpecular(math::Color(0.8f, 0.9f, 0.1f, 1.0)); light.SetAttenuationRange(3.2); light.SetConstantAttenuationFactor(0.5); light.SetLinearAttenuationFactor(0.1); @@ -241,10 +241,10 @@ TEST(Conversions, Time) TEST(Conversions, Material) { sdf::Material material; - material.SetDiffuse(ignition::math::Color(0.1f, 0.2f, 0.3f, 0.4f)); - material.SetSpecular(ignition::math::Color(0.5f, 0.6f, 0.7f, 0.8f)); - material.SetAmbient(ignition::math::Color(0.9f, 1.0f, 1.1f, 1.2f)); - material.SetEmissive(ignition::math::Color(1.3f, 1.4f, 1.5f, 1.6f)); + material.SetDiffuse(math::Color(0.1f, 0.2f, 0.3f, 0.4f)); + material.SetSpecular(math::Color(0.5f, 0.6f, 0.7f, 0.8f)); + material.SetAmbient(math::Color(0.9f, 1.0f, 1.1f, 1.2f)); + material.SetEmissive(math::Color(1.3f, 1.4f, 1.5f, 1.6f)); material.SetLighting(true); material.SetRenderOrder(2.5); material.SetDoubleSided(true); @@ -336,7 +336,7 @@ TEST(Conversions, GeometryBox) geometry.SetType(sdf::GeometryType::BOX); sdf::Box boxShape; - boxShape.SetSize(ignition::math::Vector3d(1, 2, 3)); + boxShape.SetSize(math::Vector3d(1, 2, 3)); geometry.SetBoxShape(boxShape); auto geometryMsg = convert(geometry); @@ -450,7 +450,7 @@ TEST(Conversions, GeometryMesh) geometry.SetType(sdf::GeometryType::MESH); sdf::Mesh meshShape; - meshShape.SetScale(ignition::math::Vector3d(1, 2, 3)); + meshShape.SetScale(math::Vector3d(1, 2, 3)); meshShape.SetUri("file://watermelon"); meshShape.SetSubmesh("grape"); meshShape.SetCenterSubmesh(true); @@ -481,8 +481,8 @@ TEST(Conversions, GeometryPlane) geometry.SetType(sdf::GeometryType::PLANE); sdf::Plane planeShape; - planeShape.SetSize(ignition::math::Vector2d(1, 2)); - planeShape.SetNormal(ignition::math::Vector3d::UnitY); + planeShape.SetSize(math::Vector2d(1, 2)); + planeShape.SetNormal(math::Vector3d::UnitY); geometry.SetPlaneShape(planeShape); auto geometryMsg = convert(geometry); @@ -676,8 +676,8 @@ TEST(Conversions, JointAxis) TEST(Conversions, Scene) { sdf::Scene scene; - scene.SetAmbient(ignition::math::Color(0.1f, 0.2f, 0.3f, 0.4f)); - scene.SetBackground(ignition::math::Color(0.5f, 0.6f, 0.7f, 0.8f)); + scene.SetAmbient(math::Color(0.1f, 0.2f, 0.3f, 0.4f)); + scene.SetBackground(math::Color(0.5f, 0.6f, 0.7f, 0.8f)); scene.SetShadows(true); scene.SetGrid(true); scene.SetOriginVisual(true); @@ -769,7 +769,7 @@ TEST(Conversions, MagnetometerSensor) sensor.SetType(sdf::SensorType::MAGNETOMETER); sensor.SetUpdateRate(12.4); sensor.SetTopic("my_topic"); - sensor.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0, 0, 0)); + sensor.SetRawPose(math::Pose3d(1, 2, 3, 0, 0, 0)); sdf::Noise noise; noise.SetType(sdf::NoiseType::GAUSSIAN); @@ -809,7 +809,7 @@ TEST(Conversions, AltimeterSensor) sensor.SetType(sdf::SensorType::ALTIMETER); sensor.SetUpdateRate(12.4); sensor.SetTopic("my_topic"); - sensor.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0, 0, 0)); + sensor.SetRawPose(math::Pose3d(1, 2, 3, 0, 0, 0)); sdf::Noise noise; noise.SetType(sdf::NoiseType::GAUSSIAN); diff --git a/src/EntityComponentManager.cc b/src/EntityComponentManager.cc index b5f0eb8310..1695e89e01 100644 --- a/src/EntityComponentManager.cc +++ b/src/EntityComponentManager.cc @@ -1515,9 +1515,9 @@ void EntityComponentManager::AddEntityToMessage(msgs::SerializedStateMap &_msg, } ////////////////////////////////////////////////// -ignition::msgs::SerializedState EntityComponentManager::ChangedState() const +msgs::SerializedState EntityComponentManager::ChangedState() const { - ignition::msgs::SerializedState stateMsg; + msgs::SerializedState stateMsg; // New entities for (const auto &entity : this->dataPtr->newlyCreatedEntities) @@ -1542,7 +1542,7 @@ ignition::msgs::SerializedState EntityComponentManager::ChangedState() const ////////////////////////////////////////////////// void EntityComponentManager::ChangedState( - ignition::msgs::SerializedStateMap &_state) const + msgs::SerializedStateMap &_state) const { // New entities for (const auto &entity : this->dataPtr->newlyCreatedEntities) @@ -1610,11 +1610,11 @@ void EntityComponentManagerPrivate::CalculateStateThreadLoad() } ////////////////////////////////////////////////// -ignition::msgs::SerializedState EntityComponentManager::State( +msgs::SerializedState EntityComponentManager::State( const std::unordered_set &_entities, const std::unordered_set &_types) const { - ignition::msgs::SerializedState stateMsg; + msgs::SerializedState stateMsg; for (const auto &it : this->dataPtr->componentTypeIndex) { auto entity = it.first; @@ -1680,7 +1680,7 @@ void EntityComponentManager::State( ////////////////////////////////////////////////// void EntityComponentManager::SetState( - const ignition::msgs::SerializedState &_stateMsg) + const msgs::SerializedState &_stateMsg) { IGN_PROFILE("EntityComponentManager::SetState Non-map"); // Create / remove / update entities @@ -1778,7 +1778,7 @@ void EntityComponentManager::SetState( ////////////////////////////////////////////////// void EntityComponentManager::SetState( - const ignition::msgs::SerializedStateMap &_stateMsg) + const msgs::SerializedStateMap &_stateMsg) { IGN_PROFILE("EntityComponentManager::SetState Map"); // Create / remove / update entities diff --git a/src/EntityComponentManager_TEST.cc b/src/EntityComponentManager_TEST.cc index ac8cb416ab..c627d5d3e4 100644 --- a/src/EntityComponentManager_TEST.cc +++ b/src/EntityComponentManager_TEST.cc @@ -52,27 +52,27 @@ using IntComponent = components::Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.IntComponent", IntComponent) -using UIntComponent = components::Component; +using UIntComponent = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.UIntComponent", UIntComponent) -using DoubleComponent = components::Component; +using DoubleComponent = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.DoubleComponent", DoubleComponent) using StringComponent = - components::Component; + Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.StringComponent", StringComponent) -using BoolComponent = components::Component; +using BoolComponent = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.BoolComponent", BoolComponent) -using Even = components::Component; +using Even = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Even", Even) -using Odd = components::Component; +using Odd = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Odd", Odd) struct Custom @@ -80,7 +80,7 @@ struct Custom int dummy{123}; }; -using CustomComponent = components::Component; +using CustomComponent = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.CustomComponent", CustomComponent) } @@ -394,19 +394,19 @@ TEST_P(EntityComponentManagerFixture, } { - const auto *value = manager.Component(ePose); + const auto *value = manager.Component(ePose); ASSERT_NE(nullptr, value); EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 0), value->Data()); - auto data = manager.ComponentData(ePose); + auto data = manager.ComponentData(ePose); EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 0), data); - EXPECT_TRUE(manager.SetComponentData(ePose, + EXPECT_TRUE(manager.SetComponentData(ePose, {4, 5, 6, 0, 0, 0})); - data = manager.ComponentData(ePose); + data = manager.ComponentData(ePose); EXPECT_EQ(math::Pose3d(4, 5, 6, 0, 0, 0), data); - EXPECT_FALSE(manager.SetComponentData(ePose, + EXPECT_FALSE(manager.SetComponentData(ePose, {4, 5, 6, 0, 0, 0})); } @@ -1533,11 +1533,11 @@ TEST_P(EntityComponentManagerFixture, EXPECT_TRUE(manager.SetParentEntity(e6, e2)); EXPECT_TRUE(manager.SetParentEntity(e7, e2)); - EXPECT_FALSE(manager.SetParentEntity(e1, gazebo::Entity(1000))); - EXPECT_FALSE(manager.SetParentEntity(gazebo::Entity(1000), e1)); + EXPECT_FALSE(manager.SetParentEntity(e1, Entity(1000))); + EXPECT_FALSE(manager.SetParentEntity(Entity(1000), e1)); // Check their parents - EXPECT_EQ(gazebo::kNullEntity, manager.ParentEntity(e1)); + EXPECT_EQ(kNullEntity, manager.ParentEntity(e1)); EXPECT_EQ(e1, manager.ParentEntity(e2)); EXPECT_EQ(e1, manager.ParentEntity(e3)); EXPECT_EQ(e2, manager.ParentEntity(e4)); @@ -1546,8 +1546,8 @@ TEST_P(EntityComponentManagerFixture, EXPECT_EQ(e2, manager.ParentEntity(e7)); // Detach from graph - EXPECT_TRUE(manager.SetParentEntity(e7, gazebo::kNullEntity)); - EXPECT_EQ(gazebo::kNullEntity, manager.ParentEntity(e7)); + EXPECT_TRUE(manager.SetParentEntity(e7, kNullEntity)); + EXPECT_EQ(kNullEntity, manager.ParentEntity(e7)); // Reparent EXPECT_TRUE(manager.SetParentEntity(e5, e3)); @@ -3082,11 +3082,11 @@ TEST_P(EntityComponentManagerFixture, // create an entity and component auto entity = originalECMStateMap.CreateEntity(); - originalECMStateMap.CreateComponent(entity, components::IntComponent(1)); + originalECMStateMap.CreateComponent(entity, IntComponent(1)); int foundEntities = 0; - otherECMStateMap.Each( - [&](const Entity &, const components::IntComponent *) + otherECMStateMap.Each( + [&](const Entity &, const IntComponent *) { foundEntities++; return true; @@ -3098,8 +3098,8 @@ TEST_P(EntityComponentManagerFixture, originalECMStateMap.State(stateMapMsg); otherECMStateMap.SetState(stateMapMsg); foundEntities = 0; - otherECMStateMap.Each( - [&](const Entity &, const components::IntComponent *_intComp) + otherECMStateMap.Each( + [&](const Entity &, const IntComponent *_intComp) { foundEntities++; EXPECT_EQ(1, _intComp->Data()); @@ -3109,12 +3109,12 @@ TEST_P(EntityComponentManagerFixture, // modify a component and then share the update with the other ECM stateMapMsg.Clear(); - originalECMStateMap.SetComponentData(entity, 2); + originalECMStateMap.SetComponentData(entity, 2); originalECMStateMap.State(stateMapMsg); otherECMStateMap.SetState(stateMapMsg); foundEntities = 0; - otherECMStateMap.Each( - [&](const Entity &, const components::IntComponent *_intComp) + otherECMStateMap.Each( + [&](const Entity &, const IntComponent *_intComp) { foundEntities++; EXPECT_EQ(2, _intComp->Data()); @@ -3128,8 +3128,8 @@ TEST_P(EntityComponentManagerFixture, EntityComponentManager otherECMState; foundEntities = 0; - otherECMState.Each( - [&](const Entity &, const components::IntComponent *) + otherECMState.Each( + [&](const Entity &, const IntComponent *) { foundEntities++; return true; @@ -3137,13 +3137,13 @@ TEST_P(EntityComponentManagerFixture, EXPECT_EQ(0, foundEntities); entity = originalECMState.CreateEntity(); - originalECMState.CreateComponent(entity, components::IntComponent(1)); + originalECMState.CreateComponent(entity, IntComponent(1)); auto stateMsg = originalECMState.State(); otherECMState.SetState(stateMsg); foundEntities = 0; - otherECMState.Each( - [&](const Entity &, const components::IntComponent *_intComp) + otherECMState.Each( + [&](const Entity &, const IntComponent *_intComp) { foundEntities++; EXPECT_EQ(1, _intComp->Data()); @@ -3152,12 +3152,12 @@ TEST_P(EntityComponentManagerFixture, EXPECT_EQ(1, foundEntities); stateMsg.Clear(); - originalECMState.SetComponentData(entity, 2); + originalECMState.SetComponentData(entity, 2); stateMsg = originalECMState.State(); otherECMState.SetState(stateMsg); foundEntities = 0; - otherECMState.Each( - [&](const Entity &, const components::IntComponent *_intComp) + otherECMState.Each( + [&](const Entity &, const IntComponent *_intComp) { foundEntities++; EXPECT_EQ(2, _intComp->Data()); diff --git a/src/SdfEntityCreator_TEST.cc b/src/SdfEntityCreator_TEST.cc index 12554dbf7e..6c9c6247e7 100644 --- a/src/SdfEntityCreator_TEST.cc +++ b/src/SdfEntityCreator_TEST.cc @@ -59,7 +59,7 @@ using namespace ignition; using namespace gazebo; ///////////////////////////////////////////////// -class EntityCompMgrTest : public gazebo::EntityComponentManager +class EntityCompMgrTest : public EntityComponentManager { public: void ProcessEntityRemovals() { @@ -167,21 +167,21 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) if (modelCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(1, 2, 3, 0, 0, 1), + EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 1), _pose->Data()); EXPECT_EQ("box", _name->Data()); boxModelEntity = _entity; } else if (modelCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(-1, -2, -3, 0, 0, 1), + EXPECT_EQ(math::Pose3d(-1, -2, -3, 0, 0, 1), _pose->Data()); EXPECT_EQ("cylinder", _name->Data()); cylModelEntity = _entity; } else if (modelCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0, 0, 0, 0, 0, 1), + EXPECT_EQ(math::Pose3d(0, 0, 0, 0, 0, 1), _pose->Data()); EXPECT_EQ("sphere", _name->Data()); sphModelEntity = _entity; @@ -236,7 +236,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) if (linkCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.1, 0.1, 0.1, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.1, 0.1, 0.1, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_link", _name->Data()); @@ -247,7 +247,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (linkCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.2, 0.2, 0.2, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.2, 0.2, 0.2, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_link", _name->Data()); @@ -258,7 +258,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (linkCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.3, 0.3, 0.3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.3, 0.3, 0.3, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_link", _name->Data()); @@ -370,7 +370,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) if (collisionCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.11, 0.11, 0.11, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.11, 0.11, 0.11, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_collision", _name->Data()); @@ -385,7 +385,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (collisionCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.21, 0.21, 0.21, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.21, 0.21, 0.21, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_collision", _name->Data()); @@ -400,7 +400,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (collisionCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.31, 0.31, 0.31, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.31, 0.31, 0.31, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_collision", _name->Data()); @@ -485,7 +485,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) if (visualCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.12, 0.12, 0.12, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.12, 0.12, 0.12, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_visual", _name->Data()); @@ -511,7 +511,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (visualCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.22, 0.22, 0.22, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.22, 0.22, 0.22, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_visual", _name->Data()); @@ -537,7 +537,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (visualCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.32, 0.32, 0.32, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.32, 0.32, 0.32, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_visual", _name->Data()); @@ -636,7 +636,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) lightCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 10, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 10, 0, 0, 0), _pose->Data()); EXPECT_EQ("sun", _name->Data()); @@ -646,19 +646,19 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) EXPECT_EQ("sun", _light->Data().Name()); EXPECT_EQ(sdf::LightType::DIRECTIONAL, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 10, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 0, 10, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ("", _light->Data().PoseRelativeTo()); EXPECT_TRUE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.8f, 0.8f, 0.8f, 1), + EXPECT_EQ(math::Color(0.8f, 0.8f, 0.8f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(1000, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.9, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.01, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); - EXPECT_EQ(ignition::math::Vector3d(-0.5, 0.1, -0.9), + EXPECT_EQ(math::Vector3d(-0.5, 0.1, -0.9), _light->Data().Direction()); return true; }); @@ -733,7 +733,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) EXPECT_EQ(worldEntity, _parent->Data()); EXPECT_EQ(worldEntity, this->ecm.ParentEntity(_entity)); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 0, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 0, 0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere", _name->Data()); sphModelEntity = _entity; @@ -764,7 +764,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) linkCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_link", _name->Data()); EXPECT_EQ(sphModelEntity, _parent->Data()); @@ -803,7 +803,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) visualCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_visual", _name->Data()); @@ -845,7 +845,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) // light attached to link if (lightCount == 1u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 1.0, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 1.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("link_light_point", _name->Data()); @@ -854,13 +854,13 @@ TEST_F(SdfEntityCreatorTest, CreateLights) EXPECT_EQ("link_light_point", _light->Data().Name()); EXPECT_EQ(sdf::LightType::POINT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 1, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 0, 1, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.0f, 0.0f, 1.0f, 1), + EXPECT_EQ(math::Color(0.0f, 0.0f, 1.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.1f, 0.1f, 0.1f, 1), + EXPECT_EQ(math::Color(0.1f, 0.1f, 0.1f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(2, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.05, _light->Data().ConstantAttenuationFactor()); @@ -870,7 +870,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) // directional light in the world else if (lightCount == 2u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 10, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 10, 0, 0, 0), _pose->Data()); EXPECT_EQ("directional", _name->Data()); @@ -879,25 +879,25 @@ TEST_F(SdfEntityCreatorTest, CreateLights) EXPECT_EQ("directional", _light->Data().Name()); EXPECT_EQ(sdf::LightType::DIRECTIONAL, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 10, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 0, 10, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_TRUE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.8f, 0.8f, 0.8f, 1), + EXPECT_EQ(math::Color(0.8f, 0.8f, 0.8f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(100, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.9, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.01, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); - EXPECT_EQ(ignition::math::Vector3d(0.5, 0.2, -0.9), + EXPECT_EQ(math::Vector3d(0.5, 0.2, -0.9), _light->Data().Direction()); } // point light in the world else if (lightCount == 3u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, -1.5, 3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, -1.5, 3, 0, 0, 0), _pose->Data()); EXPECT_EQ("point", _name->Data()); @@ -906,13 +906,13 @@ TEST_F(SdfEntityCreatorTest, CreateLights) EXPECT_EQ("point", _light->Data().Name()); EXPECT_EQ(sdf::LightType::POINT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, -1.5, 3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, -1.5, 3, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(1.0f, 0.0f, 0.0f, 1), + EXPECT_EQ(math::Color(1.0f, 0.0f, 0.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.1f, 0.1f, 0.1f, 1), + EXPECT_EQ(math::Color(0.1f, 0.1f, 0.1f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(4, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.2, _light->Data().ConstantAttenuationFactor()); @@ -922,7 +922,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) // spot light in the world else if (lightCount == 4u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 1.5, 3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 1.5, 3, 0, 0, 0), _pose->Data()); EXPECT_EQ("spot", _name->Data()); @@ -931,19 +931,19 @@ TEST_F(SdfEntityCreatorTest, CreateLights) EXPECT_EQ("spot", _light->Data().Name()); EXPECT_EQ(sdf::LightType::SPOT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 1.5, 3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 1.5, 3, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.0f, 1.0f, 0.0f, 1), + EXPECT_EQ(math::Color(0.0f, 1.0f, 0.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(5, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.3, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.4, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); - EXPECT_EQ(ignition::math::Vector3d(0.0, 0.0, -1.0), + EXPECT_EQ(math::Vector3d(0.0, 0.0, -1.0), _light->Data().Direction()); EXPECT_DOUBLE_EQ(0.1, _light->Data().SpotInnerAngle().Radian()); EXPECT_DOUBLE_EQ(0.5, _light->Data().SpotOuterAngle().Radian()); @@ -1218,7 +1218,7 @@ size_t removedCount(EntityCompMgrTest &_manager) { size_t count = 0; _manager.EachRemoved( - [&](const ignition::gazebo::Entity &, const Ts *...) -> bool + [&](const Entity &, const Ts *...) -> bool { ++count; return true; diff --git a/src/SdfGenerator_TEST.cc b/src/SdfGenerator_TEST.cc index 1478ff02b2..a299d45b7f 100644 --- a/src/SdfGenerator_TEST.cc +++ b/src/SdfGenerator_TEST.cc @@ -644,17 +644,17 @@ TEST_F(ElementUpdateFixture, WorldWithModelsIncludedNotExpanded) TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithInvalidUris) { const std::string goodUri = - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/2"; + "https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/2"; // These are URIs that are potentially problematic. const std::vector fuelUris = { // Thes following two URIs are valid, but have a trailing '/' - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/", - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/2/", + "https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/", + "https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/2/", // Thes following two URIs are invalid, and will not be saved - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/" + "https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/" "notInt", - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/" + "https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/" "notInt/", }; @@ -709,7 +709,7 @@ TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithInvalidUris) TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithNonFuelUris) { const std::vector includeUris = { - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack", + "https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack", std::string("file://") + PROJECT_SOURCE_PATH + "/test/worlds/models/sphere"}; diff --git a/src/ServerConfig.cc b/src/ServerConfig.cc index ba50a7369c..d5c6d027bb 100644 --- a/src/ServerConfig.cc +++ b/src/ServerConfig.cc @@ -315,7 +315,7 @@ class ignition::gazebo::ServerConfigPrivate public: std::string logRecordCompressPath = ""; /// \brief Path to where simulation resources, such as models downloaded - /// from fuel.ignitionrobotics.org, should be stored. + /// from fuel.gazebosim.org, should be stored. public: std::string resourceCache = ""; /// \brief File containing physics engine plugin. If empty, DART will be used. @@ -561,7 +561,7 @@ unsigned int ServerConfig::Seed() const void ServerConfig::SetSeed(unsigned int _seed) { this->dataPtr->seed = _seed; - ignition::math::Rand::Seed(_seed); + math::Rand::Seed(_seed); } ///////////////////////////////////////////////// @@ -902,7 +902,7 @@ parsePluginsFromDoc(const tinyxml2::XMLDocument &_doc) ///////////////////////////////////////////////// std::list -ignition::gazebo::parsePluginsFromFile(const std::string &_fname) +gazebo::parsePluginsFromFile(const std::string &_fname) { tinyxml2::XMLDocument doc; doc.LoadFile(_fname.c_str()); @@ -911,7 +911,7 @@ ignition::gazebo::parsePluginsFromFile(const std::string &_fname) ///////////////////////////////////////////////// std::list -ignition::gazebo::parsePluginsFromString(const std::string &_str) +gazebo::parsePluginsFromString(const std::string &_str) { tinyxml2::XMLDocument doc; doc.Parse(_str.c_str()); @@ -920,28 +920,28 @@ ignition::gazebo::parsePluginsFromString(const std::string &_str) ///////////////////////////////////////////////// std::list -ignition::gazebo::loadPluginInfo(bool _isPlayback) +gazebo::loadPluginInfo(bool _isPlayback) { std::list ret; // 1. Check contents of environment variable std::string envConfig; - bool configSet = ignition::common::env(gazebo::kServerConfigPathEnv, + bool configSet = common::env(kServerConfigPathEnv, envConfig, true); if (configSet) { - if (ignition::common::exists(envConfig)) + if (common::exists(envConfig)) { // Parse configuration stored in environment variable - ret = ignition::gazebo::parsePluginsFromFile(envConfig); + ret = gazebo::parsePluginsFromFile(envConfig); if (ret.empty()) { // This may be desired behavior, but warn just in case. // Some users may want to defer all loading until later // during runtime. - ignwarn << gazebo::kServerConfigPathEnv + ignwarn << kServerConfigPathEnv << " set but no plugins found\n"; } igndbg << "Loaded (" << ret.size() << ") plugins from file " << @@ -954,7 +954,7 @@ ignition::gazebo::loadPluginInfo(bool _isPlayback) // This may be desired behavior, but warn just in case. // Some users may want to defer all loading until late // during runtime. - ignwarn << gazebo::kServerConfigPathEnv + ignwarn << kServerConfigPathEnv << " set but no file found," << " no plugins loaded\n"; return ret; @@ -972,27 +972,27 @@ ignition::gazebo::loadPluginInfo(bool _isPlayback) } std::string defaultConfigDir; - ignition::common::env(IGN_HOMEDIR, defaultConfigDir); - defaultConfigDir = ignition::common::joinPaths(defaultConfigDir, ".ignition", + common::env(IGN_HOMEDIR, defaultConfigDir); + defaultConfigDir = common::joinPaths(defaultConfigDir, ".ignition", "gazebo", IGNITION_GAZEBO_MAJOR_VERSION_STR); - auto defaultConfig = ignition::common::joinPaths(defaultConfigDir, + auto defaultConfig = common::joinPaths(defaultConfigDir, configFilename); - if (!ignition::common::exists(defaultConfig)) + if (!common::exists(defaultConfig)) { - auto installedConfig = ignition::common::joinPaths( + auto installedConfig = common::joinPaths( IGNITION_GAZEBO_SERVER_CONFIG_PATH, configFilename); - if (!ignition::common::createDirectories(defaultConfigDir)) + if (!common::createDirectories(defaultConfigDir)) { ignerr << "Failed to create directory [" << defaultConfigDir << "]." << std::endl; return ret; } - if (!ignition::common::exists(installedConfig)) + if (!common::exists(installedConfig)) { ignerr << "Failed to copy installed config [" << installedConfig << "] to default config [" << defaultConfig << "]." @@ -1000,7 +1000,7 @@ ignition::gazebo::loadPluginInfo(bool _isPlayback) << std::endl; return ret; } - else if (!ignition::common::copyFile(installedConfig, defaultConfig)) + else if (!common::copyFile(installedConfig, defaultConfig)) { ignerr << "Failed to copy installed config [" << installedConfig << "] to default config [" << defaultConfig << "]." @@ -1015,7 +1015,7 @@ ignition::gazebo::loadPluginInfo(bool _isPlayback) } } - ret = ignition::gazebo::parsePluginsFromFile(defaultConfig); + ret = gazebo::parsePluginsFromFile(defaultConfig); if (ret.empty()) { diff --git a/src/ServerConfig_TEST.cc b/src/ServerConfig_TEST.cc index 4e7b7c9aa4..351bf06410 100644 --- a/src/ServerConfig_TEST.cc +++ b/src/ServerConfig_TEST.cc @@ -191,11 +191,11 @@ TEST(ParsePluginsFromFile, PlaybackConfig) TEST(LoadPluginInfo, FromEmptyEnv) { // Set environment to something that doesn't exist - ASSERT_TRUE(common::setenv(gazebo::kServerConfigPathEnv, "foo")); + ASSERT_TRUE(common::setenv(kServerConfigPathEnv, "foo")); auto plugins = loadPluginInfo(); EXPECT_EQ(0u, plugins.size()); - EXPECT_TRUE(common::unsetenv(gazebo::kServerConfigPathEnv)); + EXPECT_TRUE(common::unsetenv(kServerConfigPathEnv)); } ////////////////////////////////////////////////// @@ -204,7 +204,7 @@ TEST(LoadPluginInfo, FromValidEnv) auto validPath = common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "server_valid2.config"); - ASSERT_TRUE(common::setenv(gazebo::kServerConfigPathEnv, validPath)); + ASSERT_TRUE(common::setenv(kServerConfigPathEnv, validPath)); auto plugins = loadPluginInfo(); ASSERT_EQ(2u, plugins.size()); @@ -226,7 +226,7 @@ TEST(LoadPluginInfo, FromValidEnv) EXPECT_EQ("ignition::gazebo::TestModelSystem", plugin->Name()); EXPECT_EQ("ignition::gazebo::TestModelSystem", plugin->Plugin().Name()); - EXPECT_TRUE(common::unsetenv(gazebo::kServerConfigPathEnv)); + EXPECT_TRUE(common::unsetenv(kServerConfigPathEnv)); } ////////////////////////////////////////////////// diff --git a/src/ServerPrivate.cc b/src/ServerPrivate.cc index 6f1929b82e..fffbb62dba 100644 --- a/src/ServerPrivate.cc +++ b/src/ServerPrivate.cc @@ -381,7 +381,7 @@ void ServerPrivate::SetupTransport() } ////////////////////////////////////////////////// -bool ServerPrivate::WorldsService(ignition::msgs::StringMsg_V &_res) +bool ServerPrivate::WorldsService(msgs::StringMsg_V &_res) { std::lock_guard lock(this->worldsMutex); @@ -397,7 +397,7 @@ bool ServerPrivate::WorldsService(ignition::msgs::StringMsg_V &_res) ////////////////////////////////////////////////// bool ServerPrivate::ServerControlService( - const ignition::msgs::ServerControl &_req, msgs::Boolean &_res) + const msgs::ServerControl &_req, msgs::Boolean &_res) { _res.set_data(false); @@ -440,7 +440,7 @@ bool ServerPrivate::ServerControlService( ////////////////////////////////////////////////// void ServerPrivate::AddResourcePathsService( - const ignition::msgs::StringMsg_V &_req) + const msgs::StringMsg_V &_req) { std::vector paths; for (int i = 0; i < _req.data_size(); ++i) @@ -463,7 +463,7 @@ void ServerPrivate::AddResourcePathsService( ////////////////////////////////////////////////// bool ServerPrivate::ResourcePathsService( - ignition::msgs::StringMsg_V &_res) + msgs::StringMsg_V &_res) { _res.Clear(); diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc index 6023c036ea..59879223b5 100644 --- a/src/Server_TEST.cc +++ b/src/Server_TEST.cc @@ -54,7 +54,7 @@ class ServerFixture : public InternalFixture<::testing::TestWithParam> // See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(DefaultServerConfig)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; EXPECT_TRUE(serverConfig.SdfFile().empty()); EXPECT_TRUE(serverConfig.SdfString().empty()); EXPECT_FALSE(serverConfig.UpdateRate()); @@ -110,7 +110,7 @@ TEST_P(ServerFixture, ServerConfigPluginInfo) pluginInfo.SetName("interface"); pluginInfo.SetSdf(nullptr); - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.AddPlugin(pluginInfo); const std::list &plugins = serverConfig.Plugins(); @@ -331,7 +331,7 @@ TEST_P(ServerFixture, ///////////////////////////////////////////////// TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(SdfServerConfig)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetSdfString(TestWorldSansPhysics::World()); EXPECT_TRUE(serverConfig.SdfFile().empty()); @@ -476,7 +476,7 @@ TEST_P(ServerFixture, ///////////////////////////////////////////////// TEST_P(ServerFixture, SdfStringServerConfig) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetSdfFile(common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "shapes.sdf")); @@ -691,7 +691,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(RunOncePaused)) ///////////////////////////////////////////////// TEST_P(ServerFixture, RunNonBlockingMultiple) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetSdfString(TestWorldSansPhysics::World()); gazebo::Server server(serverConfig); @@ -792,7 +792,7 @@ TEST_P(ServerFixture, ServerControlStop) ///////////////////////////////////////////////// TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(AddSystemWhileRunning)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetSdfFile(common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "shapes.sdf")); @@ -840,7 +840,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(AddSystemWhileRunning)) ///////////////////////////////////////////////// TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(AddSystemAfterLoad)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetSdfFile(common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "shapes.sdf")); @@ -903,18 +903,18 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(AddSystemAfterLoad)) ///////////////////////////////////////////////// TEST_P(ServerFixture, Seed) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; EXPECT_EQ(0u, serverConfig.Seed()); unsigned int mySeed = 12345u; serverConfig.SetSeed(mySeed); EXPECT_EQ(mySeed, serverConfig.Seed()); - EXPECT_EQ(mySeed, ignition::math::Rand::Seed()); + EXPECT_EQ(mySeed, math::Rand::Seed()); } ///////////////////////////////////////////////// TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ResourcePath)) { - ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", + common::setenv("IGN_GAZEBO_RESOURCE_PATH", (common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds:") + common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "models")).c_str()); @@ -974,7 +974,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ResourcePath)) // Check physics system loaded meshes and got their BB correct eachCount = 0; _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::AxisAlignedBox *_box)->bool { auto box = _box->Data(); @@ -1003,7 +1003,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ResourcePath)) ///////////////////////////////////////////////// TEST_P(ServerFixture, GetResourcePaths) { - ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", + common::setenv("IGN_GAZEBO_RESOURCE_PATH", std::string("/tmp/some/path") + common::SystemPaths::Delimiter() + std::string("/home/user/another_path")); @@ -1035,12 +1035,12 @@ TEST_P(ServerFixture, GetResourcePaths) ///////////////////////////////////////////////// TEST_P(ServerFixture, AddResourcePaths) { - ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", + common::setenv("IGN_GAZEBO_RESOURCE_PATH", std::string("/tmp/some/path") + common::SystemPaths::Delimiter() + std::string("/home/user/another_path")); - ignition::common::setenv("SDF_PATH", ""); - ignition::common::setenv("IGN_FILE_PATH", ""); + common::setenv("SDF_PATH", ""); + common::setenv("IGN_FILE_PATH", ""); ServerConfig serverConfig; gazebo::Server server(serverConfig); diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc index 3f817dd1c5..3fdf7725d5 100644 --- a/src/SimulationRunner.cc +++ b/src/SimulationRunner.cc @@ -198,7 +198,7 @@ SimulationRunner::SimulationRunner(const sdf::World *_world, { ignmsg << "No systems loaded from SDF, loading defaults" << std::endl; bool isPlayback = !this->serverConfig.LogPlaybackPath().empty(); - auto plugins = ignition::gazebo::loadPluginInfo(isPlayback); + auto plugins = gazebo::loadPluginInfo(isPlayback); this->LoadServerPlugins(plugins); } @@ -404,14 +404,14 @@ void SimulationRunner::PublishStats() IGN_PROFILE("SimulationRunner::PublishStats"); // Create the world statistics message. - ignition::msgs::WorldStatistics msg; + msgs::WorldStatistics msg; msg.set_real_time_factor(this->realTimeFactor); auto realTimeSecNsec = - ignition::math::durationToSecNsec(this->currentInfo.realTime); + math::durationToSecNsec(this->currentInfo.realTime); auto simTimeSecNsec = - ignition::math::durationToSecNsec(this->currentInfo.simTime); + math::durationToSecNsec(this->currentInfo.simTime); msg.mutable_real_time()->set_sec(realTimeSecNsec.first); msg.mutable_real_time()->set_nsec(realTimeSecNsec.second); @@ -437,7 +437,7 @@ void SimulationRunner::PublishStats() // Create and publish the clock message. The clock message is not // throttled. - ignition::msgs::Clock clockMsg; + msgs::Clock clockMsg; clockMsg.mutable_real()->set_sec(realTimeSecNsec.first); clockMsg.mutable_real()->set_nsec(realTimeSecNsec.second); clockMsg.mutable_sim()->set_sec(simTimeSecNsec.first); @@ -527,7 +527,7 @@ void SimulationRunner::UpdateSystems() { IGN_PROFILE("SimulationRunner::UpdateSystems"); // \todo(nkoenig) Systems used to be updated in parallel using - // an ignition::common::WorkerPool. There is overhead associated with + // an common::WorkerPool. There is overhead associated with // this, most notably the creation and destruction of WorkOrders (see // WorkerPool.cc). We could turn on parallel updates in the future, and/or // turn it on if there are sufficient systems. More testing is required. @@ -642,14 +642,14 @@ bool SimulationRunner::Run(const uint64_t _iterations) // https://github.com/ignitionrobotics/ign-gui/pull/306 and // https://github.com/ignitionrobotics/ign-gazebo/pull/1163) advertOpts.SetMsgsPerSec(10); - this->statsPub = this->node->Advertise( + this->statsPub = this->node->Advertise( "stats", advertOpts); } if (!this->rootStatsPub.Valid()) { // Check for the existence of other publishers on `/stats` - std::vector publishers; + std::vector publishers; this->node->TopicInfo("/stats", publishers); if (!publishers.empty()) @@ -676,13 +676,13 @@ bool SimulationRunner::Run(const uint64_t _iterations) // Create the clock publisher. if (!this->clockPub.Valid()) - this->clockPub = this->node->Advertise("clock"); + this->clockPub = this->node->Advertise("clock"); // Create the global clock publisher. if (!this->rootClockPub.Valid()) { // Check for the existence of other publishers on `/clock` - std::vector publishers; + std::vector publishers; this->node->TopicInfo("/clock", publishers); if (!publishers.empty()) @@ -702,7 +702,7 @@ bool SimulationRunner::Run(const uint64_t _iterations) { ignmsg << "Found no publishers on /clock, adding root clock topic" << std::endl; - this->rootClockPub = this->node->Advertise( + this->rootClockPub = this->node->Advertise( "/clock"); } } @@ -1332,13 +1332,13 @@ SimulationRunner::UpdatePeriod() const } ///////////////////////////////////////////////// -const ignition::math::clock::duration &SimulationRunner::StepSize() const +const math::clock::duration &SimulationRunner::StepSize() const { return this->stepSize; } ///////////////////////////////////////////////// -void SimulationRunner::SetStepSize(const ignition::math::clock::duration &_step) +void SimulationRunner::SetStepSize(const math::clock::duration &_step) { this->stepSize = _step; } @@ -1414,7 +1414,7 @@ bool SimulationRunner::RequestRemoveEntity(const Entity _entity, } ////////////////////////////////////////////////// -bool SimulationRunner::GuiInfoService(ignition::msgs::GUI &_res) +bool SimulationRunner::GuiInfoService(msgs::GUI &_res) { _res.Clear(); diff --git a/src/SimulationRunner_TEST.cc b/src/SimulationRunner_TEST.cc index 5f0e91e26c..4dbae0cd04 100644 --- a/src/SimulationRunner_TEST.cc +++ b/src/SimulationRunner_TEST.cc @@ -72,11 +72,11 @@ namespace gazebo inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { namespace components { -using IntComponent = components::Component; +using IntComponent = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.IntComponent", IntComponent) -using DoubleComponent = components::Component; +using DoubleComponent = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.DoubleComponent", DoubleComponent) } @@ -122,31 +122,31 @@ TEST_P(SimulationRunnerTest, CreateEntities) // Check component types EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::World::typeId)); + World::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Model::typeId)); + Model::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::CanonicalLink::typeId)); + CanonicalLink::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Link::typeId)); + Link::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Collision::typeId)); + Collision::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Visual::typeId)); + Visual::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Light::typeId)); + Light::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Name::typeId)); + Name::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::ParentEntity::typeId)); + ParentEntity::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Geometry::typeId)); + Geometry::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( components::Material::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Inertial::typeId)); + Inertial::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Wind::typeId)); + Wind::typeId)); // Check entities // 1 x world + 1 x (default) level + 1 x wind + 5 x model + 5 x link + 5 x @@ -156,10 +156,10 @@ TEST_P(SimulationRunnerTest, CreateEntities) // Check worlds unsigned int worldCount{0}; Entity worldEntity = kNullEntity; - runner.EntityCompMgr().Each( [&](const Entity &_entity, - const components::World *_world, + const World *_world, const components::Name *_name)->bool { EXPECT_NE(nullptr, _world); @@ -187,14 +187,14 @@ TEST_P(SimulationRunnerTest, CreateEntities) Entity sphModelEntity = kNullEntity; Entity capModelEntity = kNullEntity; Entity ellipModelEntity = kNullEntity; - runner.EntityCompMgr().Each( [&](const Entity &_entity, - const components::Model *_model, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Model *_model, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _model); @@ -207,21 +207,21 @@ TEST_P(SimulationRunnerTest, CreateEntities) EXPECT_EQ(worldEntity, _parent->Data()); if (modelCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(1, 2, 3, 0, 0, 1), + EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 1), _pose->Data()); EXPECT_EQ("box", _name->Data()); boxModelEntity = _entity; } else if (modelCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(-1, -2, -3, 0, 0, 1), + EXPECT_EQ(math::Pose3d(-1, -2, -3, 0, 0, 1), _pose->Data()); EXPECT_EQ("cylinder", _name->Data()); cylModelEntity = _entity; } else if (modelCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0, 0, 0, 0, 0, 1), + EXPECT_EQ(math::Pose3d(0, 0, 0, 0, 0, 1), _pose->Data()); EXPECT_EQ("sphere", _name->Data()); sphModelEntity = _entity; @@ -257,14 +257,14 @@ TEST_P(SimulationRunnerTest, CreateEntities) Entity sphLinkEntity = kNullEntity; Entity capLinkEntity = kNullEntity; Entity ellipLinkEntity = kNullEntity; - runner.EntityCompMgr().Each( [&](const Entity &_entity, - const components::Link *_link, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Link *_link, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _link); @@ -276,7 +276,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) if (linkCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.1, 0.1, 0.1, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.1, 0.1, 0.1, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_link", _name->Data()); EXPECT_EQ(boxModelEntity, _parent->Data()); @@ -284,7 +284,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (linkCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.2, 0.2, 0.2, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.2, 0.2, 0.2, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_link", _name->Data()); EXPECT_EQ(cylModelEntity, _parent->Data()); @@ -292,7 +292,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (linkCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.3, 0.3, 0.3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.3, 0.3, 0.3, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_link", _name->Data()); EXPECT_EQ(sphModelEntity, _parent->Data()); @@ -326,10 +326,10 @@ TEST_P(SimulationRunnerTest, CreateEntities) // Check inertials unsigned int inertialCount{0}; - runner.EntityCompMgr().Each( + runner.EntityCompMgr().Each( [&](const Entity & _entity, - const components::Link *_link, - const components::Inertial *_inertial)->bool + const Link *_link, + const Inertial *_inertial)->bool { EXPECT_NE(nullptr, _link); EXPECT_NE(nullptr, _inertial); @@ -373,16 +373,16 @@ TEST_P(SimulationRunnerTest, CreateEntities) // Check collisions unsigned int collisionCount{0}; - runner.EntityCompMgr().Each( [&](const Entity &/*_entity*/, - const components::Collision *_collision, - const components::Geometry *_geometry, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Collision *_collision, + const Geometry *_geometry, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _collision); @@ -395,7 +395,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) if (collisionCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.11, 0.11, 0.11, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.11, 0.11, 0.11, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_collision", _name->Data()); @@ -409,7 +409,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (collisionCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.21, 0.21, 0.21, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.21, 0.21, 0.21, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_collision", _name->Data()); @@ -423,7 +423,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (collisionCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.31, 0.31, 0.31, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.31, 0.31, 0.31, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_collision", _name->Data()); @@ -469,18 +469,18 @@ TEST_P(SimulationRunnerTest, CreateEntities) // Check visuals unsigned int visualCount{0}; - runner.EntityCompMgr().Each( [&](const Entity &/*_entity*/, - const components::Visual *_visual, - const components::Geometry *_geometry, + const Visual *_visual, + const Geometry *_geometry, const components::Material *_material, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _visual); @@ -494,7 +494,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) if (visualCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.12, 0.12, 0.12, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.12, 0.12, 0.12, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_visual", _name->Data()); @@ -513,7 +513,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (visualCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.22, 0.22, 0.22, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.22, 0.22, 0.22, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_visual", _name->Data()); @@ -532,7 +532,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (visualCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.32, 0.32, 0.32, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.32, 0.32, 0.32, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_visual", _name->Data()); @@ -550,7 +550,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (visualCount == 4) { - EXPECT_EQ(ignition::math::Pose3d(0.52, 0.52, 0.52, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.52, 0.52, 0.52, 0, 0, 0), _pose->Data()); EXPECT_EQ("capsule_visual", _name->Data()); @@ -569,7 +569,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (visualCount == 5) { - EXPECT_EQ(ignition::math::Pose3d(0.82, 0.82, 0.82, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.82, 0.82, 0.82, 0, 0, 0), _pose->Data()); EXPECT_EQ("ellipsoid_visual", _name->Data()); @@ -578,7 +578,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) EXPECT_EQ(sdf::GeometryType::ELLIPSOID, _geometry->Data().Type()); EXPECT_NE(nullptr, _geometry->Data().EllipsoidShape()); - EXPECT_EQ(ignition::math::Vector3d(0.4, 0.6, 1.6), + EXPECT_EQ(math::Vector3d(0.4, 0.6, 1.6), _geometry->Data().EllipsoidShape()->Radii()); EXPECT_EQ(math::Color(0.0f, 0.0f, 0.0f), _material->Data().Emissive()); @@ -593,14 +593,14 @@ TEST_P(SimulationRunnerTest, CreateEntities) // Check lights unsigned int lightCount{0}; - runner.EntityCompMgr().Each( [&](const Entity &/*_entity*/, - const components::Light *_light, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Light *_light, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _light); @@ -610,7 +610,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) lightCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 10, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 10, 0, 0, 0), _pose->Data()); EXPECT_EQ("sun", _name->Data()); @@ -619,20 +619,20 @@ TEST_P(SimulationRunnerTest, CreateEntities) EXPECT_EQ("sun", _light->Data().Name()); EXPECT_EQ(sdf::LightType::DIRECTIONAL, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 10, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 0, 10, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ("", _light->Data().PoseRelativeTo()); EXPECT_TRUE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.8f, 0.8f, 0.8f, 1), + EXPECT_EQ(math::Color(0.8f, 0.8f, 0.8f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(1000, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.9, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.01, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); EXPECT_DOUBLE_EQ(1.0, _light->Data().Intensity()); - EXPECT_EQ(ignition::math::Vector3d(-0.5, 0.1, -0.9), + EXPECT_EQ(math::Vector3d(-0.5, 0.1, -0.9), _light->Data().Direction()); return true; }); @@ -662,10 +662,10 @@ TEST_P(SimulationRunnerTest, CreateLights) // Check worlds unsigned int worldCount{0}; Entity worldEntity = kNullEntity; - runner.EntityCompMgr().Each( [&](const Entity &_entity, - const components::World *_world, + const World *_world, const components::Name *_name)->bool { EXPECT_NE(nullptr, _world); @@ -685,14 +685,14 @@ TEST_P(SimulationRunnerTest, CreateLights) // Check model unsigned int modelCount{0}; Entity sphModelEntity = kNullEntity; - runner.EntityCompMgr().Each( [&](const Entity &_entity, - const components::Model *_model, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Model *_model, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _model); @@ -703,7 +703,7 @@ TEST_P(SimulationRunnerTest, CreateLights) modelCount++; EXPECT_EQ(worldEntity, _parent->Data()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 0, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 0, 0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere", _name->Data()); sphModelEntity = _entity; @@ -717,14 +717,14 @@ TEST_P(SimulationRunnerTest, CreateLights) // Check link unsigned int linkCount{0}; Entity sphLinkEntity = kNullEntity; - runner.EntityCompMgr().Each( [&](const Entity &_entity, - const components::Link *_link, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Link *_link, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _link); @@ -734,7 +734,7 @@ TEST_P(SimulationRunnerTest, CreateLights) linkCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_link", _name->Data()); EXPECT_EQ(sphModelEntity, _parent->Data()); @@ -748,18 +748,18 @@ TEST_P(SimulationRunnerTest, CreateLights) // Check visuals unsigned int visualCount{0}; - runner.EntityCompMgr().Each( [&](const Entity &/*_entity*/, - const components::Visual *_visual, - const components::Geometry *_geometry, + const Visual *_visual, + const Geometry *_geometry, const components::Material *_material, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _visual); @@ -771,7 +771,7 @@ TEST_P(SimulationRunnerTest, CreateLights) visualCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_visual", _name->Data()); @@ -792,14 +792,14 @@ TEST_P(SimulationRunnerTest, CreateLights) // Check lights unsigned int lightCount{0}; - runner.EntityCompMgr().Each( [&](const Entity &/*_entity*/, - const components::Light *_light, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Light *_light, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _light); @@ -812,19 +812,19 @@ TEST_P(SimulationRunnerTest, CreateLights) // light attached to link if (lightCount == 1u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 1.0, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 1.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("link_light_point", _name->Data()); EXPECT_EQ(sphLinkEntity, _parent->Data()); EXPECT_EQ("link_light_point", _light->Data().Name()); EXPECT_EQ(sdf::LightType::POINT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 1, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 0, 1, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.0f, 0.0f, 1.0f, 1), + EXPECT_EQ(math::Color(0.0f, 0.0f, 1.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.1f, 0.1f, 0.1f, 1), + EXPECT_EQ(math::Color(0.1f, 0.1f, 0.1f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(2, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.05, _light->Data().ConstantAttenuationFactor()); @@ -834,43 +834,43 @@ TEST_P(SimulationRunnerTest, CreateLights) // directional light in the world else if (lightCount == 2u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 10, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 10, 0, 0, 0), _pose->Data()); EXPECT_EQ("directional", _name->Data()); EXPECT_EQ(worldEntity, _parent->Data()); EXPECT_EQ("directional", _light->Data().Name()); EXPECT_EQ(sdf::LightType::DIRECTIONAL, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 10, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 0, 10, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_TRUE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.8f, 0.8f, 0.8f, 1), + EXPECT_EQ(math::Color(0.8f, 0.8f, 0.8f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(100, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.9, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.01, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); - EXPECT_EQ(ignition::math::Vector3d(0.5, 0.2, -0.9), + EXPECT_EQ(math::Vector3d(0.5, 0.2, -0.9), _light->Data().Direction()); } // point light in the world else if (lightCount == 3u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, -1.5, 3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, -1.5, 3, 0, 0, 0), _pose->Data()); EXPECT_EQ("point", _name->Data()); EXPECT_EQ(worldEntity, _parent->Data()); EXPECT_EQ("point", _light->Data().Name()); EXPECT_EQ(sdf::LightType::POINT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, -1.5, 3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, -1.5, 3, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(1.0f, 0.0f, 0.0f, 1), + EXPECT_EQ(math::Color(1.0f, 0.0f, 0.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.1f, 0.1f, 0.1f, 1), + EXPECT_EQ(math::Color(0.1f, 0.1f, 0.1f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(4, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.2, _light->Data().ConstantAttenuationFactor()); @@ -880,25 +880,25 @@ TEST_P(SimulationRunnerTest, CreateLights) // spot light in the world else if (lightCount == 4u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 1.5, 3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 1.5, 3, 0, 0, 0), _pose->Data()); EXPECT_EQ("spot", _name->Data()); EXPECT_EQ(worldEntity, _parent->Data()); EXPECT_EQ("spot", _light->Data().Name()); EXPECT_EQ(sdf::LightType::SPOT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 1.5, 3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 1.5, 3, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.0f, 1.0f, 0.0f, 1), + EXPECT_EQ(math::Color(0.0f, 1.0f, 0.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(5, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.3, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.4, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); - EXPECT_EQ(ignition::math::Vector3d(0.0, 0.0, -1.0), + EXPECT_EQ(math::Vector3d(0.0, 0.0, -1.0), _light->Data().Direction()); EXPECT_DOUBLE_EQ(0.1, _light->Data().SpotInnerAngle().Radian()); EXPECT_DOUBLE_EQ(0.5, _light->Data().SpotOuterAngle().Radian()); @@ -926,34 +926,34 @@ TEST_P(SimulationRunnerTest, CreateJointEntities) // Check component types EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::World::typeId)); + World::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::CanonicalLink::typeId)); + CanonicalLink::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Link::typeId)); + Link::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Joint::typeId)); + Joint::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::JointAxis::typeId)); + JointAxis::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::JointType::typeId)); + JointType::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::ChildLinkName::typeId)); + ChildLinkName::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::ParentLinkName::typeId)); + ParentLinkName::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::ParentEntity::typeId)); + ParentEntity::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Pose::typeId)); + Pose::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Name::typeId)); + Name::typeId)); const sdf::Model *model = root.WorldByIndex(0)->ModelByIndex(1); // Check canonical links unsigned int canonicalLinkCount{0}; - runner.EntityCompMgr().Each( - [&](const Entity &, const components::CanonicalLink *)->bool + runner.EntityCompMgr().Each( + [&](const Entity &, const CanonicalLink *)->bool { canonicalLinkCount++; return true; @@ -973,11 +973,11 @@ TEST_P(SimulationRunnerTest, CreateJointEntities) }; auto testJoint = [&testAxis](const sdf::Joint *_joint, - const components::JointAxis *_axis, - const components::JointAxis2 *_axis2, - const components::ParentLinkName *_parentLinkName, - const components::ChildLinkName *_childLinkName, - const components::Pose *_pose, + const JointAxis *_axis, + const JointAxis2 *_axis2, + const ParentLinkName *_parentLinkName, + const ChildLinkName *_childLinkName, + const Pose *_pose, const components::Name *_name, bool _checkAxis = true, bool _checkAxis2 = false) @@ -1012,25 +1012,25 @@ TEST_P(SimulationRunnerTest, CreateJointEntities) }; std::set jointTypes; - runner.EntityCompMgr().Each( [&](const Entity &_entity, - const components::Joint * /*_joint*/, - const components::JointType *_jointType, - const components::ParentLinkName *_parentLinkName, - const components::ChildLinkName *_childLinkName, - const components::Pose *_pose, + const Joint * /*_joint*/, + const JointType *_jointType, + const ParentLinkName *_parentLinkName, + const ChildLinkName *_childLinkName, + const Pose *_pose, const components::Name *_name)->bool { jointTypes.insert(_jointType->Data()); auto axis = - runner.EntityCompMgr().Component(_entity); + runner.EntityCompMgr().Component(_entity); auto axis2 = - runner.EntityCompMgr().Component(_entity); + runner.EntityCompMgr().Component(_entity); const sdf::Joint *joint = model->JointByName(_name->Data()); @@ -1184,7 +1184,7 @@ TEST_P(SimulationRunnerTest, Time) } ///////////////////////////////////////////////// -// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +// See https://github.com/gazebosim/gz-sim/issues/1175 TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) { // Load SDF file @@ -1200,9 +1200,9 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Get world entity Entity worldId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::World *_world)->bool + runner.EntityCompMgr().Each([&]( + const Entity &_entity, + const World *_world)->bool { EXPECT_NE(nullptr, _world); worldId = _entity; @@ -1212,9 +1212,9 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Get model entity Entity modelId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::Model *_model)->bool + runner.EntityCompMgr().Each([&]( + const Entity &_entity, + const Model *_model)->bool { EXPECT_NE(nullptr, _model); modelId = _entity; @@ -1224,9 +1224,9 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Get sensor entity Entity sensorId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::Sensor *_sensor)->bool + runner.EntityCompMgr().Each([&]( + const Entity &_entity, + const Sensor *_sensor)->bool { EXPECT_NE(nullptr, _sensor); sensorId = _entity; @@ -1236,9 +1236,9 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Get visual entity Entity visualId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::Visual *_visual)->bool + runner.EntityCompMgr().Each([&]( + const Entity &_entity, + const components::Visual *_visual)->bool { EXPECT_NE(nullptr, _visual); visualId = _entity; @@ -1248,7 +1248,7 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Check component registered by world plugin std::string worldComponentName{"WorldPluginComponent"}; - auto worldComponentId = ignition::common::hash64(worldComponentName); + auto worldComponentId = common::hash64(worldComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(worldComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(worldId, @@ -1256,7 +1256,7 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Check component registered by model plugin std::string modelComponentName{"ModelPluginComponent"}; - auto modelComponentId = ignition::common::hash64(modelComponentName); + auto modelComponentId = common::hash64(modelComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(modelComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(modelId, @@ -1264,7 +1264,7 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Check component registered by sensor plugin std::string sensorComponentName{"SensorPluginComponent"}; - auto sensorComponentId = ignition::common::hash64(sensorComponentName); + auto sensorComponentId = common::hash64(sensorComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(sensorComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(sensorId, @@ -1272,7 +1272,7 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Check component registered by visual plugin std::string visualComponentName{"VisualPluginComponent"}; - auto visualComponentId = ignition::common::hash64(visualComponentName); + auto visualComponentId = common::hash64(visualComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(visualComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(visualId, @@ -1285,10 +1285,10 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // reproduce? Maybe we need to test unloading plugins, but we have no API for // it yet. #if defined (__clang__) - components::Factory::Instance()->Unregister(worldComponentId); - components::Factory::Instance()->Unregister(modelComponentId); - components::Factory::Instance()->Unregister(sensorComponentId); - components::Factory::Instance()->Unregister(visualComponentId); + Factory::Instance()->Unregister(worldComponentId); + Factory::Instance()->Unregister(modelComponentId); + Factory::Instance()->Unregister(sensorComponentId); + Factory::Instance()->Unregister(visualComponentId); #endif } @@ -1304,7 +1304,7 @@ TEST_P(SimulationRunnerTest, // ServerConfig will fall back to environment variable auto config = common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "server_valid2.config"); - ASSERT_EQ(true, common::setenv(gazebo::kServerConfigPathEnv, config)); + ASSERT_EQ(true, common::setenv(kServerConfigPathEnv, config)); ServerConfig serverConfig; // Create simulation runner @@ -1345,9 +1345,9 @@ TEST_P(SimulationRunnerTest, // Get world entity Entity worldId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::World *_world)->bool + runner.EntityCompMgr().Each([&]( + const Entity &_entity, + const World *_world)->bool { EXPECT_NE(nullptr, _world); worldId = _entity; @@ -1357,9 +1357,9 @@ TEST_P(SimulationRunnerTest, // Get model entity Entity modelId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::Model *_model)->bool + runner.EntityCompMgr().Each([&]( + const Entity &_entity, + const Model *_model)->bool { EXPECT_NE(nullptr, _model); modelId = _entity; @@ -1369,9 +1369,9 @@ TEST_P(SimulationRunnerTest, // Get sensor entity Entity sensorId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::Sensor *_sensor)->bool + runner.EntityCompMgr().Each([&]( + const Entity &_entity, + const Sensor *_sensor)->bool { EXPECT_NE(nullptr, _sensor); sensorId = _entity; @@ -1381,7 +1381,7 @@ TEST_P(SimulationRunnerTest, // Check component registered by world plugin std::string worldComponentName{"WorldPluginComponent"}; - auto worldComponentId = ignition::common::hash64(worldComponentName); + auto worldComponentId = common::hash64(worldComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(worldComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(worldId, @@ -1389,7 +1389,7 @@ TEST_P(SimulationRunnerTest, // Check component registered by model plugin std::string modelComponentName{"ModelPluginComponent"}; - auto modelComponentId = ignition::common::hash64(modelComponentName); + auto modelComponentId = common::hash64(modelComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(modelComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(modelId, @@ -1397,7 +1397,7 @@ TEST_P(SimulationRunnerTest, // Check component registered by sensor plugin std::string sensorComponentName{"SensorPluginComponent"}; - auto sensorComponentId = ignition::common::hash64(sensorComponentName); + auto sensorComponentId = common::hash64(sensorComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(sensorComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(sensorId, @@ -1410,9 +1410,9 @@ TEST_P(SimulationRunnerTest, // reproduce? Maybe we need to test unloading plugins, but we have no API for // it yet. #if defined (__clang__) - components::Factory::Instance()->Unregister(worldComponentId); - components::Factory::Instance()->Unregister(modelComponentId); - components::Factory::Instance()->Unregister(sensorComponentId); + Factory::Instance()->Unregister(worldComponentId); + Factory::Instance()->Unregister(modelComponentId); + Factory::Instance()->Unregister(sensorComponentId); #endif } @@ -1429,13 +1429,13 @@ TEST_P(SimulationRunnerTest, // The user may have modified their local config. auto config = common::joinPaths(PROJECT_SOURCE_PATH, "include", "ignition", "gazebo", "server.config"); - ASSERT_TRUE(common::setenv(gazebo::kServerConfigPathEnv, config)); + ASSERT_TRUE(common::setenv(kServerConfigPathEnv, config)); // Create simulation runner auto systemLoader = std::make_shared(); SimulationRunner runner(rootWithout.WorldByIndex(0), systemLoader); ASSERT_EQ(3u, runner.SystemCount()); - common::unsetenv(gazebo::kServerConfigPathEnv); + common::unsetenv(kServerConfigPathEnv); } ///////////////////////////////////////////////// @@ -1455,24 +1455,24 @@ TEST_P(SimulationRunnerTest, // Get model entities auto boxEntity = runner.EntityCompMgr().EntityByComponents( - ignition::gazebo::components::Model(), - ignition::gazebo::components::Name("box")); + Model(), + components::Name("box")); EXPECT_NE(kNullEntity, boxEntity); auto sphereEntity = runner.EntityCompMgr().EntityByComponents( - ignition::gazebo::components::Model(), - ignition::gazebo::components::Name("sphere")); + Model(), + components::Name("sphere")); EXPECT_NE(kNullEntity, sphereEntity); auto cylinderEntity = runner.EntityCompMgr().EntityByComponents( - ignition::gazebo::components::Model(), - ignition::gazebo::components::Name("cylinder")); + Model(), + components::Name("cylinder")); EXPECT_NE(kNullEntity, cylinderEntity); // We can't access the type registered by the plugin unless we link against // it, but we know its name to check std::string componentName{"ModelPluginComponent"}; - auto componentId = ignition::common::hash64(componentName); + auto componentId = common::hash64(componentName); // Check there's no double component EXPECT_FALSE(runner.EntityCompMgr().HasComponentType(componentId)); diff --git a/src/SystemLoader_TEST.cc b/src/SystemLoader_TEST.cc index d1c8b38bd6..8d3882ec35 100644 --- a/src/SystemLoader_TEST.cc +++ b/src/SystemLoader_TEST.cc @@ -35,7 +35,7 @@ TEST(SystemLoader, Constructor) gazebo::SystemLoader sm; // Add test plugin to path (referenced in config) - auto testBuildPath = ignition::common::joinPaths( + auto testBuildPath = common::joinPaths( std::string(PROJECT_BINARY_PATH), "lib"); sm.AddSystemPluginPath(testBuildPath); diff --git a/src/TestFixture.cc b/src/TestFixture.cc index 8f1dffd9f5..e3a9479749 100644 --- a/src/TestFixture.cc +++ b/src/TestFixture.cc @@ -113,7 +113,7 @@ class ignition::gazebo::TestFixturePrivate public: void Init(const ServerConfig &_config); /// \brief Pointer to underlying server - public: std::shared_ptr server{nullptr}; + public: std::shared_ptr server{nullptr}; /// \brief Pointer to underlying Helper interface public: std::shared_ptr helperSystem{nullptr}; @@ -149,7 +149,7 @@ TestFixture::~TestFixture() void TestFixturePrivate::Init(const ServerConfig &_config) { this->helperSystem = std::make_shared(); - this->server = std::make_shared(_config); + this->server = std::make_shared(_config); } ////////////////////////////////////////////////// @@ -208,7 +208,7 @@ TestFixture &TestFixture::OnPostUpdate(std::function TestFixture::Server() const +std::shared_ptr TestFixture::Server() const { return this->dataPtr->server; } diff --git a/src/Util_TEST.cc b/src/Util_TEST.cc index 3a2ec1f081..6555cfcc7f 100644 --- a/src/Util_TEST.cc +++ b/src/Util_TEST.cc @@ -824,7 +824,7 @@ TEST_F(UtilTest, EntityFromMsg) ecm.CreateComponent(actorDEntity, components::ParentEntity(worldEntity)); // Check entities - auto createMsg = [&ecm](Entity _id, const std::string &_name = "", + auto createMsg = [&](Entity _id, const std::string &_name = "", msgs::Entity::Type _type = msgs::Entity::NONE) -> msgs::Entity { msgs::Entity msg; diff --git a/src/World.cc b/src/World.cc index 2d1514f79c..8f8ac5d5b6 100644 --- a/src/World.cc +++ b/src/World.cc @@ -140,7 +140,7 @@ Entity World::LightByName(const EntityComponentManager &_ecm, const std::string &_name) const { // Can't use components::Light in EntityByComponents, see - // https://github.com/ignitionrobotics/ign-gazebo/issues/376 + // https://github.com/gazebosim/gz-sim/issues/376 auto entities = _ecm.EntitiesByComponents( components::ParentEntity(this->dataPtr->id), components::Name(_name)); @@ -158,7 +158,7 @@ Entity World::ActorByName(const EntityComponentManager &_ecm, const std::string &_name) const { // Can't use components::Actor in EntityByComponents, see - // https://github.com/ignitionrobotics/ign-gazebo/issues/376 + // https://github.com/gazebosim/gz-sim/issues/376 auto entities = _ecm.EntitiesByComponents( components::ParentEntity(this->dataPtr->id), components::Name(_name)); @@ -185,7 +185,7 @@ Entity World::ModelByName(const EntityComponentManager &_ecm, std::vector World::Lights(const EntityComponentManager &_ecm) const { // Can't use components::Light in EntityByComponents, see - // https://github.com/ignitionrobotics/ign-gazebo/issues/376 + // https://github.com/gazebosim/gz-sim/issues/376 auto entities = _ecm.EntitiesByComponents( components::ParentEntity(this->dataPtr->id)); @@ -202,7 +202,7 @@ std::vector World::Lights(const EntityComponentManager &_ecm) const std::vector World::Actors(const EntityComponentManager &_ecm) const { // Can't use components::Actor in EntityByComponents, see - // https://github.com/ignitionrobotics/ign-gazebo/issues/376 + // https://github.com/gazebosim/gz-sim/issues/376 auto entities = _ecm.EntitiesByComponents( components::ParentEntity(this->dataPtr->id)); diff --git a/src/cmd/cmdgazebo.rb.in b/src/cmd/cmdgazebo.rb.in index 023843ce1d..abf4aada61 100755 --- a/src/cmd/cmdgazebo.rb.in +++ b/src/cmd/cmdgazebo.rb.in @@ -465,7 +465,7 @@ has properly set the DYLD_LIBRARY_PATH environment variables." if plugin.end_with? ".dylib" puts "`ign gazebo` currently only works with the -s argument on macOS. -See https://github.com/ignitionrobotics/ign-gazebo/issues/44 for more info." +See https://github.com/gazebosim/gz-sim/issues/44 for more info." exit(-1) end @@ -530,7 +530,7 @@ See https://github.com/gazebosim/gz-sim/issues/168 for more info." else options['gui'] if plugin.end_with? ".dylib" puts "`ign gazebo` currently only works with the -s argument on macOS. -See https://github.com/ignitionrobotics/ign-gazebo/issues/44 for more info." +See https://github.com/gazebosim/gz-sim/issues/44 for more info." exit(-1) end diff --git a/src/gui/AboutDialogHandler.cc b/src/gui/AboutDialogHandler.cc index 545f6fbb66..8e94a48e15 100644 --- a/src/gui/AboutDialogHandler.cc +++ b/src/gui/AboutDialogHandler.cc @@ -28,15 +28,16 @@ using namespace gazebo::gui; ///////////////////////////////////////////////// AboutDialogHandler::AboutDialogHandler() { + aboutText += "Gazebo " + std::string(GZ_DISTRIBUTION) + "
"; aboutText += std::string(IGNITION_GAZEBO_VERSION_HEADER); aboutText += "" "" "" "" "" @@ -45,9 +46,9 @@ AboutDialogHandler::AboutDialogHandler() "Tutorials:" "" "" "" diff --git a/src/gui/GuiFileHandler.cc b/src/gui/GuiFileHandler.cc index 8572af744a..643ef2dd7b 100644 --- a/src/gui/GuiFileHandler.cc +++ b/src/gui/GuiFileHandler.cc @@ -45,7 +45,7 @@ void GuiFileHandler::SaveWorldAs(const QString &_fileUrl, std::string localPath = url.toLocalFile().toStdString() + suffix; std::string service{"/gazebo/worlds"}; - ignition::msgs::StringMsg_V worldsMsg; + msgs::StringMsg_V worldsMsg; bool result{false}; unsigned int timeout{5000}; diff --git a/src/gui/GuiRunner.cc b/src/gui/GuiRunner.cc index ab8a8d43e9..201b3f606d 100644 --- a/src/gui/GuiRunner.cc +++ b/src/gui/GuiRunner.cc @@ -255,7 +255,7 @@ void GuiRunner::RequestState() } } - ignition::msgs::StringMsg req; + msgs::StringMsg req; req.set_data(reqSrv); // Subscribe to periodic updates. diff --git a/src/gui/Gui_TEST.cc b/src/gui/Gui_TEST.cc index 92a98a1dad..8f3d69e42d 100644 --- a/src/gui/Gui_TEST.cc +++ b/src/gui/Gui_TEST.cc @@ -44,17 +44,17 @@ class GuiTest : public InternalFixture<::testing::Test> }; ///////////////////////////////////////////////// -// https://github.com/ignitionrobotics/ign-gazebo/issues/8 +// https://github.com/gazebosim/gz-sim/issues/8 // See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 TEST_F(GuiTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PathManager)) { common::Console::SetVerbosity(4); igndbg << "Start test" << std::endl; - ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", + common::setenv("IGN_GAZEBO_RESOURCE_PATH", "/from_env:/tmp/more_env"); - ignition::common::setenv("SDF_PATH", ""); - ignition::common::setenv("IGN_FILE_PATH", ""); + common::setenv("SDF_PATH", ""); + common::setenv("IGN_FILE_PATH", ""); igndbg << "Environment set" << std::endl; transport::Node node; @@ -94,8 +94,8 @@ TEST_F(GuiTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PathManager)) node.Advertise("/gazebo/resource_paths/get", pathsCb); igndbg << "Paths advertised" << std::endl; - auto app = ignition::gazebo::gui::createGui( - gg_argc, gg_argv, nullptr, nullptr, false, nullptr); + auto app = createGui(gg_argc, gg_argv, nullptr, + nullptr, false, nullptr); EXPECT_NE(nullptr, app); igndbg << "GUI created" << std::endl; diff --git a/src/gui/plugins/align_tool/AlignTool.cc b/src/gui/plugins/align_tool/AlignTool.cc index a2d965ef26..24e0815005 100644 --- a/src/gui/plugins/align_tool/AlignTool.cc +++ b/src/gui/plugins/align_tool/AlignTool.cc @@ -352,14 +352,14 @@ void AlignTool::Align() this->dataPtr->scene = rendering::sceneFromFirstRenderEngine(); // Get current list of selected entities - std::vector selectedList; - ignition::rendering::VisualPtr relativeVisual; + std::vector selectedList; + rendering::VisualPtr relativeVisual; for (const auto &entityId : this->dataPtr->selectedEntities) { for (auto i = 0u; i < this->dataPtr->scene->VisualCount(); ++i) { - ignition::rendering::VisualPtr vis = + rendering::VisualPtr vis = this->dataPtr->scene->VisualByIndex(i); if (!vis) continue; @@ -389,8 +389,8 @@ void AlignTool::Align() (relativeVisual = selectedList.back()); // Callback function for ignition node request - std::function cb = - [](const ignition::msgs::Boolean &/* _rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/* _rep*/, const bool _result) { if (!_result) ignerr << "Error setting pose" << std::endl; @@ -404,7 +404,7 @@ void AlignTool::Align() } int axisIndex = static_cast(this->dataPtr->axis); - ignition::msgs::Pose req; + msgs::Pose req; ignition::math::AxisAlignedBox targetBox = relativeVisual->BoundingBox(); ignition::math::Vector3d targetMin = targetBox.Min(); @@ -566,7 +566,7 @@ bool AlignTool::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::EntitiesSelected::kType) + gui::events::EntitiesSelected::kType) { auto selectedEvent = reinterpret_cast( @@ -589,7 +589,7 @@ bool AlignTool::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::DeselectAllEntities::kType) + gui::events::DeselectAllEntities::kType) { this->dataPtr->selectedEntities.clear(); } @@ -597,5 +597,5 @@ bool AlignTool::eventFilter(QObject *_obj, QEvent *_event) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::AlignTool, +IGNITION_ADD_PLUGIN(AlignTool, ignition::gui::Plugin) diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 0c9fe29d50..ad83a21d68 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -154,7 +154,7 @@ using namespace gazebo; ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const msgs::Light &_data) +void gazebo::setData(QStandardItem *_item, const msgs::Light &_data) { if (nullptr == _item) return; @@ -234,7 +234,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const msgs::Light &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, +void gazebo::setData(QStandardItem *_item, const math::Vector3d &_data) { if (nullptr == _item) @@ -251,7 +251,7 @@ void ignition::gazebo::setData(QStandardItem *_item, ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const std::string &_data) +void gazebo::setData(QStandardItem *_item, const std::string &_data) { if (nullptr == _item) return; @@ -264,7 +264,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const std::string &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, +void gazebo::setData(QStandardItem *_item, const std::ostringstream &_data) { if (nullptr == _item) @@ -278,7 +278,7 @@ void ignition::gazebo::setData(QStandardItem *_item, ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const bool &_data) +void gazebo::setData(QStandardItem *_item, const bool &_data) { if (nullptr == _item) return; @@ -290,7 +290,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const bool &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const int &_data) +void gazebo::setData(QStandardItem *_item, const int &_data) { if (nullptr == _item) return; @@ -302,14 +302,14 @@ void ignition::gazebo::setData(QStandardItem *_item, const int &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const Entity &_data) +void gazebo::setData(QStandardItem *_item, const Entity &_data) { setData(_item, static_cast(_data)); } ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const double &_data) +void gazebo::setData(QStandardItem *_item, const double &_data) { if (nullptr == _item) return; @@ -321,7 +321,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const double &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const sdf::Physics &_data) +void gazebo::setData(QStandardItem *_item, const sdf::Physics &_data) { if (nullptr == _item) return; @@ -336,7 +336,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const sdf::Physics &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, +void gazebo::setData(QStandardItem *_item, const sdf::Material &_data) { if (nullptr == _item) @@ -369,7 +369,7 @@ void ignition::gazebo::setData(QStandardItem *_item, ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, +void gazebo::setData(QStandardItem *_item, const math::SphericalCoordinates &_data) { if (nullptr == _item) @@ -388,7 +388,7 @@ void ignition::gazebo::setData(QStandardItem *_item, } ////////////////////////////////////////////////// -void ignition::gazebo::setUnit(QStandardItem *_item, const std::string &_unit) +void gazebo::setUnit(QStandardItem *_item, const std::string &_unit) { if (nullptr == _item) return; @@ -417,7 +417,7 @@ ComponentsModel::ComponentsModel() : QStandardItemModel() ///////////////////////////////////////////////// QStandardItem *ComponentsModel::AddComponentType( - ignition::gazebo::ComponentTypeId _typeId) + ComponentTypeId _typeId) { IGN_PROFILE_THREAD_NAME("Qt thread"); IGN_PROFILE("ComponentsModel::AddComponentType"); @@ -448,7 +448,7 @@ QStandardItem *ComponentsModel::AddComponentType( ///////////////////////////////////////////////// void ComponentsModel::RemoveComponentType( - ignition::gazebo::ComponentTypeId _typeId) + ComponentTypeId _typeId) { IGN_PROFILE_THREAD_NAME("Qt thread"); IGN_PROFILE("ComponentsModel::RemoveComponentType"); @@ -485,7 +485,7 @@ QHash ComponentsModel::RoleNames() ComponentInspector::ComponentInspector() : GuiSystem(), dataPtr(std::make_unique()) { - qRegisterMetaType(); + qRegisterMetaType(); qRegisterMetaType("Entity"); } @@ -961,7 +961,7 @@ bool ComponentInspector::eventFilter(QObject *_obj, QEvent *_event) { if (!this->dataPtr->locked) { - if (_event->type() == gazebo::gui::events::EntitiesSelected::kType) + if (_event->type() == gui::events::EntitiesSelected::kType) { auto event = reinterpret_cast(_event); if (event && !event->Data().empty()) @@ -970,7 +970,7 @@ bool ComponentInspector::eventFilter(QObject *_obj, QEvent *_event) } } - if (_event->type() == gazebo::gui::events::DeselectAllEntities::kType) + if (_event->type() == gui::events::DeselectAllEntities::kType) { auto event = reinterpret_cast( _event); @@ -1127,14 +1127,14 @@ void ComponentInspector::OnLight( ///////////////////////////////////////////////// void ComponentInspector::OnPhysics(double _stepSize, double _realTimeFactor) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error setting physics parameters" << std::endl; }; - ignition::msgs::Physics req; + msgs::Physics req; req.set_max_step_size(_stepSize); req.set_real_time_factor(_realTimeFactor); auto physicsCmdService = "/world/" + this->dataPtr->worldName @@ -1344,5 +1344,5 @@ void ComponentInspector::OnAddSystem(const QString &_name, } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::ComponentInspector, +IGNITION_ADD_PLUGIN(ComponentInspector, ignition::gui::Plugin) diff --git a/src/gui/plugins/entity_tree/EntityTree.cc b/src/gui/plugins/entity_tree/EntityTree.cc index 38a80a9557..99fa75fcae 100644 --- a/src/gui/plugins/entity_tree/EntityTree.cc +++ b/src/gui/plugins/entity_tree/EntityTree.cc @@ -526,7 +526,7 @@ void EntityTree::OnLoadMesh(const QString &_mesh) ///////////////////////////////////////////////// bool EntityTree::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gazebo::gui::events::EntitiesSelected::kType) + if (_event->type() == gui::events::EntitiesSelected::kType) { auto selectedEvent = reinterpret_cast(_event); @@ -544,7 +544,7 @@ bool EntityTree::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::DeselectAllEntities::kType) + gui::events::DeselectAllEntities::kType) { auto deselectAllEvent = reinterpret_cast(_event); @@ -577,5 +577,5 @@ bool EntityTree::eventFilter(QObject *_obj, QEvent *_event) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::EntityTree, +IGNITION_ADD_PLUGIN(EntityTree, ignition::gui::Plugin) diff --git a/src/gui/plugins/joint_position_controller/JointPositionController.cc b/src/gui/plugins/joint_position_controller/JointPositionController.cc index c800f14aff..b233383f1f 100644 --- a/src/gui/plugins/joint_position_controller/JointPositionController.cc +++ b/src/gui/plugins/joint_position_controller/JointPositionController.cc @@ -291,7 +291,7 @@ void JointPositionController::Update(const UpdateInfo &, QMetaObject::invokeMethod(&this->dataPtr->jointsModel, "RemoveJoint", Qt::QueuedConnection, - Q_ARG(Entity, jointEntity)); + Q_ARG(ignition::gazebo::Entity, jointEntity)); } } } @@ -374,7 +374,7 @@ void JointPositionController::OnCommand(const QString &_jointName, double _pos) { std::string jointName = _jointName.toStdString(); - ignition::msgs::Double msg; + msgs::Double msg; msg.set_data(_pos); auto topic = transport::TopicUtils::AsValidTopic("/model/" + this->dataPtr->modelName.toStdString() + "/joint/" + jointName + @@ -387,7 +387,7 @@ void JointPositionController::OnCommand(const QString &_jointName, double _pos) return; } - auto pub = this->dataPtr->node.Advertise(topic); + auto pub = this->dataPtr->node.Advertise(topic); pub.Publish(msg); } @@ -404,7 +404,7 @@ void JointPositionController::OnReset() continue; } - ignition::msgs::Double msg; + msgs::Double msg; msg.set_data(0); auto topic = transport::TopicUtils::AsValidTopic("/model/" + this->dataPtr->modelName.toStdString() + "/joint/" + jointName + @@ -417,11 +417,11 @@ void JointPositionController::OnReset() return; } - auto pub = this->dataPtr->node.Advertise(topic); + auto pub = this->dataPtr->node.Advertise(topic); pub.Publish(msg); } } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::gui::JointPositionController, +IGNITION_ADD_PLUGIN(JointPositionController, ignition::gui::Plugin) diff --git a/src/gui/plugins/modules/EntityContextMenu.cc b/src/gui/plugins/modules/EntityContextMenu.cc index d2282c4dc0..83141a634b 100644 --- a/src/gui/plugins/modules/EntityContextMenu.cc +++ b/src/gui/plugins/modules/EntityContextMenu.cc @@ -86,7 +86,7 @@ using namespace gazebo; void IgnGazeboPlugin::registerTypes(const char *_uri) { // Register our 'EntityContextMenuItem' in qml engine - qmlRegisterType(_uri, 1, 0, + qmlRegisterType(_uri, 1, 0, "EntityContextMenuItem"); } @@ -163,14 +163,14 @@ void EntityContextMenu::OnRemove( "/world/" + this->dataPtr->worldName + "/remove"; } - std::function cb = - [](const ignition::msgs::Boolean &_rep, const bool _result) + std::function cb = + [](const msgs::Boolean &_rep, const bool _result) { if (!_result || !_rep.data()) ignerr << "Error sending remove request" << std::endl; }; - ignition::msgs::Entity req; + msgs::Entity req; req.set_name(_data.toStdString()); req.set_type(convert(_type.toStdString())); @@ -180,8 +180,8 @@ void EntityContextMenu::OnRemove( ///////////////////////////////////////////////// void EntityContextMenu::OnRequest(const QString &_request, const QString &_data) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error sending move to request" << std::endl; @@ -190,13 +190,13 @@ void EntityContextMenu::OnRequest(const QString &_request, const QString &_data) std::string request = _request.toStdString(); if (request == "move_to") { - ignition::msgs::StringMsg req; + msgs::StringMsg req; req.set_data(_data.toStdString()); this->dataPtr->node.Request(this->dataPtr->moveToService, req, cb); } else if (request == "follow") { - ignition::msgs::StringMsg req; + msgs::StringMsg req; req.set_data(_data.toStdString()); this->dataPtr->node.Request(this->dataPtr->followService, req, cb); } @@ -232,7 +232,7 @@ void EntityContextMenu::OnRequest(const QString &_request, const QString &_data) } else if (request == "view_collisions") { - ignition::msgs::StringMsg req; + msgs::StringMsg req; req.set_data(_data.toStdString()); this->dataPtr->node.Request(this->dataPtr->viewCollisionsService, req, cb); } diff --git a/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc b/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc index 2935caaf1c..94f852a452 100644 --- a/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc +++ b/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc @@ -251,5 +251,5 @@ void PlaybackScrubber::OnDrop(double _value) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::PlaybackScrubber, +IGNITION_ADD_PLUGIN(PlaybackScrubber, ignition::gui::Plugin) diff --git a/src/gui/plugins/plot_3d/Plot3D.cc b/src/gui/plugins/plot_3d/Plot3D.cc index 45565bbc75..b2e2657a3c 100644 --- a/src/gui/plugins/plot_3d/Plot3D.cc +++ b/src/gui/plugins/plot_3d/Plot3D.cc @@ -165,7 +165,7 @@ void Plot3D::ClearPlot() // Clear previous plot if (this->dataPtr->markerMsg.point().size() > 0) { - this->dataPtr->markerMsg.set_action(ignition::msgs::Marker::DELETE_MARKER); + this->dataPtr->markerMsg.set_action(msgs::Marker::DELETE_MARKER); this->dataPtr->node.Request("/marker", this->dataPtr->markerMsg); } } @@ -245,7 +245,7 @@ void Plot3D::Update(const UpdateInfo &, EntityComponentManager &_ecm) return; this->dataPtr->prevPos = point; - ignition::msgs::Set(this->dataPtr->markerMsg.add_point(), point); + msgs::Set(this->dataPtr->markerMsg.add_point(), point); // Reduce message array if (this->dataPtr->markerMsg.point_size() > this->dataPtr->maxPoints) @@ -401,5 +401,5 @@ void Plot3D::SetMaxPoints(int _maxPoints) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::gui::Plot3D, +IGNITION_ADD_PLUGIN(Plot3D, ignition::gui::Plugin) diff --git a/src/gui/plugins/resource_spawner/ResourceSpawner.cc b/src/gui/plugins/resource_spawner/ResourceSpawner.cc index 9320e88be4..73450c73ef 100644 --- a/src/gui/plugins/resource_spawner/ResourceSpawner.cc +++ b/src/gui/plugins/resource_spawner/ResourceSpawner.cc @@ -217,7 +217,7 @@ ResourceSpawner::ResourceSpawner() ignition::gui::App()->Engine()->rootContext()->setContextProperty( "OwnerList", &this->dataPtr->ownerModel); this->dataPtr->fuelClient = - std::make_unique(); + std::make_unique(); } ///////////////////////////////////////////////// @@ -482,7 +482,7 @@ void ResourceSpawner::OnDownloadFuelResource(const QString &_path, // Set the waiting cursor while the resource downloads QGuiApplication::setOverrideCursor(Qt::WaitCursor); if (this->dataPtr->fuelClient->DownloadModel( - ignition::common::URI(_path.toStdString()), localPath)) + common::URI(_path.toStdString()), localPath)) { // Successful download, set thumbnail std::string thumbnailPath = common::joinPaths(localPath, "thumbnails"); @@ -564,7 +564,7 @@ void ResourceSpawner::LoadConfig(const tinyxml2::XMLElement *) std::set ownerSet; for (auto const &server : servers) { - std::vector models; + std::vector models; for (auto iter = this->dataPtr->fuelClient->Models(server); iter; ++iter) { models.push_back(iter->Identification()); @@ -584,10 +584,10 @@ void ResourceSpawner::LoadConfig(const tinyxml2::XMLElement *) // If the resource is cached, we can go ahead and populate the // respective information if (this->dataPtr->fuelClient->CachedModel( - ignition::common::URI(id.UniqueName()), path)) + common::URI(id.UniqueName()), path)) { resource.isDownloaded = true; - resource.sdfPath = ignition::common::joinPaths(path, "model.sdf"); + resource.sdfPath = common::joinPaths(path, "model.sdf"); std::string thumbnailPath = common::joinPaths(path, "thumbnails"); this->SetThumbnail(thumbnailPath, resource); } @@ -633,5 +633,5 @@ void ResourceSpawner::OnResourceSpawn(const QString &_sdfPath) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::ResourceSpawner, +IGNITION_ADD_PLUGIN(ResourceSpawner, ignition::gui::Plugin) diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index b5097c15fb..7f91596a8c 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -794,7 +794,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) std::chrono::steady_clock::duration dt; dt = t - this->dataPtr->recordStartTime; int64_t sec, nsec; - std::tie(sec, nsec) = ignition::math::durationToSecNsec(dt); + std::tie(sec, nsec) = math::durationToSecNsec(dt); msgs::Time msg; msg.set_sec(sec); msg.set_nsec(nsec); @@ -1259,7 +1259,7 @@ bool IgnRenderer::GeneratePreview(const sdf::Root &_sdf) // Only preview first model sdf::Light light = *(_sdf.Light()); this->dataPtr->spawnPreviewPose = light.RawPose(); - light.SetName(ignition::common::Uuid().String()); + light.SetName(common::Uuid().String()); Entity lightVisualId = this->UniqueId(); if (!lightVisualId) { @@ -1550,8 +1550,8 @@ void IgnRenderer::HandleModelPlacement() this->TerminateSpawnPreview(); math::Pose3d modelPose = this->dataPtr->spawnPreviewPose; - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error creating model" << std::endl; @@ -1665,7 +1665,7 @@ double IgnRenderer::SnapValue( ///////////////////////////////////////////////// void IgnRenderer::SnapPoint( - ignition::math::Vector3d &_point, math::Vector3d &_snapVals, + math::Vector3d &_point, math::Vector3d &_snapVals, double _sensitivity) const { if (_snapVals.X() <= 0 || _snapVals.Y() <= 0 || _snapVals.Z() <= 0) @@ -1772,7 +1772,7 @@ void IgnRenderer::HandleMouseTransformControl() // check if the visual is an axis in the gizmo visual math::Vector3d axis = this->dataPtr->transformControl.AxisById(visual->Id()); - if (axis != ignition::math::Vector3d::Zero) + if (axis != math::Vector3d::Zero) { // start the transform process this->dataPtr->transformControl.SetActiveAxis(axis); @@ -1790,14 +1790,14 @@ void IgnRenderer::HandleMouseTransformControl() { if (this->dataPtr->transformControl.Node()) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error setting pose" << std::endl; }; rendering::NodePtr node = this->dataPtr->transformControl.Node(); - ignition::msgs::Pose req; + msgs::Pose req; req.set_name(node->Name()); msgs::Set(req.mutable_position(), node->WorldPosition()); msgs::Set(req.mutable_orientation(), node->WorldRotation()); @@ -1840,7 +1840,7 @@ void IgnRenderer::HandleMouseTransformControl() // check if the visual is an axis in the gizmo visual math::Vector3d axis = this->dataPtr->transformControl.AxisById(visual->Id()); - if (axis == ignition::math::Vector3d::Zero) + if (axis == math::Vector3d::Zero) { auto topVis = this->dataPtr->renderUtil.SceneManager().TopLevelVisual(visual); @@ -1908,7 +1908,7 @@ void IgnRenderer::HandleMouseTransformControl() this->dataPtr->startWorldPos = target->WorldPosition(); } - ignition::math::Vector3d worldPos = + math::Vector3d worldPos = target->WorldPosition(); math::Vector3d distance = this->dataPtr->transformControl.TranslationFrom2d(axis, start, end); @@ -2060,7 +2060,7 @@ void IgnRenderer::HandleMouseViewControl() // unset the target on release (by setting to inf) else if (this->dataPtr->mouseEvent.Type() == common::MouseEvent::RELEASE) { - this->dataPtr->target = ignition::math::INF_D; + this->dataPtr->target = math::INF_D; } // Pan with left button @@ -2532,7 +2532,7 @@ math::Vector3d IgnRenderer::ScreenToPlane( this->dataPtr->rayQuery->SetFromCamera( this->dataPtr->camera, math::Vector2d(nx, ny)); - ignition::math::Planed plane(ignition::math::Vector3d(0, 0, 1), 0); + math::Planed plane(math::Vector3d(0, 0, 1), 0); math::Vector3d origin = this->dataPtr->rayQuery->Origin(); math::Vector3d direction = this->dataPtr->rayQuery->Direction(); @@ -2716,7 +2716,7 @@ void TextureNode::PrepareNode() newId, sz, QQuickWindow::TextureIsOpaque); #else // TODO(anyone) Use createTextureFromNativeObject - // https://github.com/ignitionrobotics/ign-gui/issues/113 + // https://github.com/gazebosim/gz-gui/issues/113 #ifndef _WIN32 # pragma GCC diagnostic push # pragma GCC diagnostic ignored "-Wdeprecated-declarations" @@ -3536,8 +3536,8 @@ void Scene3D::OnDropped(const QString &_drop, int _mouseX, int _mouseY) return; } - std::function cb = - [](const ignition::msgs::Boolean &_res, const bool _result) + std::function cb = + [](const msgs::Boolean &_res, const bool _result) { if (!_result || !_res.data()) ignerr << "Error creating dropped entity." << std::endl; @@ -3679,7 +3679,7 @@ bool Scene3D::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::EntitiesSelected::kType) + gui::events::EntitiesSelected::kType) { auto selectedEvent = reinterpret_cast( @@ -3713,7 +3713,7 @@ bool Scene3D::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::DeselectAllEntities::kType) + gui::events::DeselectAllEntities::kType) { auto deselectEvent = reinterpret_cast( @@ -3967,7 +3967,7 @@ void RenderWindowItem::SetVisibilityMask(uint32_t _mask) } ///////////////////////////////////////////////// -void RenderWindowItem::OnHovered(const ignition::math::Vector2i &_hoverPos) +void RenderWindowItem::OnHovered(const math::Vector2i &_hoverPos) { this->dataPtr->renderThread->ignRenderer.NewHoverEvent(_hoverPos); } @@ -4086,5 +4086,5 @@ void RenderWindowItem::HandleKeyRelease(QKeyEvent *_e) // // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::Scene3D, +IGNITION_ADD_PLUGIN(gazebo::Scene3D, ignition::gui::Plugin) diff --git a/src/gui/plugins/shapes/Shapes.cc b/src/gui/plugins/shapes/Shapes.cc index 2cd0108237..3e5ca46c7a 100644 --- a/src/gui/plugins/shapes/Shapes.cc +++ b/src/gui/plugins/shapes/Shapes.cc @@ -81,5 +81,5 @@ void Shapes::OnMode(const QString &_mode) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::Shapes, +IGNITION_ADD_PLUGIN(Shapes, ignition::gui::Plugin) diff --git a/src/gui/plugins/transform_control/TransformControl.cc b/src/gui/plugins/transform_control/TransformControl.cc index 54215f8304..b2cb21bbc4 100644 --- a/src/gui/plugins/transform_control/TransformControl.cc +++ b/src/gui/plugins/transform_control/TransformControl.cc @@ -258,14 +258,14 @@ void TransformControl::OnMode(const QString &_mode) // Legacy behaviour: send request to GzScene3D if (this->dataPtr->legacy) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error setting transform mode" << std::endl; }; - ignition::msgs::StringMsg req; + msgs::StringMsg req; req.set_data(modeStr); this->dataPtr->node.Request(this->dataPtr->service, req, cb); } @@ -284,7 +284,7 @@ void TransformControl::OnMode(const QString &_mode) else ignerr << "Unknown transform mode: [" << modeStr << "]" << std::endl; - ignition::gazebo::gui::events::TransformControlModeActive + gazebo::gui::events::TransformControlModeActive transformControlModeActive(this->dataPtr->transformMode); ignition::gui::App()->sendEvent( ignition::gui::App()->findChild(), @@ -1017,5 +1017,5 @@ void TransformControlPrivate::SnapPoint( } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::TransformControl, +IGNITION_ADD_PLUGIN(TransformControl, ignition::gui::Plugin) diff --git a/src/gui/plugins/video_recorder/VideoRecorder.cc b/src/gui/plugins/video_recorder/VideoRecorder.cc index 1eb9b3e69a..0e88285286 100644 --- a/src/gui/plugins/video_recorder/VideoRecorder.cc +++ b/src/gui/plugins/video_recorder/VideoRecorder.cc @@ -367,7 +367,7 @@ void VideoRecorder::LoadConfig(const tinyxml2::XMLElement * _pluginElem) ///////////////////////////////////////////////// bool VideoRecorder::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gui::events::Render::kType) { this->dataPtr->OnRender(); } @@ -386,13 +386,13 @@ void VideoRecorder::OnStart(const QString &_format) if (this->dataPtr->legacy) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error sending video record start request" << std::endl; }; - ignition::msgs::VideoRecord req; + msgs::VideoRecord req; req.set_start(this->dataPtr->recordVideo); req.set_format(this->dataPtr->format); req.set_save_filename(this->dataPtr->filename); @@ -408,14 +408,14 @@ void VideoRecorder::OnStop() if (this->dataPtr->legacy) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error sending video record stop request" << std::endl; }; - ignition::msgs::VideoRecord req; + msgs::VideoRecord req; req.set_stop(true); this->dataPtr->node.Request(this->dataPtr->service, req, cb); } @@ -462,5 +462,5 @@ void VideoRecorder::OnCancel() } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::VideoRecorder, +IGNITION_ADD_PLUGIN(VideoRecorder, ignition::gui::Plugin) diff --git a/src/gui/plugins/view_angle/ViewAngle.cc b/src/gui/plugins/view_angle/ViewAngle.cc index 8f3b34f431..0e9fa5797d 100644 --- a/src/gui/plugins/view_angle/ViewAngle.cc +++ b/src/gui/plugins/view_angle/ViewAngle.cc @@ -463,5 +463,5 @@ bool ViewAnglePrivate::UpdateQtCamClipDist() } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::ViewAngle, +IGNITION_ADD_PLUGIN(ViewAngle, ignition::gui::Plugin) diff --git a/src/ign.cc b/src/ign.cc index 76344cf872..c846aacece 100644 --- a/src/ign.cc +++ b/src/ign.cc @@ -56,7 +56,7 @@ extern "C" void cmdVerbosity( const char *_verbosity) { int verbosity = std::atoi(_verbosity); - ignition::common::Console::SetVerbosity(verbosity); + common::Console::SetVerbosity(verbosity); // SDFormat only has 2 levels: quiet / loud. Let sim users suppress all SDF // console output with zero verbosity. @@ -78,17 +78,17 @@ extern "C" const char *findFuelResource( { std::string path; std::string worldPath; - ignition::fuel_tools::FuelClient fuelClient; + fuel_tools::FuelClient fuelClient; // Attempt to find cached copy, and then attempt download - if (fuelClient.CachedWorld(ignition::common::URI(_pathToResource), path)) + if (fuelClient.CachedWorld(common::URI(_pathToResource), path)) { ignmsg << "Cached world found." << std::endl; worldPath = path; } // cppcheck-suppress syntaxError - else if (ignition::fuel_tools::Result result = - fuelClient.DownloadWorld(ignition::common::URI(_pathToResource), path); + else if (fuel_tools::Result result = + fuelClient.DownloadWorld(common::URI(_pathToResource), path); result) { ignmsg << "Successfully downloaded world from fuel." << std::endl; @@ -101,20 +101,20 @@ extern "C" const char *findFuelResource( return ""; } - if (!ignition::common::exists(worldPath)) + if (!common::exists(worldPath)) return ""; // Find the first sdf file in the world path for now, the later intention is // to load an optional world config file first and if that does not exist, // continue to load the first sdf file found as done below - for (ignition::common::DirIter file(worldPath); - file != ignition::common::DirIter(); ++file) + for (common::DirIter file(worldPath); + file != common::DirIter(); ++file) { std::string current(*file); - if (ignition::common::isFile(current)) + if (common::isFile(current)) { - std::string fileName = ignition::common::basename(current); + std::string fileName = common::basename(current); std::string::size_type fileExtensionIndex = fileName.rfind("."); std::string fileExtension = fileName.substr(fileExtensionIndex + 1); @@ -138,7 +138,7 @@ extern "C" int runServer(const char *_sdfString, int _headless, float _recordPeriod) { std::string startingWorldPath{""}; - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; // Lock until the starting world is received from Gui if (_waitGui == 1) @@ -173,7 +173,7 @@ extern "C" int runServer(const char *_sdfString, // Path for compressed log, used to check for duplicates std::string cmpPath = std::string(recordPathMod); - if (!std::string(1, cmpPath.back()).compare(ignition::common::separator(""))) + if (!std::string(1, cmpPath.back()).compare(common::separator(""))) { // Remove the separator at end of path cmpPath = cmpPath.substr(0, cmpPath.length() - 1); @@ -207,7 +207,7 @@ extern "C" int runServer(const char *_sdfString, // Update compressed file path to name of recording directory path cmpPath = std::string(recordPathMod); - if (!std::string(1, cmpPath.back()).compare(ignition::common::separator( + if (!std::string(1, cmpPath.back()).compare(common::separator( ""))) { // Remove the separator at end of path @@ -216,8 +216,8 @@ extern "C" int runServer(const char *_sdfString, cmpPath += ".zip"; // Check if path or compressed file with same prefix exists - if (ignition::common::exists(recordPathMod) || - ignition::common::exists(cmpPath)) + if (common::exists(recordPathMod) || + common::exists(cmpPath)) { // Overwrite if flag specified if (_logOverwrite > 0) @@ -225,15 +225,15 @@ extern "C" int runServer(const char *_sdfString, bool recordMsg = false; bool cmpMsg = false; // Remove files before initializing console log files on top of them - if (ignition::common::exists(recordPathMod)) + if (common::exists(recordPathMod)) { recordMsg = true; - ignition::common::removeAll(recordPathMod); + common::removeAll(recordPathMod); } - if (ignition::common::exists(cmpPath)) + if (common::exists(cmpPath)) { cmpMsg = true; - ignition::common::removeFile(cmpPath); + common::removeFile(cmpPath); } // Create log file before printing any messages so they can be logged @@ -260,7 +260,7 @@ extern "C" int runServer(const char *_sdfString, { // Remove the separator at end of path if (!std::string(1, recordPathMod.back()).compare( - ignition::common::separator(""))) + common::separator(""))) { recordPathMod = recordPathMod.substr(0, recordPathMod.length() - 1); @@ -271,8 +271,8 @@ extern "C" int runServer(const char *_sdfString, // Keep renaming until path does not exist for both directory and // compressed file - while (ignition::common::exists(recordPathMod) || - ignition::common::exists(cmpPath)) + while (common::exists(recordPathMod) || + common::exists(cmpPath)) { recordPathMod = recordOrigPrefix + "(" + std::to_string(count++) + ")"; @@ -280,7 +280,7 @@ extern "C" int runServer(const char *_sdfString, cmpPath = std::string(recordPathMod); // Remove the separator at end of path if (!std::string(1, cmpPath.back()).compare( - ignition::common::separator(""))) + common::separator(""))) { cmpPath = cmpPath.substr(0, cmpPath.length() - 1); } @@ -312,7 +312,7 @@ extern "C" int runServer(const char *_sdfString, } serverConfig.SetLogRecordPath(recordPathMod); - std::vector topics = ignition::common::split( + std::vector topics = common::split( _recordTopics, ":"); for (const std::string &topic : topics) { @@ -379,7 +379,7 @@ extern "C" int runServer(const char *_sdfString, else { ignmsg << "Playing back states" << _playback << std::endl; - serverConfig.SetLogPlaybackPath(ignition::common::absPath( + serverConfig.SetLogPlaybackPath(common::absPath( std::string(_playback))); } } @@ -402,7 +402,7 @@ extern "C" int runServer(const char *_sdfString, } // Create the Gazebo server - ignition::gazebo::Server server(serverConfig); + gazebo::Server server(serverConfig); // Run the server server.Run(true, _iterations, _run == 0); @@ -426,6 +426,6 @@ extern "C" int runGui(const char *_guiConfig, const char *_file, int _waitGui, // be converted to a const char *. The const cast is here to prevent a warning // since we do need to pass a char* to runGui char *argv = const_cast("ign-gazebo-gui"); - return ignition::gazebo::gui::runGui( + return gazebo::gui::runGui( argc, &argv, _guiConfig, _file, _waitGui, _renderEngine); } diff --git a/src/ign.hh b/src/ign.hh index 18eac3cfc5..58fa40dfed 100644 --- a/src/ign.hh +++ b/src/ign.hh @@ -82,7 +82,7 @@ extern "C" IGNITION_GAZEBO_VISIBLE int runGui(const char *_guiConfig, /// \brief External hook to find or download a fuel world provided a URL. /// \param[in] _pathToResource Path to the fuel world resource, ie, -/// https://staging-fuel.ignitionrobotics.org/1.0/gmas/worlds/ShapesClone +/// https://staging-fuel.gazebosim.org/1.0/gmas/worlds/ShapesClone /// \return C-string containing the path to the local world sdf file extern "C" IGNITION_GAZEBO_VISIBLE const char *findFuelResource( char *_pathToResource); diff --git a/src/ign_TEST.cc b/src/ign_TEST.cc index 397441bed4..29fb643dba 100644 --- a/src/ign_TEST.cc +++ b/src/ign_TEST.cc @@ -21,9 +21,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include "ignition/gazebo/test_config.hh" // NOLINT(build/include) @@ -37,6 +37,11 @@ static const std::string kIgnModelCommand( ///////////////////////////////////////////////// std::string customExecStr(std::string _cmd) { + // Augment the system plugin path. + ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", + ignition::common::joinPaths( + std::string(PROJECT_BINARY_PATH), "lib").c_str()); + _cmd += " 2>&1"; FILE *pipe = popen(_cmd.c_str(), "r"); @@ -100,7 +105,7 @@ TEST(CmdLine, CachedFuelWorld) std::string projectPath = std::string(PROJECT_SOURCE_PATH) + "/test/worlds"; ignition::common::setenv("IGN_FUEL_CACHE_PATH", projectPath.c_str()); std::string cmd = kIgnCommand + " -r -v 4 --iterations 5" + - " https://fuel.ignitionrobotics.org/1.0/OpenRobotics/worlds/Test%20world"; + " https://fuel.gazebosim.org/1.0/OpenRobotics/worlds/Test%20world"; std::cout << "Running command [" << cmd << "]" << std::endl; std::string output = customExecStr(cmd); diff --git a/src/network/NetworkManagerPrimary.cc b/src/network/NetworkManagerPrimary.cc index e9759eb735..f8e51562ce 100644 --- a/src/network/NetworkManagerPrimary.cc +++ b/src/network/NetworkManagerPrimary.cc @@ -212,7 +212,7 @@ bool NetworkManagerPrimary::SecondariesCanStep() const // TODO(anyone) Ideally we'd check the number of connections against the // number of expected secondaries, but there's no interface for that // on ign-transport yet: - // https://github.com/ignitionrobotics/ign-transport/issues/39 + // https://github.com/gazebosim/gz-transport/issues/39 return this->simStepPub.HasConnections(); } diff --git a/src/network/PeerInfo.cc b/src/network/PeerInfo.cc index e749caff66..b345fde017 100644 --- a/src/network/PeerInfo.cc +++ b/src/network/PeerInfo.cc @@ -24,8 +24,8 @@ using namespace gazebo; ///////////////////////////////////////////////// PeerInfo::PeerInfo(const NetworkRole &_role): - id(ignition::common::Uuid().String()), - hostname(ignition::transport::hostname()), + id(common::Uuid().String()), + hostname(transport::hostname()), role(_role) { } @@ -42,36 +42,36 @@ std::string PeerInfo::Namespace() const } ///////////////////////////////////////////////// -ignition::gazebo::private_msgs::PeerInfo ignition::gazebo::toProto( +private_msgs::PeerInfo gazebo::toProto( const PeerInfo &_info) { - ignition::gazebo::private_msgs::PeerInfo proto; + private_msgs::PeerInfo proto; proto.set_id(_info.id); proto.set_hostname(_info.hostname); switch (_info.role) { case NetworkRole::ReadOnly: - proto.set_role(ignition::gazebo::private_msgs::PeerInfo::READ_ONLY); + proto.set_role(private_msgs::PeerInfo::READ_ONLY); break; case NetworkRole::SimulationPrimary: proto.set_role( - ignition::gazebo::private_msgs::PeerInfo::SIMULATION_PRIMARY); + private_msgs::PeerInfo::SIMULATION_PRIMARY); break; case NetworkRole::SimulationSecondary: proto.set_role( - ignition::gazebo::private_msgs::PeerInfo::SIMULATION_SECONDARY); + private_msgs::PeerInfo::SIMULATION_SECONDARY); break; case NetworkRole::None: default: - proto.set_role(ignition::gazebo::private_msgs::PeerInfo::NONE); + proto.set_role(private_msgs::PeerInfo::NONE); } return proto; } ///////////////////////////////////////////////// -PeerInfo ignition::gazebo::fromProto( - const ignition::gazebo::private_msgs::PeerInfo& _proto) +PeerInfo gazebo::fromProto( + const private_msgs::PeerInfo& _proto) { PeerInfo info; info.id = _proto.id(); @@ -79,16 +79,16 @@ PeerInfo ignition::gazebo::fromProto( switch (_proto.role()) { - case ignition::gazebo::private_msgs::PeerInfo::READ_ONLY: + case private_msgs::PeerInfo::READ_ONLY: info.role = NetworkRole::ReadOnly; break; - case ignition::gazebo::private_msgs::PeerInfo::SIMULATION_PRIMARY: + case private_msgs::PeerInfo::SIMULATION_PRIMARY: info.role = NetworkRole::SimulationPrimary; break; - case ignition::gazebo::private_msgs::PeerInfo::SIMULATION_SECONDARY: + case private_msgs::PeerInfo::SIMULATION_SECONDARY: info.role = NetworkRole::SimulationSecondary; break; - case ignition::gazebo::private_msgs::PeerInfo::NONE: + case private_msgs::PeerInfo::NONE: default: info.role = NetworkRole::None; break; diff --git a/src/network/PeerTracker.cc b/src/network/PeerTracker.cc index f4271fac98..e10a785e84 100644 --- a/src/network/PeerTracker.cc +++ b/src/network/PeerTracker.cc @@ -26,7 +26,7 @@ using namespace gazebo; PeerTracker::PeerTracker( PeerInfo _info, EventManager *_eventMgr, - const ignition::transport::NodeOptions &_options): + const transport::NodeOptions &_options): info(std::move(_info)), eventMgr(_eventMgr), node(_options) diff --git a/src/rendering/MarkerManager.cc b/src/rendering/MarkerManager.cc index 736815b45b..6ecf8af556 100644 --- a/src/rendering/MarkerManager.cc +++ b/src/rendering/MarkerManager.cc @@ -42,50 +42,50 @@ class ignition::gazebo::MarkerManagerPrivate /// \brief Processes a marker message. /// \param[in] _msg The message data. /// \return True if the marker was processed successfully. - public: bool ProcessMarkerMsg(const ignition::msgs::Marker &_msg); + public: bool ProcessMarkerMsg(const msgs::Marker &_msg); /// \brief Converts an ignition msg render type to ignition rendering /// \param[in] _msg The message data /// \return Converted rendering type, if any. - public: ignition::rendering::MarkerType MsgToType( - const ignition::msgs::Marker &_msg); + public: rendering::MarkerType MsgToType( + const msgs::Marker &_msg); /// \brief Converts an ignition msg material to ignition rendering // material. // \param[in] _msg The message data. // \return Converted rendering material, if any. public: rendering::MaterialPtr MsgToMaterial( - const ignition::msgs::Marker &_msg); + const msgs::Marker &_msg); /// \brief Updates the markers. public: void Update(); /// \brief Callback that receives marker messages. /// \param[in] _req The marker message. - public: void OnMarkerMsg(const ignition::msgs::Marker &_req); + public: void OnMarkerMsg(const msgs::Marker &_req); /// \brief Callback that receives multiple marker messages. /// \param[in] _req The vector of marker messages /// \param[in] _res Response data /// \return True if the request is received - public: bool OnMarkerMsgArray(const ignition::msgs::Marker_V &_req, - ignition::msgs::Boolean &_res); + public: bool OnMarkerMsgArray(const msgs::Marker_V &_req, + msgs::Boolean &_res); /// \brief Services callback that returns a list of markers. /// \param[out] _rep Service reply /// \return True on success. - public: bool OnList(ignition::msgs::Marker_V &_rep); + public: bool OnList(msgs::Marker_V &_rep); /// \brief Sets Marker from marker message. /// \param[in] _msg The message data. /// \param[out] _markerPtr The message pointer to set. - public: void SetMarker(const ignition::msgs::Marker &_msg, + public: void SetMarker(const msgs::Marker &_msg, const rendering::MarkerPtr &_markerPtr); /// \brief Sets Visual from marker message. /// \param[in] _msg The message data. /// \param[out] _visualPtr The visual pointer to set. - public: void SetVisual(const ignition::msgs::Marker &_msg, + public: void SetVisual(const msgs::Marker &_msg, const rendering::VisualPtr &_visualPtr); /// \brief Sets sim time from time. @@ -100,22 +100,22 @@ class ignition::gazebo::MarkerManagerPrivate /// \brief Map of visuals public: std::map> visuals; + std::map> visuals; /// \brief List of marker message to process. - public: std::list markerMsgs; + public: std::list markerMsgs; /// \brief Pointer to the scene public: rendering::ScenePtr scene; /// \brief Ignition node - public: ignition::transport::Node node; + public: transport::Node node; /// \brief Sim time according to UpdateInfo in RenderUtil public: std::chrono::steady_clock::duration simTime; /// \brief The last marker message received - public: ignition::msgs::Marker msg; + public: msgs::Marker msg; /// \brief Topic name for the marker service public: std::string topicName = "/marker"; @@ -149,7 +149,7 @@ void MarkerManager::Update() } ///////////////////////////////////////////////// -bool MarkerManager::Init(const ignition::rendering::ScenePtr &_scene) +bool MarkerManager::Init(const rendering::ScenePtr &_scene) { if (!_scene) { @@ -229,8 +229,8 @@ void MarkerManagerPrivate::Update() if (it->second->GeometryCount() == 0u) continue; - ignition::rendering::MarkerPtr markerPtr = - std::dynamic_pointer_cast + rendering::MarkerPtr markerPtr = + std::dynamic_pointer_cast (it->second->GeometryByIndex(0u)); if (markerPtr != nullptr) { @@ -263,7 +263,7 @@ void MarkerManagerPrivate::SetSimTime( } ///////////////////////////////////////////////// -void MarkerManagerPrivate::SetVisual(const ignition::msgs::Marker &_msg, +void MarkerManagerPrivate::SetVisual(const msgs::Marker &_msg, const rendering::VisualPtr &_visualPtr) { // Set Visual Scale @@ -302,7 +302,7 @@ void MarkerManagerPrivate::SetVisual(const ignition::msgs::Marker &_msg, } ///////////////////////////////////////////////// -void MarkerManagerPrivate::SetMarker(const ignition::msgs::Marker &_msg, +void MarkerManagerPrivate::SetMarker(const msgs::Marker &_msg, const rendering::MarkerPtr &_markerPtr) { _markerPtr->SetLayer(_msg.layer()); @@ -319,7 +319,7 @@ void MarkerManagerPrivate::SetMarker(const ignition::msgs::Marker &_msg, _markerPtr->SetLifetime(std::chrono::seconds(0)); } // Set Marker Render Type - ignition::rendering::MarkerType markerType = MsgToType(_msg); + rendering::MarkerType markerType = MsgToType(_msg); _markerPtr->SetType(markerType); // Set Marker Material @@ -357,49 +357,49 @@ void MarkerManagerPrivate::SetMarker(const ignition::msgs::Marker &_msg, } ///////////////////////////////////////////////// -ignition::rendering::MarkerType MarkerManagerPrivate::MsgToType( - const ignition::msgs::Marker &_msg) +rendering::MarkerType MarkerManagerPrivate::MsgToType( + const msgs::Marker &_msg) { - ignition::msgs::Marker_Type marker = this->msg.type(); - if (marker != _msg.type() && _msg.type() != ignition::msgs::Marker::NONE) + msgs::Marker_Type marker = this->msg.type(); + if (marker != _msg.type() && _msg.type() != msgs::Marker::NONE) { marker = _msg.type(); this->msg.set_type(_msg.type()); } switch (marker) { - case ignition::msgs::Marker::BOX: - return ignition::rendering::MarkerType::MT_BOX; - case ignition::msgs::Marker::CAPSULE: - return ignition::rendering::MarkerType::MT_CAPSULE; - case ignition::msgs::Marker::CYLINDER: - return ignition::rendering::MarkerType::MT_CYLINDER; - case ignition::msgs::Marker::LINE_STRIP: - return ignition::rendering::MarkerType::MT_LINE_STRIP; - case ignition::msgs::Marker::LINE_LIST: - return ignition::rendering::MarkerType::MT_LINE_LIST; - case ignition::msgs::Marker::POINTS: - return ignition::rendering::MarkerType::MT_POINTS; - case ignition::msgs::Marker::SPHERE: - return ignition::rendering::MarkerType::MT_SPHERE; - case ignition::msgs::Marker::TEXT: - return ignition::rendering::MarkerType::MT_TEXT; - case ignition::msgs::Marker::TRIANGLE_FAN: - return ignition::rendering::MarkerType::MT_TRIANGLE_FAN; - case ignition::msgs::Marker::TRIANGLE_LIST: - return ignition::rendering::MarkerType::MT_TRIANGLE_LIST; - case ignition::msgs::Marker::TRIANGLE_STRIP: - return ignition::rendering::MarkerType::MT_TRIANGLE_STRIP; + case msgs::Marker::BOX: + return rendering::MarkerType::MT_BOX; + case msgs::Marker::CAPSULE: + return rendering::MarkerType::MT_CAPSULE; + case msgs::Marker::CYLINDER: + return rendering::MarkerType::MT_CYLINDER; + case msgs::Marker::LINE_STRIP: + return rendering::MarkerType::MT_LINE_STRIP; + case msgs::Marker::LINE_LIST: + return rendering::MarkerType::MT_LINE_LIST; + case msgs::Marker::POINTS: + return rendering::MarkerType::MT_POINTS; + case msgs::Marker::SPHERE: + return rendering::MarkerType::MT_SPHERE; + case msgs::Marker::TEXT: + return rendering::MarkerType::MT_TEXT; + case msgs::Marker::TRIANGLE_FAN: + return rendering::MarkerType::MT_TRIANGLE_FAN; + case msgs::Marker::TRIANGLE_LIST: + return rendering::MarkerType::MT_TRIANGLE_LIST; + case msgs::Marker::TRIANGLE_STRIP: + return rendering::MarkerType::MT_TRIANGLE_STRIP; default: ignerr << "Unable to create marker of type[" << _msg.type() << "]\n"; break; } - return ignition::rendering::MarkerType::MT_NONE; + return rendering::MarkerType::MT_NONE; } ///////////////////////////////////////////////// rendering::MaterialPtr MarkerManagerPrivate::MsgToMaterial( - const ignition::msgs::Marker &_msg) + const msgs::Marker &_msg) { rendering::MaterialPtr material = this->scene->CreateMaterial(); @@ -433,7 +433,7 @@ rendering::MaterialPtr MarkerManagerPrivate::MsgToMaterial( } ////////////////////////////////////////////////// -bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) +bool MarkerManagerPrivate::ProcessMarkerMsg(const msgs::Marker &_msg) { // Get the namespace, if it exists. Otherwise, use the global namespace std::string ns; @@ -453,14 +453,14 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) // Otherwise generate unique id else { - id = ignition::math::Rand::IntUniform(0, ignition::math::MAX_I32); + id = math::Rand::IntUniform(0, math::MAX_I32); // Make sure it's unique if namespace is given if (nsIter != this->visuals.end()) { while (nsIter->second.find(id) != nsIter->second.end()) - id = ignition::math::Rand::IntUniform(ignition::math::MIN_UI32, - ignition::math::MAX_UI32); + id = math::Rand::IntUniform(math::MIN_UI32, + math::MAX_UI32); } } @@ -470,7 +470,7 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) visualIter = nsIter->second.find(id); // Add/modify a marker - if (_msg.action() == ignition::msgs::Marker::ADD_MODIFY) + if (_msg.action() == msgs::Marker::ADD_MODIFY) { // Modify an existing marker, identified by namespace and id if (nsIter != this->visuals.end() && @@ -480,8 +480,8 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) { // TODO(anyone): Update so that multiple markers can // be attached to one visual - ignition::rendering::MarkerPtr markerPtr = - std::dynamic_pointer_cast + rendering::MarkerPtr markerPtr = + std::dynamic_pointer_cast (visualIter->second->GeometryByIndex(0)); visualIter->second->RemoveGeometryByIndex(0); @@ -528,7 +528,7 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) } } // Remove a single marker - else if (_msg.action() == ignition::msgs::Marker::DELETE_MARKER) + else if (_msg.action() == msgs::Marker::DELETE_MARKER) { // Remove the marker if it can be found. if (nsIter != this->visuals.end() && @@ -549,7 +549,7 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) } } // Remove all markers, or all markers in a namespace - else if (_msg.action() == ignition::msgs::Marker::DELETE_ALL) + else if (_msg.action() == msgs::Marker::DELETE_ALL) { // If given namespace doesn't exist if (!ns.empty() && nsIter == this->visuals.end()) @@ -593,7 +593,7 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) ///////////////////////////////////////////////// -bool MarkerManagerPrivate::OnList(ignition::msgs::Marker_V &_rep) +bool MarkerManagerPrivate::OnList(msgs::Marker_V &_rep) { std::lock_guard lock(this->mutex); _rep.clear_marker(); @@ -603,7 +603,7 @@ bool MarkerManagerPrivate::OnList(ignition::msgs::Marker_V &_rep) { for (auto iter : mIter.second) { - ignition::msgs::Marker *markerMsg = _rep.add_marker(); + msgs::Marker *markerMsg = _rep.add_marker(); markerMsg->set_ns(mIter.first); markerMsg->set_id(iter.first); } @@ -613,7 +613,7 @@ bool MarkerManagerPrivate::OnList(ignition::msgs::Marker_V &_rep) } ///////////////////////////////////////////////// -void MarkerManagerPrivate::OnMarkerMsg(const ignition::msgs::Marker &_req) +void MarkerManagerPrivate::OnMarkerMsg(const msgs::Marker &_req) { std::lock_guard lock(this->mutex); this->markerMsgs.push_back(_req); @@ -621,7 +621,7 @@ void MarkerManagerPrivate::OnMarkerMsg(const ignition::msgs::Marker &_req) ///////////////////////////////////////////////// bool MarkerManagerPrivate::OnMarkerMsgArray( - const ignition::msgs::Marker_V&_req, ignition::msgs::Boolean &_res) + const msgs::Marker_V&_req, msgs::Boolean &_res) { std::lock_guard lock(this->mutex); std::copy(_req.marker().begin(), _req.marker().end(), diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 6f4ef07941..d9d8d8b4a3 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -228,7 +228,7 @@ class ignition::gazebo::RenderUtilPrivate public: MarkerManager markerManager; /// \brief Pointer to rendering engine. - public: ignition::rendering::RenderEngine *engine{nullptr}; + public: rendering::RenderEngine *engine{nullptr}; /// \brief rendering scene to be managed by the scene manager and used to /// generate sensor data @@ -2341,6 +2341,14 @@ void RenderUtilPrivate::RemoveRenderingEntities( const EntityComponentManager &_ecm, const UpdateInfo &_info) { IGN_PROFILE("RenderUtilPrivate::RemoveRenderingEntities"); + _ecm.EachRemoved( + [&](const Entity &_entity, const components::Actor *)->bool + { + this->removeEntities[_entity] = _info.iterations; + this->entityPoses.erase(_entity); + this->actorTransforms.erase(_entity); + return true; + }); _ecm.EachRemoved( [&](const Entity &_entity, const components::Model *)->bool { @@ -2499,7 +2507,7 @@ bool RenderUtil::HeadlessRendering() const ///////////////////////////////////////////////// void RenderUtil::InitRenderEnginePluginPaths() { - ignition::common::SystemPaths pluginPath; + common::SystemPaths pluginPath; pluginPath.SetPluginPathEnv(kRenderPluginPathEnv); rendering::setPluginPaths(pluginPath.PluginPaths()); } diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index 3b53f5b9b0..48e1983cf4 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -677,8 +677,8 @@ rendering::GeometryPtr SceneManager::LoadGeometry(const sdf::Geometry &_geom, descriptor.subMeshName = _geom.MeshShape()->Submesh(); descriptor.centerSubMesh = _geom.MeshShape()->CenterSubmesh(); - ignition::common::MeshManager *meshManager = - ignition::common::MeshManager::Instance(); + common::MeshManager *meshManager = + common::MeshManager::Instance(); descriptor.mesh = meshManager->Load(descriptor.meshName); geom = this->dataPtr->scene->CreateMesh(descriptor); scale = _geom.MeshShape()->Scale(); @@ -745,7 +745,7 @@ rendering::GeometryPtr SceneManager::LoadGeometry(const sdf::Geometry &_geom, std::string name("POLYLINE_" + common::Uuid().String()); - auto meshManager = ignition::common::MeshManager::Instance(); + auto meshManager = common::MeshManager::Instance(); meshManager->CreateExtrudedPolyline(name, vertices, _geom.PolylineShape()[0].Height()); @@ -1950,6 +1950,28 @@ void SceneManager::RemoveEntity(Entity _id) if (!this->dataPtr->scene) return; + { + auto it = this->dataPtr->actors.find(_id); + if (it != this->dataPtr->actors.end()) + { + this->dataPtr->actors.erase(it); + } + } + { + auto it = this->dataPtr->actorTrajectories.find(_id); + if (it != this->dataPtr->actorTrajectories.end()) + { + this->dataPtr->actorTrajectories.erase(it); + } + } + { + auto it = this->dataPtr->actorSkeletons.find(_id); + if (it != this->dataPtr->actorSkeletons.end()) + { + this->dataPtr->actorSkeletons.erase(it); + } + } + { auto it = this->dataPtr->visuals.find(_id); if (it != this->dataPtr->visuals.end()) diff --git a/src/systems/ackermann_steering/AckermannSteering.cc b/src/systems/ackermann_steering/AckermannSteering.cc index d2dc5f39e7..34d22ab1a7 100644 --- a/src/systems/ackermann_steering/AckermannSteering.cc +++ b/src/systems/ackermann_steering/AckermannSteering.cc @@ -58,21 +58,21 @@ class ignition::gazebo::systems::AckermannSteeringPrivate { /// \brief Callback for velocity subscription /// \param[in] _msg Velocity message - public: void OnCmdVel(const ignition::msgs::Twist &_msg); + public: void OnCmdVel(const msgs::Twist &_msg); /// \brief Update odometry and publish an odometry message. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateOdometry(const UpdateInfo &_info, + const EntityComponentManager &_ecm); /// \brief Update the linear and angular velocities. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateVelocity(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateVelocity(const UpdateInfo &_info, + const EntityComponentManager &_ecm); /// \brief Ignition communication node. public: transport::Node node; @@ -165,10 +165,10 @@ class ignition::gazebo::systems::AckermannSteeringPrivate public: std::chrono::steady_clock::duration lastOdomTime{0}; /// \brief Linear velocity limiter. - public: std::unique_ptr limiterLin; + public: std::unique_ptr limiterLin; /// \brief Angular velocity limiter. - public: std::unique_ptr limiterAng; + public: std::unique_ptr limiterAng; /// \brief Previous control command. public: Commands last0Cmd; @@ -260,8 +260,8 @@ void AckermannSteering::Configure(const Entity &_entity, this->dataPtr->wheelRadius).first; // Instantiate the speed limiters. - this->dataPtr->limiterLin = std::make_unique(); - this->dataPtr->limiterAng = std::make_unique(); + this->dataPtr->limiterLin = std::make_unique(); + this->dataPtr->limiterAng = std::make_unique(); // Parse speed limiter parameters. if (_sdf->HasElement("min_velocity")) @@ -375,8 +375,8 @@ void AckermannSteering::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void AckermannSteering::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void AckermannSteering::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("AckermannSteering::PreUpdate"); @@ -587,8 +587,8 @@ void AckermannSteering::PostUpdate(const UpdateInfo &_info, ////////////////////////////////////////////////// void AckermannSteeringPrivate::UpdateOdometry( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + const EntityComponentManager &_ecm) { IGN_PROFILE("AckermannSteering::UpdateOdometry"); // Initialize, if not already initialized. @@ -690,7 +690,7 @@ void AckermannSteeringPrivate::UpdateOdometry( // Construct the Pose_V/tf message and publish it. msgs::Pose_V tfMsg; - ignition::msgs::Pose *tfMsgPose = tfMsg.add_pose(); + msgs::Pose *tfMsgPose = tfMsg.add_pose(); tfMsgPose->mutable_header()->CopyFrom(*msg.mutable_header()); tfMsgPose->mutable_position()->CopyFrom(msg.mutable_pose()->position()); tfMsgPose->mutable_orientation()->CopyFrom(msg.mutable_pose()->orientation()); @@ -702,8 +702,8 @@ void AckermannSteeringPrivate::UpdateOdometry( ////////////////////////////////////////////////// void AckermannSteeringPrivate::UpdateVelocity( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + const EntityComponentManager &_ecm) { IGN_PROFILE("AckermannSteering::UpdateVelocity"); @@ -788,7 +788,7 @@ void AckermannSteeringPrivate::OnCmdVel(const msgs::Twist &_msg) } IGNITION_ADD_PLUGIN(AckermannSteering, - ignition::gazebo::System, + System, AckermannSteering::ISystemConfigure, AckermannSteering::ISystemPreUpdate, AckermannSteering::ISystemPostUpdate) diff --git a/src/systems/altimeter/Altimeter.cc b/src/systems/altimeter/Altimeter.cc index 3152c0c7e7..18c83458ee 100644 --- a/src/systems/altimeter/Altimeter.cc +++ b/src/systems/altimeter/Altimeter.cc @@ -261,7 +261,6 @@ void AltimeterPrivate::UpdateAltimeters(const EntityComponentManager &_ecm) auto it = this->entitySensorMap.find(_entity); if (it != this->entitySensorMap.end()) { - math::Vector3d linearVel; math::Pose3d worldPose = _worldPose->Data(); it->second->SetPosition(worldPose.Pos().Z()); it->second->SetVerticalVelocity(_worldLinearVel->Data().Z()); diff --git a/src/systems/apply_joint_force/ApplyJointForce.cc b/src/systems/apply_joint_force/ApplyJointForce.cc index 042f585565..ab0db7b485 100644 --- a/src/systems/apply_joint_force/ApplyJointForce.cc +++ b/src/systems/apply_joint_force/ApplyJointForce.cc @@ -35,7 +35,7 @@ class ignition::gazebo::systems::ApplyJointForcePrivate { /// \brief Callback for joint force subscription /// \param[in] _msg Joint force message - public: void OnCmdForce(const ignition::msgs::Double &_msg); + public: void OnCmdForce(const msgs::Double &_msg); /// \brief Ignition communication node. public: transport::Node node; @@ -111,8 +111,8 @@ void ApplyJointForce::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void ApplyJointForce::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void ApplyJointForce::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("ApplyJointForce::PreUpdate"); @@ -164,7 +164,7 @@ void ApplyJointForcePrivate::OnCmdForce(const msgs::Double &_msg) } IGNITION_ADD_PLUGIN(ApplyJointForce, - ignition::gazebo::System, + System, ApplyJointForce::ISystemConfigure, ApplyJointForce::ISystemPreUpdate) diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.cc b/src/systems/battery_plugin/LinearBatteryPlugin.cc index 1b484783cf..bb9562fe7f 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.cc +++ b/src/systems/battery_plugin/LinearBatteryPlugin.cc @@ -63,11 +63,11 @@ class ignition::gazebo::systems::LinearBatteryPluginPrivate /// \brief Callback executed to start recharging. /// \param[in] _req This value should be true. - public: void OnEnableRecharge(const ignition::msgs::Boolean &_req); + public: void OnEnableRecharge(const msgs::Boolean &_req); /// \brief Callback executed to stop recharging. /// \param[in] _req This value should be true. - public: void OnDisableRecharge(const ignition::msgs::Boolean &_req); + public: void OnDisableRecharge(const msgs::Boolean &_req); /// \brief Callback connected to additional topics that can start battery /// draining. @@ -411,7 +411,7 @@ double LinearBatteryPluginPrivate::StateOfCharge() const ////////////////////////////////////////////////// void LinearBatteryPluginPrivate::OnEnableRecharge( - const ignition::msgs::Boolean &/*_req*/) + const msgs::Boolean &/*_req*/) { igndbg << "Request for start charging received" << std::endl; this->startCharging = true; @@ -419,7 +419,7 @@ void LinearBatteryPluginPrivate::OnEnableRecharge( ////////////////////////////////////////////////// void LinearBatteryPluginPrivate::OnDisableRecharge( - const ignition::msgs::Boolean &/*_req*/) + const msgs::Boolean &/*_req*/) { igndbg << "Request for stop charging received" << std::endl; this->startCharging = false; @@ -434,8 +434,8 @@ void LinearBatteryPluginPrivate::OnBatteryDrainingMsg( ////////////////////////////////////////////////// void LinearBatteryPlugin::PreUpdate( - const ignition::gazebo::UpdateInfo &/*_info*/, - ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &/*_info*/, + EntityComponentManager &_ecm) { IGN_PROFILE("LinearBatteryPlugin::PreUpdate"); @@ -670,7 +670,7 @@ double LinearBatteryPlugin::OnUpdateVoltage( } IGNITION_ADD_PLUGIN(LinearBatteryPlugin, - ignition::gazebo::System, + System, LinearBatteryPlugin::ISystemConfigure, LinearBatteryPlugin::ISystemPreUpdate, LinearBatteryPlugin::ISystemUpdate, diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.hh b/src/systems/battery_plugin/LinearBatteryPlugin.hh index e98460a15b..71782ddf64 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.hh +++ b/src/systems/battery_plugin/LinearBatteryPlugin.hh @@ -57,7 +57,7 @@ namespace systems /// - `` Hours taken to fully charge the battery. /// (Required if `` is set to true) /// - `` True to change the battery behavior to fix some issues - /// described in https://github.com/ignitionrobotics/ign-gazebo/issues/225. + /// described in https://github.com/gazebosim/gz-sim/issues/225. /// - `` A topic that is used to start battery /// discharge. Any message on the specified topic will cause the batter to /// start draining. This element can be specified multiple times if diff --git a/src/systems/breadcrumbs/Breadcrumbs.cc b/src/systems/breadcrumbs/Breadcrumbs.cc index c6484e5551..a89567142b 100644 --- a/src/systems/breadcrumbs/Breadcrumbs.cc +++ b/src/systems/breadcrumbs/Breadcrumbs.cc @@ -172,8 +172,8 @@ void Breadcrumbs::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void Breadcrumbs::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void Breadcrumbs::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("Breadcrumbs::PreUpdate"); @@ -434,7 +434,7 @@ void Breadcrumbs::OnDeploy(const msgs::Empty &) } IGNITION_ADD_PLUGIN(Breadcrumbs, - ignition::gazebo::System, + System, Breadcrumbs::ISystemConfigure, Breadcrumbs::ISystemPreUpdate) diff --git a/src/systems/buoyancy/Buoyancy.cc b/src/systems/buoyancy/Buoyancy.cc index eaa50b1aa7..c906ccf334 100644 --- a/src/systems/buoyancy/Buoyancy.cc +++ b/src/systems/buoyancy/Buoyancy.cc @@ -337,8 +337,8 @@ void Buoyancy::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void Buoyancy::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("Buoyancy::PreUpdate"); const components::Gravity *gravity = _ecm.Component( @@ -376,8 +376,8 @@ void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info, _entity, components::Collision()); double volumeSum = 0; - ignition::math::Vector3d weightedPosInLinkSum = - ignition::math::Vector3d::Zero; + math::Vector3d weightedPosInLinkSum = + math::Vector3d::Zero; // Compute the volume of the link by iterating over all the collision // elements and storing each geometry's volume. @@ -581,7 +581,7 @@ bool Buoyancy::IsEnabled(Entity _entity, } IGNITION_ADD_PLUGIN(Buoyancy, - ignition::gazebo::System, + System, Buoyancy::ISystemConfigure, Buoyancy::ISystemPreUpdate) diff --git a/src/systems/camera_video_recorder/CameraVideoRecorder.cc b/src/systems/camera_video_recorder/CameraVideoRecorder.cc index 6918036299..013a255a93 100644 --- a/src/systems/camera_video_recorder/CameraVideoRecorder.cc +++ b/src/systems/camera_video_recorder/CameraVideoRecorder.cc @@ -70,7 +70,7 @@ class ignition::gazebo::systems::CameraVideoRecorderPrivate public: std::mutex updateMutex; /// \brief Connection to the post-render event. - public: ignition::common::ConnectionPtr postRenderConn; + public: common::ConnectionPtr postRenderConn; /// \brief Pointer to the event manager public: EventManager *eventMgr = nullptr; @@ -356,7 +356,7 @@ void CameraVideoRecorderPrivate::OnPostRender() std::chrono::steady_clock::duration dt; dt = t - this->recordStartTime; int64_t sec, nsec; - std::tie(sec, nsec) = ignition::math::durationToSecNsec(dt); + std::tie(sec, nsec) = math::durationToSecNsec(dt); msgs::Time msg; msg.set_sec(sec); msg.set_nsec(nsec); @@ -461,7 +461,7 @@ void CameraVideoRecorder::PostUpdate(const UpdateInfo &_info, } IGNITION_ADD_PLUGIN(CameraVideoRecorder, - ignition::gazebo::System, + System, CameraVideoRecorder::ISystemConfigure, CameraVideoRecorder::ISystemPostUpdate) diff --git a/src/systems/camera_video_recorder/CameraVideoRecorder.hh b/src/systems/camera_video_recorder/CameraVideoRecorder.hh index f5f3dc02c1..c905301036 100644 --- a/src/systems/camera_video_recorder/CameraVideoRecorder.hh +++ b/src/systems/camera_video_recorder/CameraVideoRecorder.hh @@ -51,7 +51,7 @@ namespace systems /// /// Video recorder bitrate (bps). The default value is /// 2070000 bps, and the supported type is unsigned int. - class CameraVideoRecorder: + class CameraVideoRecorder final: public System, public ISystemConfigure, public ISystemPostUpdate diff --git a/src/systems/collada_world_exporter/ColladaWorldExporter.cc b/src/systems/collada_world_exporter/ColladaWorldExporter.cc index 66ee000dfa..6cc6aaa301 100644 --- a/src/systems/collada_world_exporter/ColladaWorldExporter.cc +++ b/src/systems/collada_world_exporter/ColladaWorldExporter.cc @@ -85,7 +85,7 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate components::Name, components::Geometry, components::Transparency>( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Visual *, const components::Name *_name, const components::Geometry *_geom, @@ -107,12 +107,12 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate } mat->SetTransparency(_transparency->Data()); - const ignition::common::Mesh *mesh; - std::weak_ptr subm; + const common::Mesh *mesh; + std::weak_ptr subm; math::Vector3d scale; math::Matrix4d matrix(worldPose); - ignition::common::MeshManager *meshManager = - ignition::common::MeshManager::Instance(); + common::MeshManager *meshManager = + common::MeshManager::Instance(); auto addSubmeshFunc = [&](int _matIndex) { diff --git a/src/systems/contact/Contact.cc b/src/systems/contact/Contact.cc index afd1122245..ac5bf96914 100644 --- a/src/systems/contact/Contact.cc +++ b/src/systems/contact/Contact.cc @@ -123,7 +123,7 @@ void ContactSensor::Load(const sdf::ElementPtr &_sdf, const std::string &_topic, } ignmsg << "Contact system publishing on " << this->topic << std::endl; - this->pub = this->node.Advertise(this->topic); + this->pub = this->node.Advertise(this->topic); } ////////////////////////////////////////////////// diff --git a/src/systems/detachable_joint/DetachableJoint.cc b/src/systems/detachable_joint/DetachableJoint.cc index 0946aa9505..7d40dd4786 100644 --- a/src/systems/detachable_joint/DetachableJoint.cc +++ b/src/systems/detachable_joint/DetachableJoint.cc @@ -114,8 +114,8 @@ void DetachableJoint::Configure(const Entity &_entity, ////////////////////////////////////////////////// void DetachableJoint::PreUpdate( - const ignition::gazebo::UpdateInfo &/*_info*/, - ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &/*_info*/, + EntityComponentManager &_ecm) { IGN_PROFILE("DetachableJoint::PreUpdate"); if (this->validConfig && !this->initialized) @@ -190,7 +190,7 @@ void DetachableJoint::OnDetachRequest(const msgs::Empty &) } IGNITION_ADD_PLUGIN(DetachableJoint, - ignition::gazebo::System, + System, DetachableJoint::ISystemConfigure, DetachableJoint::ISystemPreUpdate) diff --git a/src/systems/diff_drive/DiffDrive.cc b/src/systems/diff_drive/DiffDrive.cc index ec8e5a46d2..e869cc5a58 100644 --- a/src/systems/diff_drive/DiffDrive.cc +++ b/src/systems/diff_drive/DiffDrive.cc @@ -59,25 +59,25 @@ class ignition::gazebo::systems::DiffDrivePrivate { /// \brief Callback for velocity subscription /// \param[in] _msg Velocity message - public: void OnCmdVel(const ignition::msgs::Twist &_msg); + public: void OnCmdVel(const msgs::Twist &_msg); /// \brief Callback for enable/disable subscription /// \param[in] _msg Boolean message - public: void OnEnable(const ignition::msgs::Boolean &_msg); + public: void OnEnable(const msgs::Boolean &_msg); /// \brief Update odometry and publish an odometry message. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateOdometry(const UpdateInfo &_info, + const EntityComponentManager &_ecm); /// \brief Update the linear and angular velocities. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateVelocity(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateVelocity(const UpdateInfo &_info, + const EntityComponentManager &_ecm); /// \brief Ignition communication node. public: transport::Node node; @@ -128,10 +128,10 @@ class ignition::gazebo::systems::DiffDrivePrivate public: transport::Node::Publisher tfPub; /// \brief Linear velocity limiter. - public: std::unique_ptr limiterLin; + public: std::unique_ptr limiterLin; /// \brief Angular velocity limiter. - public: std::unique_ptr limiterAng; + public: std::unique_ptr limiterAng; /// \brief Previous control command. public: Commands last0Cmd; @@ -206,8 +206,8 @@ void DiffDrive::Configure(const Entity &_entity, this->dataPtr->wheelRadius).first; // Instantiate the speed limiters. - this->dataPtr->limiterLin = std::make_unique(); - this->dataPtr->limiterAng = std::make_unique(); + this->dataPtr->limiterLin = std::make_unique(); + this->dataPtr->limiterAng = std::make_unique(); // Parse speed limiter parameters. @@ -386,8 +386,8 @@ void DiffDrive::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void DiffDrive::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void DiffDrive::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("DiffDrive::PreUpdate"); @@ -524,8 +524,8 @@ void DiffDrive::PostUpdate(const UpdateInfo &_info, } ////////////////////////////////////////////////// -void DiffDrivePrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) +void DiffDrivePrivate::UpdateOdometry(const UpdateInfo &_info, + const EntityComponentManager &_ecm) { IGN_PROFILE("DiffDrive::UpdateOdometry"); // Initialize, if not already initialized. @@ -608,7 +608,7 @@ void DiffDrivePrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, // Construct the Pose_V/tf message and publish it. msgs::Pose_V tfMsg; - ignition::msgs::Pose *tfMsgPose = tfMsg.add_pose(); + msgs::Pose *tfMsgPose = tfMsg.add_pose(); tfMsgPose->mutable_header()->CopyFrom(*msg.mutable_header()); tfMsgPose->mutable_position()->CopyFrom(msg.mutable_pose()->position()); tfMsgPose->mutable_orientation()->CopyFrom(msg.mutable_pose()->orientation()); @@ -619,8 +619,8 @@ void DiffDrivePrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, } ////////////////////////////////////////////////// -void DiffDrivePrivate::UpdateVelocity(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &/*_ecm*/) +void DiffDrivePrivate::UpdateVelocity(const UpdateInfo &_info, + const EntityComponentManager &/*_ecm*/) { IGN_PROFILE("DiffDrive::UpdateVelocity"); @@ -674,7 +674,7 @@ void DiffDrivePrivate::OnEnable(const msgs::Boolean &_msg) } IGNITION_ADD_PLUGIN(DiffDrive, - ignition::gazebo::System, + System, DiffDrive::ISystemConfigure, DiffDrive::ISystemPreUpdate, DiffDrive::ISystemPostUpdate) diff --git a/src/systems/imu/Imu.cc b/src/systems/imu/Imu.cc index 5afbd67ae0..4494d40cb5 100644 --- a/src/systems/imu/Imu.cc +++ b/src/systems/imu/Imu.cc @@ -53,7 +53,7 @@ class ignition::gazebo::systems::ImuPrivate { /// \brief A map of IMU entity to its IMU sensor. public: std::unordered_map> entitySensorMap; + std::unique_ptr> entitySensorMap; /// \brief Ign-sensors sensor factory for creating sensors public: sensors::SensorFactory sensorFactory; diff --git a/src/systems/joint_controller/JointController.cc b/src/systems/joint_controller/JointController.cc index 3f5a1cdfd1..afd7b481e2 100644 --- a/src/systems/joint_controller/JointController.cc +++ b/src/systems/joint_controller/JointController.cc @@ -39,7 +39,7 @@ class ignition::gazebo::systems::JointControllerPrivate { /// \brief Callback for velocity subscription /// \param[in] _msg Velocity message - public: void OnCmdVel(const ignition::msgs::Double &_msg); + public: void OnCmdVel(const msgs::Double &_msg); /// \brief Ignition communication node. public: transport::Node node; @@ -61,7 +61,7 @@ class ignition::gazebo::systems::JointControllerPrivate public: bool useForceCommands{false}; /// \brief Velocity PID controller. - public: ignition::math::PID velPid; + public: math::PID velPid; }; ////////////////////////////////////////////////// @@ -173,8 +173,8 @@ void JointController::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void JointController::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void JointController::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("JointController::PreUpdate"); @@ -260,7 +260,7 @@ void JointControllerPrivate::OnCmdVel(const msgs::Double &_msg) } IGNITION_ADD_PLUGIN(JointController, - ignition::gazebo::System, + System, JointController::ISystemConfigure, JointController::ISystemPreUpdate) diff --git a/src/systems/joint_position_controller/JointPositionController.cc b/src/systems/joint_position_controller/JointPositionController.cc index 5f7ca8a8a8..7262ebd466 100644 --- a/src/systems/joint_position_controller/JointPositionController.cc +++ b/src/systems/joint_position_controller/JointPositionController.cc @@ -40,7 +40,7 @@ class ignition::gazebo::systems::JointPositionControllerPrivate { /// \brief Callback for position subscription /// \param[in] _msg Position message - public: void OnCmdPos(const ignition::msgs::Double &_msg); + public: void OnCmdPos(const msgs::Double &_msg); /// \brief Ignition communication node. public: transport::Node node; @@ -61,7 +61,7 @@ class ignition::gazebo::systems::JointPositionControllerPrivate public: Model model{kNullEntity}; /// \brief Position PID controller. - public: ignition::math::PID posPid; + public: math::PID posPid; /// \brief Joint index to be used. public: unsigned int jointIndex = 0u; @@ -218,8 +218,8 @@ void JointPositionController::Configure(const Entity &_entity, ////////////////////////////////////////////////// void JointPositionController::PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("JointPositionController::PreUpdate"); @@ -357,7 +357,7 @@ void JointPositionControllerPrivate::OnCmdPos(const msgs::Double &_msg) } IGNITION_ADD_PLUGIN(JointPositionController, - ignition::gazebo::System, + System, JointPositionController::ISystemConfigure, JointPositionController::ISystemPreUpdate) diff --git a/src/systems/joint_state_publisher/JointStatePublisher.cc b/src/systems/joint_state_publisher/JointStatePublisher.cc index 5a995b9dfd..024b8e3d70 100644 --- a/src/systems/joint_state_publisher/JointStatePublisher.cc +++ b/src/systems/joint_state_publisher/JointStatePublisher.cc @@ -69,7 +69,7 @@ void JointStatePublisher::Configure( while (elem) { std::string jointName = elem->Get(); - gazebo::Entity jointEntity = this->model.JointByName(_ecm, jointName); + Entity jointEntity = this->model.JointByName(_ecm, jointName); if (jointEntity != kNullEntity) { this->CreateComponents(_ecm, jointEntity); @@ -105,7 +105,7 @@ void JointStatePublisher::Configure( ////////////////////////////////////////////////// void JointStatePublisher::CreateComponents(EntityComponentManager &_ecm, - gazebo::Entity _joint) + Entity _joint) { if (this->joints.find(_joint) != this->joints.end()) { @@ -313,7 +313,7 @@ void JointStatePublisher::PostUpdate(const UpdateInfo &_info, } IGNITION_ADD_PLUGIN(JointStatePublisher, - ignition::gazebo::System, + System, JointStatePublisher::ISystemConfigure, JointStatePublisher::ISystemPostUpdate) diff --git a/src/systems/lift_drag/LiftDrag.cc b/src/systems/lift_drag/LiftDrag.cc index d809f2292c..4defe386a9 100644 --- a/src/systems/lift_drag/LiftDrag.cc +++ b/src/systems/lift_drag/LiftDrag.cc @@ -106,16 +106,16 @@ class ignition::gazebo::systems::LiftDragPrivate /// \brief center of pressure in link local coordinates with respect to the /// link's center of mass - public: ignition::math::Vector3d cp = math::Vector3d::Zero; + public: math::Vector3d cp = math::Vector3d::Zero; /// \brief Normally, this is taken as a direction parallel to the chord /// of the airfoil in zero angle of attack forward flight. - public: ignition::math::Vector3d forward = math::Vector3d::UnitX; + public: math::Vector3d forward = math::Vector3d::UnitX; /// \brief A vector in the lift/drag plane, perpendicular to the forward /// vector. Inflow velocity orthogonal to forward and upward vectors /// is considered flow in the wing sweep direction. - public: ignition::math::Vector3d upward = math::Vector3d::UnitZ; + public: math::Vector3d upward = math::Vector3d::UnitZ; /// \brief how much to change CL per radian of control surface joint /// value. @@ -154,15 +154,15 @@ void LiftDragPrivate::Load(const EntityComponentManager &_ecm, this->radialSymmetry).first; this->area = _sdf->Get("area", this->area).first; this->alpha0 = _sdf->Get("a0", this->alpha0).first; - this->cp = _sdf->Get("cp", this->cp).first; + this->cp = _sdf->Get("cp", this->cp).first; // blade forward (-drag) direction in link frame this->forward = - _sdf->Get("forward", this->forward).first; + _sdf->Get("forward", this->forward).first; this->forward.Normalize(); // blade upward (+lift) direction in link frame - this->upward = _sdf->Get( + this->upward = _sdf->Get( "upward", this->upward) .first; this->upward.Normalize(); @@ -281,12 +281,12 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) // rotate forward and upward vectors into world frame const auto forwardI = pose.Rot().RotateVector(this->forward); - ignition::math::Vector3d upwardI; + math::Vector3d upwardI; if (this->radialSymmetry) { // use inflow velocity to determine upward direction // which is the component of inflow perpendicular to forward direction. - ignition::math::Vector3d tmp = forwardI.Cross(velI); + math::Vector3d tmp = forwardI.Cross(velI); upwardI = forwardI.Cross(tmp).Normalize(); } else @@ -300,7 +300,7 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) const double minRatio = -1.0; const double maxRatio = 1.0; // check sweep (angle between velI and lift-drag-plane) - double sinSweepAngle = ignition::math::clamp( + double sinSweepAngle = math::clamp( spanwiseI.Dot(velI), minRatio, maxRatio); // get cos from trig identity @@ -340,7 +340,7 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) // given upwardI and liftI are both unit vectors, we can drop the denominator // cos(theta) = a.Dot(b) const double cosAlpha = - ignition::math::clamp(liftI.Dot(upwardI), minRatio, maxRatio); + math::clamp(liftI.Dot(upwardI), minRatio, maxRatio); // Is alpha positive or negative? Test: // forwardI points toward zero alpha @@ -389,7 +389,7 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) } // compute lift force at cp - ignition::math::Vector3d lift = cl * q * this->area * liftI; + math::Vector3d lift = cl * q * this->area * liftI; // compute cd at cp, check for stall, correct for sweep double cd; @@ -412,7 +412,7 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) cd = std::fabs(cd); // drag at cp - ignition::math::Vector3d drag = cd * q * this->area * dragDirection; + math::Vector3d drag = cd * q * this->area * dragDirection; // compute cm at cp, check for stall, correct for sweep double cm; @@ -441,12 +441,12 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) // compute moment (torque) at cp // spanwiseI used to be momentDirection - ignition::math::Vector3d moment = cm * q * this->area * spanwiseI; + math::Vector3d moment = cm * q * this->area * spanwiseI; // force and torque about cg in world frame - ignition::math::Vector3d force = lift + drag; - ignition::math::Vector3d torque = moment; + math::Vector3d force = lift + drag; + math::Vector3d torque = moment; // Correct for nan or inf force.Correct(); this->cp.Correct(); @@ -558,7 +558,7 @@ void LiftDrag::PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ecm) } IGNITION_ADD_PLUGIN(LiftDrag, - ignition::gazebo::System, + System, LiftDrag::ISystemConfigure, LiftDrag::ISystemPreUpdate) diff --git a/src/systems/log/LogPlayback.cc b/src/systems/log/LogPlayback.cc index b7529705c6..31a5b6159a 100644 --- a/src/systems/log/LogPlayback.cc +++ b/src/systems/log/LogPlayback.cc @@ -602,10 +602,10 @@ void LogPlayback::Update(const UpdateInfo &_info, EntityComponentManager &_ecm) } } -IGNITION_ADD_PLUGIN(ignition::gazebo::systems::LogPlayback, - ignition::gazebo::System, +IGNITION_ADD_PLUGIN(LogPlayback, + System, LogPlayback::ISystemConfigure, LogPlayback::ISystemUpdate) -IGNITION_ADD_PLUGIN_ALIAS(ignition::gazebo::systems::LogPlayback, +IGNITION_ADD_PLUGIN_ALIAS(LogPlayback, "ignition::gazebo::systems::LogPlayback") diff --git a/src/systems/log/LogRecord.cc b/src/systems/log/LogRecord.cc index 918359f6dc..8a974c0c3b 100644 --- a/src/systems/log/LogRecord.cc +++ b/src/systems/log/LogRecord.cc @@ -371,7 +371,7 @@ bool LogRecordPrivate::Start(const std::string &_logPath, // This calls Log::Open() and loads sql schema if (this->recorder.Start(dbPath) == - ignition::transport::log::RecorderError::SUCCESS) + transport::log::RecorderError::SUCCESS) { this->instStarted = true; return true; @@ -736,11 +736,11 @@ void LogRecord::PostUpdate(const UpdateInfo &_info, this->dataPtr->LogModelResources(_ecm); } -IGNITION_ADD_PLUGIN(ignition::gazebo::systems::LogRecord, - ignition::gazebo::System, +IGNITION_ADD_PLUGIN(LogRecord, + gazebo::System, LogRecord::ISystemConfigure, LogRecord::ISystemPreUpdate, LogRecord::ISystemPostUpdate) -IGNITION_ADD_PLUGIN_ALIAS(ignition::gazebo::systems::LogRecord, +IGNITION_ADD_PLUGIN_ALIAS(LogRecord, "ignition::gazebo::systems::LogRecord") diff --git a/src/systems/log_video_recorder/LogVideoRecorder.cc b/src/systems/log_video_recorder/LogVideoRecorder.cc index 29416a3a0e..8fe62313cd 100644 --- a/src/systems/log_video_recorder/LogVideoRecorder.cc +++ b/src/systems/log_video_recorder/LogVideoRecorder.cc @@ -372,8 +372,8 @@ void LogVideoRecorder::PostUpdate(const UpdateInfo &_info, ////////////////////////////////////////////////// void LogVideoRecorderPrivate::Rewind() { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error sending rewind request" << std::endl; @@ -399,14 +399,14 @@ void LogVideoRecorderPrivate::Play() ////////////////////////////////////////////////// void LogVideoRecorderPrivate::Follow(const std::string &_entity) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error sending follow request" << std::endl; }; - ignition::msgs::StringMsg req; + msgs::StringMsg req; req.set_data(_entity); if (this->node.Request(this->followService, req, cb)) { @@ -417,14 +417,14 @@ void LogVideoRecorderPrivate::Follow(const std::string &_entity) ////////////////////////////////////////////////// void LogVideoRecorderPrivate::Record(bool _record) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error sending record request" << std::endl; }; - ignition::msgs::VideoRecord req; + msgs::VideoRecord req; if (_record) { @@ -445,7 +445,7 @@ void LogVideoRecorderPrivate::Record(bool _record) } IGNITION_ADD_PLUGIN(LogVideoRecorder, - ignition::gazebo::System, + System, LogVideoRecorder::ISystemConfigure, LogVideoRecorder::ISystemPostUpdate) diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc index 78ab1b7d65..9493abe590 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc @@ -78,7 +78,7 @@ class ignition::gazebo::systems::LogicalAudioSensorPluginPrivate const logical_audio::SourcePlayInfo &_sourcePlayInfo); /// \brief Node used to create publishers and services - public: ignition::transport::Node node; + public: transport::Node node; /// \brief A flag used to initialize a source's playing information /// before starting simulation. @@ -97,7 +97,7 @@ class ignition::gazebo::systems::LogicalAudioSensorPluginPrivate /// (an entity can have multiple microphones attached to it). /// The value is the microphone's detection publisher. public: std::unordered_map micEntities; + transport::Node::Publisher> micEntities; /// \brief A mutex used to ensure that the play source service call does /// not interfere with the source's state in the PreUpdate step. @@ -240,7 +240,7 @@ void LogicalAudioSensorPlugin::PostUpdate(const UpdateInfo &_info, // publish the source that the microphone heard, along with the // volume level the microphone detected. The detected source's // ID is embedded in the message's header - ignition::msgs::Double msg; + msgs::Double msg; auto header = msg.mutable_header(); auto timeStamp = header->mutable_stamp(); timeStamp->set_sec(simSeconds.count()); @@ -284,7 +284,7 @@ void LogicalAudioSensorPluginPrivate::CreateAudioSource( } _ids.insert(id); - ignition::math::Pose3d pose; + math::Pose3d pose; if (!_elem->HasElement("pose")) { ignwarn << "Audio source is missing a pose. " @@ -293,7 +293,7 @@ void LogicalAudioSensorPluginPrivate::CreateAudioSource( } else { - pose = _elem->Get("pose"); + pose = _elem->Get("pose"); } if (!_elem->HasElement("attenuation_function")) @@ -385,16 +385,16 @@ void LogicalAudioSensorPluginPrivate::CreateAudioSource( components::LogicalAudioSourcePlayInfo(playInfo)); // create service callbacks that allow this source to be played/stopped - std::function playSrvCb = - [this, entity](ignition::msgs::Boolean &_resp) + std::function playSrvCb = + [this, entity](msgs::Boolean &_resp) { std::lock_guard lock(this->playSourceMutex); this->sourceEntities[entity].first = true; _resp.set_data(true); return true; }; - std::function stopSrvCb = - [this, entity](ignition::msgs::Boolean &_resp) + std::function stopSrvCb = + [this, entity](msgs::Boolean &_resp) { std::lock_guard lock(this->stopSourceMutex); this->sourceEntities[entity].second = true; @@ -454,7 +454,7 @@ void LogicalAudioSensorPluginPrivate::CreateMicrophone( } _ids.insert(id); - ignition::math::Pose3d pose; + math::Pose3d pose; if (!_elem->HasElement("pose")) { ignwarn << "Microphone is missing a pose. " @@ -463,7 +463,7 @@ void LogicalAudioSensorPluginPrivate::CreateMicrophone( } else { - pose = _elem->Get("pose"); + pose = _elem->Get("pose"); } double volumeDetectionThreshold; @@ -501,7 +501,7 @@ void LogicalAudioSensorPluginPrivate::CreateMicrophone( components::Pose(pose)); // create the detection publisher for this microphone - auto pub = this->node.Advertise( + auto pub = this->node.Advertise( scopedName(entity, _ecm) + "/detection"); if (!pub) { @@ -526,7 +526,7 @@ bool LogicalAudioSensorPluginPrivate::DurationExceeded( } IGNITION_ADD_PLUGIN(LogicalAudioSensorPlugin, - ignition::gazebo::System, + System, LogicalAudioSensorPlugin::ISystemConfigure, LogicalAudioSensorPlugin::ISystemPreUpdate, LogicalAudioSensorPlugin::ISystemPostUpdate) diff --git a/src/systems/magnetometer/Magnetometer.cc b/src/systems/magnetometer/Magnetometer.cc index 2ecad15692..829810f9ee 100644 --- a/src/systems/magnetometer/Magnetometer.cc +++ b/src/systems/magnetometer/Magnetometer.cc @@ -52,7 +52,7 @@ class ignition::gazebo::systems::MagnetometerPrivate { /// \brief A map of magnetometer entity to its sensor. public: std::unordered_map> entitySensorMap; + std::unique_ptr> entitySensorMap; /// \brief Ign-sensors sensor factory for creating sensors public: sensors::SensorFactory sensorFactory; diff --git a/src/systems/multicopter_control/MulticopterVelocityControl.cc b/src/systems/multicopter_control/MulticopterVelocityControl.cc index 17fc2b56ff..09746000e5 100644 --- a/src/systems/multicopter_control/MulticopterVelocityControl.cc +++ b/src/systems/multicopter_control/MulticopterVelocityControl.cc @@ -335,8 +335,8 @@ math::Inertiald MulticopterVelocityControl::VehicleInertial( ////////////////////////////////////////////////// void MulticopterVelocityControl::PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("MulticopterVelocityControl::PreUpdate"); @@ -427,7 +427,7 @@ void MulticopterVelocityControl::OnEnable( ////////////////////////////////////////////////// void MulticopterVelocityControl::PublishRotorVelocities( - ignition::gazebo::EntityComponentManager &_ecm, + EntityComponentManager &_ecm, const Eigen::VectorXd &_vels) { if (_vels.size() != this->rotorVelocitiesMsg.velocity_size()) @@ -464,7 +464,7 @@ void MulticopterVelocityControl::PublishRotorVelocities( } IGNITION_ADD_PLUGIN(MulticopterVelocityControl, - ignition::gazebo::System, + System, MulticopterVelocityControl::ISystemConfigure, MulticopterVelocityControl::ISystemPreUpdate) diff --git a/src/systems/multicopter_motor_model/MulticopterMotorModel.cc b/src/systems/multicopter_motor_model/MulticopterMotorModel.cc index db6552555b..fe225a478a 100644 --- a/src/systems/multicopter_motor_model/MulticopterMotorModel.cc +++ b/src/systems/multicopter_motor_model/MulticopterMotorModel.cc @@ -120,7 +120,7 @@ enum class MotorType { class ignition::gazebo::systems::MulticopterMotorModelPrivate { /// \brief Callback for actuator commands. - public: void OnActuatorMsg(const ignition::msgs::Actuators &_msg); + public: void OnActuatorMsg(const msgs::Actuators &_msg); /// \brief Apply link forces and moments based on propeller state. public: void UpdateForcesAndMoments(EntityComponentManager &_ecm); @@ -377,8 +377,8 @@ void MulticopterMotorModel::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void MulticopterMotorModel::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void MulticopterMotorModel::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("MulticopterMotorModel::PreUpdate"); @@ -476,7 +476,7 @@ void MulticopterMotorModel::PreUpdate(const ignition::gazebo::UpdateInfo &_info, ////////////////////////////////////////////////// void MulticopterMotorModelPrivate::OnActuatorMsg( - const ignition::msgs::Actuators &_msg) + const msgs::Actuators &_msg) { std::lock_guard lock(this->recvdActuatorsMsgMutex); this->recvdActuatorsMsg = _msg; @@ -566,8 +566,8 @@ void MulticopterMotorModelPrivate::UpdateForcesAndMoments( realMotorVelocity * realMotorVelocity * this->motorConstant; - using Pose = ignition::math::Pose3d; - using Vector3 = ignition::math::Vector3d; + using Pose = math::Pose3d; + using Vector3 = math::Vector3d; Link link(this->linkEntity); const auto worldPose = link.WorldPose(_ecm); @@ -678,7 +678,7 @@ void MulticopterMotorModelPrivate::UpdateForcesAndMoments( } IGNITION_ADD_PLUGIN(MulticopterMotorModel, - ignition::gazebo::System, + System, MulticopterMotorModel::ISystemConfigure, MulticopterMotorModel::ISystemPreUpdate) diff --git a/src/systems/performer_detector/PerformerDetector.cc b/src/systems/performer_detector/PerformerDetector.cc index 7da45abd73..99c2c1a738 100644 --- a/src/systems/performer_detector/PerformerDetector.cc +++ b/src/systems/performer_detector/PerformerDetector.cc @@ -130,8 +130,8 @@ void PerformerDetector::Configure(const Entity &_entity, ////////////////////////////////////////////////// void PerformerDetector::PostUpdate( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + const EntityComponentManager &_ecm) { IGN_PROFILE("PerformerDetector::PostUpdate"); @@ -260,7 +260,7 @@ void PerformerDetector::Publish( } IGNITION_ADD_PLUGIN(PerformerDetector, - ignition::gazebo::System, + System, PerformerDetector::ISystemConfigure, PerformerDetector::ISystemPostUpdate) diff --git a/src/systems/physics/EntityFeatureMap_TEST.cc b/src/systems/physics/EntityFeatureMap_TEST.cc index f4c0e9d12f..510b5d3866 100644 --- a/src/systems/physics/EntityFeatureMap_TEST.cc +++ b/src/systems/physics/EntityFeatureMap_TEST.cc @@ -64,7 +64,7 @@ class EntityFeatureMapFixture: public InternalFixture<::testing::Test> << "Failed to find plugin [" << pluginLib << "]"; // Load engine plugin - ignition::plugin::Loader pluginLoader; + plugin::Loader pluginLoader; auto plugins = pluginLoader.LoadLib(pathToLib); ASSERT_FALSE(plugins.empty()) << "Unable to load the [" << pathToLib << "] library."; @@ -82,7 +82,7 @@ class EntityFeatureMapFixture: public InternalFixture<::testing::Test> << pathToLib << "]"; this->engine = - ignition::physics::RequestEngine::From(plugin); ASSERT_NE(nullptr, this->engine); diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index f78c0d64e6..33eb83abdf 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -157,37 +157,37 @@ class ignition::gazebo::systems::PhysicsPrivate /// implement to be supported by this system. /// New features can't be added to this list in minor / patch releases, in /// order to maintain backwards compatibility with downstream physics plugins. - public: struct MinimumFeatureList : ignition::physics::FeatureList< - ignition::physics::FindFreeGroupFeature, - ignition::physics::SetFreeGroupWorldPose, - ignition::physics::FreeGroupFrameSemantics, - ignition::physics::LinkFrameSemantics, - ignition::physics::ForwardStep, - ignition::physics::RemoveModelFromWorld, - ignition::physics::sdf::ConstructSdfLink, - ignition::physics::sdf::ConstructSdfModel, - ignition::physics::sdf::ConstructSdfWorld + public: struct MinimumFeatureList : physics::FeatureList< + physics::FindFreeGroupFeature, + physics::SetFreeGroupWorldPose, + physics::FreeGroupFrameSemantics, + physics::LinkFrameSemantics, + physics::ForwardStep, + physics::RemoveModelFromWorld, + physics::sdf::ConstructSdfLink, + physics::sdf::ConstructSdfModel, + physics::sdf::ConstructSdfWorld >{}; /// \brief Engine type with just the minimum features. - public: using EnginePtrType = ignition::physics::EnginePtr< - ignition::physics::FeaturePolicy3d, MinimumFeatureList>; + public: using EnginePtrType = physics::EnginePtr< + physics::FeaturePolicy3d, MinimumFeatureList>; /// \brief World type with just the minimum features. - public: using WorldPtrType = ignition::physics::WorldPtr< - ignition::physics::FeaturePolicy3d, MinimumFeatureList>; + public: using WorldPtrType = physics::WorldPtr< + physics::FeaturePolicy3d, MinimumFeatureList>; /// \brief Model type with just the minimum features. - public: using ModelPtrType = ignition::physics::ModelPtr< - ignition::physics::FeaturePolicy3d, MinimumFeatureList>; + public: using ModelPtrType = physics::ModelPtr< + physics::FeaturePolicy3d, MinimumFeatureList>; /// \brief Link type with just the minimum features. - public: using LinkPtrType = ignition::physics::LinkPtr< - ignition::physics::FeaturePolicy3d, MinimumFeatureList>; + public: using LinkPtrType = physics::LinkPtr< + physics::FeaturePolicy3d, MinimumFeatureList>; /// \brief Free group type with just the minimum features. - public: using FreeGroupPtrType = ignition::physics::FreeGroupPtr< - ignition::physics::FeaturePolicy3d, MinimumFeatureList>; + public: using FreeGroupPtrType = physics::FreeGroupPtr< + physics::FeaturePolicy3d, MinimumFeatureList>; /// \brief Create physics entities /// \param[in] _ecm Constant reference to ECM. @@ -293,7 +293,7 @@ class ignition::gazebo::systems::PhysicsPrivate /// \param[in] _from An ancestor of the _to entity. /// \param[in] _to A descendant of the _from entity. /// \return Pose transform between the two entities - public: ignition::math::Pose3d RelativePose(const Entity &_from, + public: math::Pose3d RelativePose(const Entity &_from, const Entity &_to, const EntityComponentManager &_ecm) const; /// \brief Enable contact surface customization for the given world. @@ -430,18 +430,18 @@ class ignition::gazebo::systems::PhysicsPrivate public: struct FrictionPyramidSlipComplianceFeatureList : physics::FeatureList< MinimumFeatureList, - ignition::physics::GetShapeFrictionPyramidSlipCompliance, - ignition::physics::SetShapeFrictionPyramidSlipCompliance>{}; + physics::GetShapeFrictionPyramidSlipCompliance, + physics::SetShapeFrictionPyramidSlipCompliance>{}; ////////////////////////////////////////////////// // Joints /// \brief Feature list to handle joints. - public: struct JointFeatureList : ignition::physics::FeatureList< + public: struct JointFeatureList : physics::FeatureList< MinimumFeatureList, - ignition::physics::GetBasicJointProperties, - ignition::physics::GetBasicJointState, - ignition::physics::SetBasicJointState, - ignition::physics::sdf::ConstructSdfJoint>{}; + physics::GetBasicJointProperties, + physics::GetBasicJointState, + physics::SetBasicJointState, + physics::sdf::ConstructSdfJoint>{}; ////////////////////////////////////////////////// @@ -464,50 +464,50 @@ class ignition::gazebo::systems::PhysicsPrivate // Collisions /// \brief Feature list to handle collisions. - public: struct CollisionFeatureList : ignition::physics::FeatureList< + public: struct CollisionFeatureList : physics::FeatureList< MinimumFeatureList, - ignition::physics::sdf::ConstructSdfCollision>{}; + physics::sdf::ConstructSdfCollision>{}; /// \brief Feature list to handle contacts information. - public: struct ContactFeatureList : ignition::physics::FeatureList< + public: struct ContactFeatureList : physics::FeatureList< CollisionFeatureList, - ignition::physics::GetContactsFromLastStepFeature>{}; + physics::GetContactsFromLastStepFeature>{}; /// \brief Feature list to change contacts before they are applied to physics. public: struct SetContactPropertiesCallbackFeatureList : - ignition::physics::FeatureList< + physics::FeatureList< ContactFeatureList, - ignition::physics::SetContactPropertiesCallbackFeature>{}; + physics::SetContactPropertiesCallbackFeature>{}; /// \brief Collision type with collision features. - public: using ShapePtrType = ignition::physics::ShapePtr< - ignition::physics::FeaturePolicy3d, CollisionFeatureList>; + public: using ShapePtrType = physics::ShapePtr< + physics::FeaturePolicy3d, CollisionFeatureList>; /// \brief World type with just the minimum features. Non-pointer. - public: using WorldShapeType = ignition::physics::World< - ignition::physics::FeaturePolicy3d, ContactFeatureList>; + public: using WorldShapeType = physics::World< + physics::FeaturePolicy3d, ContactFeatureList>; ////////////////////////////////////////////////// // Collision filtering with bitmasks /// \brief Feature list to filter collisions with bitmasks. - public: struct CollisionMaskFeatureList : ignition::physics::FeatureList< + public: struct CollisionMaskFeatureList : physics::FeatureList< CollisionFeatureList, - ignition::physics::CollisionFilterMaskFeature>{}; + physics::CollisionFilterMaskFeature>{}; ////////////////////////////////////////////////// // Link force /// \brief Feature list for applying forces to links. - public: struct LinkForceFeatureList : ignition::physics::FeatureList< - ignition::physics::AddLinkExternalForceTorque>{}; + public: struct LinkForceFeatureList : physics::FeatureList< + physics::AddLinkExternalForceTorque>{}; ////////////////////////////////////////////////// // Bounding box /// \brief Feature list for model bounding box. - public: struct BoundingBoxFeatureList : ignition::physics::FeatureList< + public: struct BoundingBoxFeatureList : physics::FeatureList< MinimumFeatureList, - ignition::physics::GetModelBoundingBox>{}; + physics::GetModelBoundingBox>{}; ////////////////////////////////////////////////// @@ -541,8 +541,8 @@ class ignition::gazebo::systems::PhysicsPrivate ////////////////////////////////////////////////// // World velocity command public: struct WorldVelocityCommandFeatureList : - ignition::physics::FeatureList< - ignition::physics::SetFreeGroupWorldVelocity>{}; + physics::FeatureList< + physics::SetFreeGroupWorldVelocity>{}; ////////////////////////////////////////////////// @@ -581,9 +581,9 @@ class ignition::gazebo::systems::PhysicsPrivate // Nested Models /// \brief Feature list to construct nested models - public: struct NestedModelFeatureList : ignition::physics::FeatureList< + public: struct NestedModelFeatureList : physics::FeatureList< MinimumFeatureList, - ignition::physics::sdf::ConstructSdfNestedModel>{}; + physics::sdf::ConstructSdfNestedModel>{}; ////////////////////////////////////////////////// /// \brief World EntityFeatureMap @@ -764,7 +764,7 @@ void Physics::Configure(const Entity &_entity, } // Load engine plugin - ignition::plugin::Loader pluginLoader; + plugin::Loader pluginLoader; auto plugins = pluginLoader.LoadLib(pathToLib); if (plugins.empty()) { @@ -794,8 +794,8 @@ void Physics::Configure(const Entity &_entity, continue; } - this->dataPtr->engine = ignition::physics::RequestEngine< - ignition::physics::FeaturePolicy3d, + this->dataPtr->engine = physics::RequestEngine< + physics::FeaturePolicy3d, PhysicsPrivate::MinimumFeatureList>::From(plugin); if (nullptr != this->dataPtr->engine) @@ -805,8 +805,8 @@ void Physics::Configure(const Entity &_entity, break; } - auto missingFeatures = ignition::physics::RequestEngine< - ignition::physics::FeaturePolicy3d, + auto missingFeatures = physics::RequestEngine< + physics::FeaturePolicy3d, PhysicsPrivate::MinimumFeatureList>::MissingFeatureNames(plugin); std::stringstream msg; @@ -1226,7 +1226,7 @@ void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm) return true; } - auto &meshManager = *ignition::common::MeshManager::Instance(); + auto &meshManager = *common::MeshManager::Instance(); auto fullPath = asFullPath(meshSdf->Uri(), meshSdf->FilePath()); auto *mesh = meshManager.Load(fullPath); if (nullptr == mesh) @@ -1324,7 +1324,7 @@ void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm) } std::string name("POLYLINE_" + common::Uuid().String()); - auto meshManager = ignition::common::MeshManager::Instance(); + auto meshManager = common::MeshManager::Instance(); meshManager->CreateExtrudedPolyline(name, vertices, _geom->Data().PolylineShape()[0].Height()); @@ -2421,9 +2421,9 @@ ignition::physics::ForwardStep::Output PhysicsPrivate::Step( const std::chrono::steady_clock::duration &_dt) { IGN_PROFILE("PhysicsPrivate::Step"); - ignition::physics::ForwardStep::Input input; - ignition::physics::ForwardStep::State state; - ignition::physics::ForwardStep::Output output; + physics::ForwardStep::Input input; + physics::ForwardStep::State state; + physics::ForwardStep::Output output; input.Get() = _dt; @@ -2436,7 +2436,7 @@ ignition::physics::ForwardStep::Output PhysicsPrivate::Step( } ////////////////////////////////////////////////// -ignition::math::Pose3d PhysicsPrivate::RelativePose(const Entity &_from, +math::Pose3d PhysicsPrivate::RelativePose(const Entity &_from, const Entity &_to, const EntityComponentManager &_ecm) const { math::Pose3d transform; @@ -2997,7 +2997,7 @@ void PhysicsPrivate::UpdateSim(EntityComponentManager &_ecm, this->LinkFrameDataAtOffset(linkPhys, _pose->Data()); auto entityWorldPose = math::eigen3::convert(entityFrameData.pose); - ignition::math::Vector3d entityWorldAngularVel = + math::Vector3d entityWorldAngularVel = math::eigen3::convert(entityFrameData.angularVelocity); auto entityBodyAngularVel = @@ -3022,7 +3022,7 @@ void PhysicsPrivate::UpdateSim(EntityComponentManager &_ecm, this->LinkFrameDataAtOffset(linkPhys, _pose->Data()); auto entityWorldPose = math::eigen3::convert(entityFrameData.pose); - ignition::math::Vector3d entityWorldLinearAcc = + math::Vector3d entityWorldLinearAcc = math::eigen3::convert(entityFrameData.linearAcceleration); auto entityBodyLinearAcc = @@ -3452,7 +3452,7 @@ void PhysicsPrivate::DisableContactSurfaceCustomization(const Entity &_world) } IGNITION_ADD_PLUGIN(Physics, - ignition::gazebo::System, + gazebo::System, Physics::ISystemConfigure, Physics::ISystemUpdate) diff --git a/src/systems/pose_publisher/PosePublisher.cc b/src/systems/pose_publisher/PosePublisher.cc index 010c88b10b..04067e33c7 100644 --- a/src/systems/pose_publisher/PosePublisher.cc +++ b/src/systems/pose_publisher/PosePublisher.cc @@ -156,12 +156,12 @@ class ignition::gazebo::systems::PosePublisherPrivate /// \brief A variable that gets populated with poses. This also here as a /// member variable to avoid repeated memory allocations and improve /// performance. - public: ignition::msgs::Pose poseMsg; + public: msgs::Pose poseMsg; /// \brief A variable that gets populated with poses. This also here as a /// member variable to avoid repeated memory allocations and improve /// performance. - public: ignition::msgs::Pose_V poseVMsg; + public: msgs::Pose_V poseVMsg; /// \brief True to publish a vector of poses. False to publish individual pose /// msgs. @@ -263,23 +263,23 @@ void PosePublisher::Configure(const Entity &_entity, if (this->dataPtr->usePoseV) { this->dataPtr->posePub = - this->dataPtr->node.Advertise(poseTopic); + this->dataPtr->node.Advertise(poseTopic); if (this->dataPtr->staticPosePublisher) { this->dataPtr->poseStaticPub = - this->dataPtr->node.Advertise( + this->dataPtr->node.Advertise( staticPoseTopic); } } else { this->dataPtr->posePub = - this->dataPtr->node.Advertise(poseTopic); + this->dataPtr->node.Advertise(poseTopic); if (this->dataPtr->staticPosePublisher) { this->dataPtr->poseStaticPub = - this->dataPtr->node.Advertise( + this->dataPtr->node.Advertise( staticPoseTopic); } } @@ -530,7 +530,7 @@ void PosePublisherPrivate::PublishPoses( IGN_PROFILE("PosePublisher::PublishPoses"); // publish poses - ignition::msgs::Pose *msg = nullptr; + msgs::Pose *msg = nullptr; if (this->usePoseV) this->poseVMsg.Clear(); diff --git a/src/systems/scene_broadcaster/SceneBroadcaster.cc b/src/systems/scene_broadcaster/SceneBroadcaster.cc index f88ae5b2bd..d2fa2a6d3c 100644 --- a/src/systems/scene_broadcaster/SceneBroadcaster.cc +++ b/src/systems/scene_broadcaster/SceneBroadcaster.cc @@ -89,21 +89,21 @@ class ignition::gazebo::systems::SceneBroadcasterPrivate /// \brief Callback for scene info service. /// \param[out] _res Response containing the latest scene message. /// \return True if successful. - public: bool SceneInfoService(ignition::msgs::Scene &_res); + public: bool SceneInfoService(msgs::Scene &_res); /// \brief Callback for scene graph service. /// \param[out] _res Response containing the the scene graph in DOT format. /// \return True if successful. - public: bool SceneGraphService(ignition::msgs::StringMsg &_res); + public: bool SceneGraphService(msgs::StringMsg &_res); /// \brief Callback for state service. /// \param[out] _res Response containing the latest full state. /// \return True if successful. - public: bool StateService(ignition::msgs::SerializedStepMap &_res); + public: bool StateService(msgs::SerializedStepMap &_res); /// \brief Callback for state service - non blocking. /// \param[out] _res Response containing the last available full state. - public: void StateAsyncService(const ignition::msgs::StringMsg &_req); + public: void StateAsyncService(const msgs::StringMsg &_req); /// \brief Updates the scene graph when entities are added /// \param[in] _manager The entity component manager @@ -619,7 +619,7 @@ void SceneBroadcasterPrivate::SetupTransport(const std::string &_worldName) // Scene info topic std::string sceneTopic{ns + "/scene/info"}; - this->scenePub = this->node->Advertise(sceneTopic); + this->scenePub = this->node->Advertise(sceneTopic); ignmsg << "Publishing scene information on [" << sceneTopic << "]" << std::endl; @@ -628,7 +628,7 @@ void SceneBroadcasterPrivate::SetupTransport(const std::string &_worldName) std::string deletionTopic{ns + "/scene/deletion"}; this->deletionPub = - this->node->Advertise(deletionTopic); + this->node->Advertise(deletionTopic); ignmsg << "Publishing entity deletions on [" << deletionTopic << "]" << std::endl; @@ -637,7 +637,7 @@ void SceneBroadcasterPrivate::SetupTransport(const std::string &_worldName) std::string stateTopic{ns + "/state"}; this->statePub = - this->node->Advertise(stateTopic); + this->node->Advertise(stateTopic); ignmsg << "Publishing state changes on [" << stateTopic << "]" << std::endl; @@ -666,7 +666,7 @@ void SceneBroadcasterPrivate::SetupTransport(const std::string &_worldName) } ////////////////////////////////////////////////// -bool SceneBroadcasterPrivate::SceneInfoService(ignition::msgs::Scene &_res) +bool SceneBroadcasterPrivate::SceneInfoService(msgs::Scene &_res) { std::lock_guard lock(this->graphMutex); @@ -686,7 +686,7 @@ bool SceneBroadcasterPrivate::SceneInfoService(ignition::msgs::Scene &_res) ////////////////////////////////////////////////// void SceneBroadcasterPrivate::StateAsyncService( - const ignition::msgs::StringMsg &_req) + const msgs::StringMsg &_req) { std::unique_lock lock(this->stateMutex); this->stateServiceRequest = true; @@ -695,7 +695,7 @@ void SceneBroadcasterPrivate::StateAsyncService( ////////////////////////////////////////////////// bool SceneBroadcasterPrivate::StateService( - ignition::msgs::SerializedStepMap &_res) + msgs::SerializedStepMap &_res) { _res.Clear(); @@ -717,7 +717,7 @@ bool SceneBroadcasterPrivate::StateService( } ////////////////////////////////////////////////// -bool SceneBroadcasterPrivate::SceneGraphService(ignition::msgs::StringMsg &_res) +bool SceneBroadcasterPrivate::SceneGraphService(msgs::StringMsg &_res) { std::lock_guard lock(this->graphMutex); @@ -987,22 +987,22 @@ void SceneBroadcasterPrivate::SceneGraphAddEntities( msgs::IMUSensor * imuMsg = sensorMsg->mutable_imu(); const auto * imu = imuComp->Data().ImuSensor(); - ignition::gazebo::set( + set( imuMsg->mutable_linear_acceleration()->mutable_x_noise(), imu->LinearAccelerationXNoise()); - ignition::gazebo::set( + set( imuMsg->mutable_linear_acceleration()->mutable_y_noise(), imu->LinearAccelerationYNoise()); - ignition::gazebo::set( + set( imuMsg->mutable_linear_acceleration()->mutable_z_noise(), imu->LinearAccelerationZNoise()); - ignition::gazebo::set( + set( imuMsg->mutable_angular_velocity()->mutable_x_noise(), imu->AngularVelocityXNoise()); - ignition::gazebo::set( + set( imuMsg->mutable_angular_velocity()->mutable_y_noise(), imu->AngularVelocityYNoise()); - ignition::gazebo::set( + set( imuMsg->mutable_angular_velocity()->mutable_z_noise(), imu->AngularVelocityZNoise()); } @@ -1288,7 +1288,7 @@ void SceneBroadcasterPrivate::RemoveFromGraph(const Entity _entity, IGNITION_ADD_PLUGIN(SceneBroadcaster, - ignition::gazebo::System, + System, SceneBroadcaster::ISystemConfigure, SceneBroadcaster::ISystemPostUpdate) diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc index 3a0573d58a..92463253d4 100644 --- a/src/systems/sensors/Sensors.cc +++ b/src/systems/sensors/Sensors.cc @@ -127,7 +127,7 @@ class ignition::gazebo::systems::SensorsPrivate public: std::condition_variable renderCv; /// \brief Connection to events::Stop event, used to stop thread - public: ignition::common::ConnectionPtr stopConn; + public: common::ConnectionPtr stopConn; /// \brief Update time for the next rendering iteration public: std::chrono::steady_clock::duration updateTime; diff --git a/src/systems/thermal/Thermal.cc b/src/systems/thermal/Thermal.cc index 28bd118931..c757ed2245 100644 --- a/src/systems/thermal/Thermal.cc +++ b/src/systems/thermal/Thermal.cc @@ -52,8 +52,8 @@ Thermal::~Thermal() = default; ////////////////////////////////////////////////// void Thermal::Configure(const Entity &_entity, const std::shared_ptr &_sdf, - gazebo::EntityComponentManager &_ecm, - gazebo::EventManager & /*_eventMgr*/) + EntityComponentManager &_ecm, + EventManager & /*_eventMgr*/) { const std::string temperatureTag = "temperature"; const std::string heatSignatureTag = "heat_signature"; diff --git a/src/systems/touch_plugin/TouchPlugin.cc b/src/systems/touch_plugin/TouchPlugin.cc index ccd177bb90..9f32ec1071 100644 --- a/src/systems/touch_plugin/TouchPlugin.cc +++ b/src/systems/touch_plugin/TouchPlugin.cc @@ -409,7 +409,7 @@ void TouchPlugin::PostUpdate(const UpdateInfo &_info, } IGNITION_ADD_PLUGIN(TouchPlugin, - ignition::gazebo::System, + System, TouchPlugin::ISystemConfigure, TouchPlugin::ISystemPreUpdate, TouchPlugin::ISystemPostUpdate) diff --git a/src/systems/track_controller/TrackController.cc b/src/systems/track_controller/TrackController.cc index 116d3cb787..fdf8d1d51a 100644 --- a/src/systems/track_controller/TrackController.cc +++ b/src/systems/track_controller/TrackController.cc @@ -91,8 +91,8 @@ class ignition::gazebo::systems::TrackControllerPrivate /// \param[in] _frictionDirection First friction direction (in world coords). /// \return The computed contact surface speed. public: double ComputeSurfaceMotion( - double _beltSpeed, const ignition::math::Vector3d &_beltDirection, - const ignition::math::Vector3d &_frictionDirection); + double _beltSpeed, const math::Vector3d &_beltDirection, + const math::Vector3d &_frictionDirection); /// \brief Compute the first friction direction of the contact surface. /// \param[in] _centerOfRotation The point around which the track circles ( @@ -100,11 +100,11 @@ class ignition::gazebo::systems::TrackControllerPrivate /// \param[in] _contactWorldPosition Position of the contact point. /// \param[in] _contactNormal Normal of the contact surface (in world coords). /// \param[in] _beltDirection Direction of the belt (in world coords). - public: ignition::math::Vector3d ComputeFrictionDirection( - const ignition::math::Vector3d &_centerOfRotation, - const ignition::math::Vector3d &_contactWorldPosition, - const ignition::math::Vector3d &_contactNormal, - const ignition::math::Vector3d &_beltDirection); + public: math::Vector3d ComputeFrictionDirection( + const math::Vector3d &_centerOfRotation, + const math::Vector3d &_contactWorldPosition, + const math::Vector3d &_contactNormal, + const math::Vector3d &_beltDirection); /// \brief Name of the link to which the track is attached. public: std::string linkName; @@ -342,24 +342,24 @@ void TrackController::Configure(const Entity &_entity, if (this->dataPtr->debug) { this->dataPtr->debugMarker.set_ns(this->dataPtr->linkName + "/friction"); - this->dataPtr->debugMarker.set_action(ignition::msgs::Marker::ADD_MODIFY); - this->dataPtr->debugMarker.set_type(ignition::msgs::Marker::BOX); - this->dataPtr->debugMarker.set_visibility(ignition::msgs::Marker::GUI); + this->dataPtr->debugMarker.set_action(msgs::Marker::ADD_MODIFY); + this->dataPtr->debugMarker.set_type(msgs::Marker::BOX); + this->dataPtr->debugMarker.set_visibility(msgs::Marker::GUI); this->dataPtr->debugMarker.mutable_lifetime()->set_sec(0); this->dataPtr->debugMarker.mutable_lifetime()->set_nsec(4000000); // Set material properties - ignition::msgs::Set( + msgs::Set( this->dataPtr->debugMarker.mutable_material()->mutable_ambient(), - ignition::math::Color(0, 0, 1, 1)); - ignition::msgs::Set( + math::Color(0, 0, 1, 1)); + msgs::Set( this->dataPtr->debugMarker.mutable_material()->mutable_diffuse(), - ignition::math::Color(0, 0, 1, 1)); + math::Color(0, 0, 1, 1)); // Set marker scale - ignition::msgs::Set( + msgs::Set( this->dataPtr->debugMarker.mutable_scale(), - ignition::math::Vector3d(0.3, 0.03, 0.03)); + math::Vector3d(0.3, 0.03, 0.03)); } } @@ -530,7 +530,7 @@ void TrackControllerPrivate::ComputeSurfaceProperties( p += rot.RotateVector( math::Vector3d::UnitX * this->debugMarker.scale().x() / 2); - ignition::msgs::Set(this->debugMarker.mutable_pose(), math::Pose3d( + msgs::Set(this->debugMarker.mutable_pose(), math::Pose3d( p.X(), p.Y(), p.Z(), rot.Roll(), rot.Pitch(), rot.Yaw())); this->debugMarker.mutable_material()->mutable_diffuse()->set_r( surfaceMotion >= 0 ? 0 : 1); @@ -541,8 +541,8 @@ void TrackControllerPrivate::ComputeSurfaceProperties( ////////////////////////////////////////////////// double TrackControllerPrivate::ComputeSurfaceMotion( - const double _beltSpeed, const ignition::math::Vector3d &_beltDirection, - const ignition::math::Vector3d &_frictionDirection) + const double _beltSpeed, const math::Vector3d &_beltDirection, + const math::Vector3d &_frictionDirection) { // the dot product is the cosine of the angle they // form (because both are unit vectors) @@ -553,11 +553,11 @@ double TrackControllerPrivate::ComputeSurfaceMotion( } ////////////////////////////////////////////////// -ignition::math::Vector3d TrackControllerPrivate::ComputeFrictionDirection( - const ignition::math::Vector3d &_centerOfRotation, - const ignition::math::Vector3d &_contactWorldPosition, - const ignition::math::Vector3d &_contactNormal, - const ignition::math::Vector3d &_beltDirection) +math::Vector3d TrackControllerPrivate::ComputeFrictionDirection( + const math::Vector3d &_centerOfRotation, + const math::Vector3d &_contactWorldPosition, + const math::Vector3d &_contactNormal, + const math::Vector3d &_beltDirection) { if (_centerOfRotation.IsFinite()) { @@ -614,7 +614,7 @@ void TrackControllerPrivate::OnCenterOfRotation(const msgs::Vector3d& _msg) } IGNITION_ADD_PLUGIN(TrackController, - ignition::gazebo::System, + System, TrackController::ISystemConfigure, TrackController::ISystemPreUpdate) diff --git a/src/systems/tracked_vehicle/TrackedVehicle.cc b/src/systems/tracked_vehicle/TrackedVehicle.cc index e175d44329..4b3ecc64e6 100644 --- a/src/systems/tracked_vehicle/TrackedVehicle.cc +++ b/src/systems/tracked_vehicle/TrackedVehicle.cc @@ -60,25 +60,25 @@ class ignition::gazebo::systems::TrackedVehiclePrivate { /// \brief Callback for velocity subscription /// \param[in] _msg Velocity message - public: void OnCmdVel(const ignition::msgs::Twist &_msg); + public: void OnCmdVel(const msgs::Twist &_msg); /// \brief Callback for steering efficiency subscription /// \param[in] _msg Steering efficiency message - public: void OnSteeringEfficiency(const ignition::msgs::Double &_msg); + public: void OnSteeringEfficiency(const msgs::Double &_msg); /// \brief Update odometry and publish an odometry message. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateOdometry(const UpdateInfo &_info, + const EntityComponentManager &_ecm); /// \brief Update the linear and angular velocities. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateVelocity(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateVelocity(const UpdateInfo &_info, + const EntityComponentManager &_ecm); /// \brief Ignition communication node. public: transport::Node node; @@ -423,31 +423,31 @@ void TrackedVehicle::Configure(const Entity &_entity, { this->dataPtr->debugMarker.set_ns( this->dataPtr->model.Name(_ecm) + "/cor"); - this->dataPtr->debugMarker.set_action(ignition::msgs::Marker::ADD_MODIFY); - this->dataPtr->debugMarker.set_type(ignition::msgs::Marker::SPHERE); - this->dataPtr->debugMarker.set_visibility(ignition::msgs::Marker::GUI); + this->dataPtr->debugMarker.set_action(msgs::Marker::ADD_MODIFY); + this->dataPtr->debugMarker.set_type(msgs::Marker::SPHERE); + this->dataPtr->debugMarker.set_visibility(msgs::Marker::GUI); this->dataPtr->debugMarker.mutable_lifetime()->set_sec(0); this->dataPtr->debugMarker.mutable_lifetime()->set_nsec(4000000); this->dataPtr->debugMarker.set_id(1); // Set material properties - ignition::msgs::Set( + msgs::Set( this->dataPtr->debugMarker.mutable_material()->mutable_ambient(), - ignition::math::Color(0, 0, 1, 1)); - ignition::msgs::Set( + math::Color(0, 0, 1, 1)); + msgs::Set( this->dataPtr->debugMarker.mutable_material()->mutable_diffuse(), - ignition::math::Color(0, 0, 1, 1)); + math::Color(0, 0, 1, 1)); // Set marker scale - ignition::msgs::Set( + msgs::Set( this->dataPtr->debugMarker.mutable_scale(), - ignition::math::Vector3d(0.1, 0.1, 0.1)); + math::Vector3d(0.1, 0.1, 0.1)); } } ////////////////////////////////////////////////// -void TrackedVehicle::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void TrackedVehicle::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("TrackedVehicle::PreUpdate"); @@ -546,8 +546,8 @@ void TrackedVehicle::PostUpdate(const UpdateInfo &_info, ////////////////////////////////////////////////// void TrackedVehiclePrivate::UpdateOdometry( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + const EntityComponentManager &_ecm) { IGN_PROFILE("TrackedVehicle::UpdateOdometry"); // Initialize, if not already initialized. @@ -629,8 +629,8 @@ void TrackedVehiclePrivate::UpdateOdometry( ////////////////////////////////////////////////// void TrackedVehiclePrivate::UpdateVelocity( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + const EntityComponentManager &_ecm) { IGN_PROFILE("TrackedVehicle::UpdateVelocity"); @@ -702,7 +702,7 @@ void TrackedVehiclePrivate::UpdateVelocity( const auto bodyPose = worldPose(this->bodyLink, _ecm); const auto bodyYAxisGlobal = - bodyPose.Rot().RotateVector(ignition::math::Vector3d(0, 1, 0)); + bodyPose.Rot().RotateVector(math::Vector3d(0, 1, 0)); // centerOfRotation may be +inf this->centerOfRotation = (bodyYAxisGlobal * desiredRotationRadiusSigned) + bodyPose.Pos(); @@ -742,7 +742,7 @@ void TrackedVehiclePrivate::UpdateVelocity( << ", right v=" << this->rightSpeed << (sendCommandsToTracks ? " (sent to tracks)" : "") << std::endl; - ignition::msgs::Set(this->debugMarker.mutable_pose(), math::Pose3d( + msgs::Set(this->debugMarker.mutable_pose(), math::Pose3d( this->centerOfRotation.X(), this->centerOfRotation.Y(), this->centerOfRotation.Z(), @@ -761,7 +761,7 @@ void TrackedVehiclePrivate::OnCmdVel(const msgs::Twist &_msg) ////////////////////////////////////////////////// void TrackedVehiclePrivate::OnSteeringEfficiency( - const ignition::msgs::Double& _msg) + const msgs::Double& _msg) { std::lock_guard lock(this->mutex); this->steeringEfficiency = _msg.data(); @@ -769,7 +769,7 @@ void TrackedVehiclePrivate::OnSteeringEfficiency( } IGNITION_ADD_PLUGIN(TrackedVehicle, - ignition::gazebo::System, + System, TrackedVehicle::ISystemConfigure, TrackedVehicle::ISystemPreUpdate, TrackedVehicle::ISystemPostUpdate) diff --git a/src/systems/triggered_publisher/TriggeredPublisher.cc b/src/systems/triggered_publisher/TriggeredPublisher.cc index cc7a4f88ad..6544754098 100644 --- a/src/systems/triggered_publisher/TriggeredPublisher.cc +++ b/src/systems/triggered_publisher/TriggeredPublisher.cc @@ -855,7 +855,7 @@ bool TriggeredPublisher::MatchInput(const transport::ProtoMsg &_inputMsg) } IGNITION_ADD_PLUGIN(TriggeredPublisher, - ignition::gazebo::System, + System, TriggeredPublisher::ISystemConfigure, TriggeredPublisher::ISystemPreUpdate) diff --git a/src/systems/velocity_control/VelocityControl.cc b/src/systems/velocity_control/VelocityControl.cc index 8082c39716..46b418de6c 100644 --- a/src/systems/velocity_control/VelocityControl.cc +++ b/src/systems/velocity_control/VelocityControl.cc @@ -41,26 +41,26 @@ class ignition::gazebo::systems::VelocityControlPrivate { /// \brief Callback for model velocity subscription /// \param[in] _msg Velocity message - public: void OnCmdVel(const ignition::msgs::Twist &_msg); + public: void OnCmdVel(const msgs::Twist &_msg); /// \brief Callback for link velocity subscription /// \param[in] _msg Velocity message - public: void OnLinkCmdVel(const ignition::msgs::Twist &_msg, - const ignition::transport::MessageInfo &_info); + public: void OnLinkCmdVel(const msgs::Twist &_msg, + const transport::MessageInfo &_info); /// \brief Update the linear and angular velocities. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateVelocity(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateVelocity(const UpdateInfo &_info, + const EntityComponentManager &_ecm); /// \brief Update link velocity. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateLinkVelocity(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateLinkVelocity(const UpdateInfo &_info, + const EntityComponentManager &_ecm); /// \brief Ignition communication node. public: transport::Node node; @@ -180,8 +180,8 @@ void VelocityControl::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void VelocityControl::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void VelocityControl::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("VelocityControl::PreUpdate"); @@ -324,8 +324,8 @@ void VelocityControl::PostUpdate(const UpdateInfo &_info, ////////////////////////////////////////////////// void VelocityControlPrivate::UpdateVelocity( - const ignition::gazebo::UpdateInfo &/*_info*/, - const ignition::gazebo::EntityComponentManager &/*_ecm*/) + const UpdateInfo &/*_info*/, + const EntityComponentManager &/*_ecm*/) { IGN_PROFILE("VeocityControl::UpdateVelocity"); @@ -336,8 +336,8 @@ void VelocityControlPrivate::UpdateVelocity( ////////////////////////////////////////////////// void VelocityControlPrivate::UpdateLinkVelocity( - const ignition::gazebo::UpdateInfo &/*_info*/, - const ignition::gazebo::EntityComponentManager &/*_ecm*/) + const UpdateInfo &/*_info*/, + const EntityComponentManager &/*_ecm*/) { IGN_PROFILE("VelocityControl::UpdateLinkVelocity"); @@ -375,7 +375,7 @@ void VelocityControlPrivate::OnLinkCmdVel(const msgs::Twist &_msg, } IGNITION_ADD_PLUGIN(VelocityControl, - ignition::gazebo::System, + System, VelocityControl::ISystemConfigure, VelocityControl::ISystemPreUpdate, VelocityControl::ISystemPostUpdate) diff --git a/src/systems/wheel_slip/WheelSlip.cc b/src/systems/wheel_slip/WheelSlip.cc index 78385295de..343ee82837 100644 --- a/src/systems/wheel_slip/WheelSlip.cc +++ b/src/systems/wheel_slip/WheelSlip.cc @@ -386,7 +386,7 @@ void WheelSlip::PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ecm) } IGNITION_ADD_PLUGIN(WheelSlip, - ignition::gazebo::System, + System, WheelSlip::ISystemConfigure, WheelSlip::ISystemPreUpdate) diff --git a/src/systems/wind_effects/WindEffects.cc b/src/systems/wind_effects/WindEffects.cc index 39eee5e760..47db52bf2f 100644 --- a/src/systems/wind_effects/WindEffects.cc +++ b/src/systems/wind_effects/WindEffects.cc @@ -392,7 +392,7 @@ void WindEffectsPrivate::UpdateWindVelocity(const UpdateInfo &_info, direction = this->noiseDirection->Apply(direction); // Apply wind velocity - ignition::math::Vector3d windVel; + math::Vector3d windVel; windVel.X(magnitude * std::cos(IGN_DTOR(direction))); windVel.Y(magnitude * std::sin(IGN_DTOR(direction))); diff --git a/test/integration/ackermann_steering_system.cc b/test/integration/ackermann_steering_system.cc index c21884589f..e18cff38b5 100644 --- a/test/integration/ackermann_steering_system.cc +++ b/test/integration/ackermann_steering_system.cc @@ -64,8 +64,8 @@ class AckermannSteeringTest test::Relay testSystem; std::vector poses; - testSystem.OnPostUpdate([&poses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&poses](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto id = _ecm.EntityByComponents( components::Model(), @@ -125,8 +125,8 @@ class AckermannSteeringTest const double desiredLinVel = 10.5; const double desiredAngVel = 0.1; velocityRamp.OnPreUpdate( - [&](const gazebo::UpdateInfo &/*_info*/, - const gazebo::EntityComponentManager &) + [&](const UpdateInfo &/*_info*/, + const EntityComponentManager &) { msgs::Set(msg.mutable_linear(), math::Vector3d(desiredLinVel, 0, 0)); @@ -232,8 +232,8 @@ TEST_P(AckermannSteeringTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SkidPublishCmd)) test::Relay testSystem; std::vector poses; - testSystem.OnPostUpdate([&poses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&poses](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto id = _ecm.EntityByComponents( components::Model(), @@ -330,8 +330,8 @@ TEST_P(AckermannSteeringTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TfPublishes)) test::Relay testSystem; std::vector poses; - testSystem.OnPostUpdate([&poses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&poses](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto id = _ecm.EntityByComponents( components::Model(), diff --git a/test/integration/air_pressure_system.cc b/test/integration/air_pressure_system.cc index 3db386e4d0..4e2644e2a1 100644 --- a/test/integration/air_pressure_system.cc +++ b/test/integration/air_pressure_system.cc @@ -64,11 +64,11 @@ TEST_F(AirPressureTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(AirPressure)) // Create a system that checks sensor topic test::Relay testSystem; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::AirPressureSensor *, const components::Name *_name) -> bool { diff --git a/test/integration/altimeter_system.cc b/test/integration/altimeter_system.cc index 979fafc37b..a536f0e794 100644 --- a/test/integration/altimeter_system.cc +++ b/test/integration/altimeter_system.cc @@ -83,13 +83,13 @@ TEST_F(AltimeterTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(ModelFalling)) test::Relay testSystem; std::vector poses; std::vector velocities; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Altimeter *, const components::Name *_name, const components::WorldPose *_worldPose, diff --git a/test/integration/apply_joint_force_system.cc b/test/integration/apply_joint_force_system.cc index e1b28c54b9..25c9011a17 100644 --- a/test/integration/apply_joint_force_system.cc +++ b/test/integration/apply_joint_force_system.cc @@ -72,7 +72,7 @@ TEST_F(ApplyJointForceTestFixture, test::Relay testSystem; std::vector jointForceCmd; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { auto joint = _ecm.EntityByComponents(components::Joint(), components::Name(jointName)); diff --git a/test/integration/battery_plugin.cc b/test/integration/battery_plugin.cc index 15e130fb65..b6e3ed9fd7 100644 --- a/test/integration/battery_plugin.cc +++ b/test/integration/battery_plugin.cc @@ -60,15 +60,15 @@ class BatteryPluginTest : public InternalFixture<::testing::Test> EXPECT_TRUE(plugin.has_value()); this->systemPtr = plugin.value(); - this->mockSystem = static_cast( - systemPtr->QueryInterface()); + this->mockSystem = static_cast( + systemPtr->QueryInterface()); EXPECT_NE(nullptr, this->mockSystem); } - public: ignition::gazebo::SystemPluginPtr systemPtr; - public: gazebo::MockSystem *mockSystem; + public: SystemPluginPtr systemPtr; + public: MockSystem *mockSystem; - private: gazebo::SystemLoader sm; + private: SystemLoader sm; }; @@ -87,9 +87,9 @@ TEST_F(BatteryPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SingleBattery)) serverConfig.SetSdfFile(sdfPath); // A pointer to the ecm. This will be valid once we run the mock system - gazebo::EntityComponentManager *ecm = nullptr; + EntityComponentManager *ecm = nullptr; this->mockSystem->preUpdateCallback = - [&ecm](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&ecm](const UpdateInfo &, EntityComponentManager &_ecm) { ecm = &_ecm; @@ -111,7 +111,7 @@ TEST_F(BatteryPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SingleBattery)) // the LinearBatteryPlugin is not zero when created. If // components::BatterySoC is zero on start, then the Physics plugin // can disable a joint. This in turn can prevent the joint from - // rotating. See https://github.com/ignitionrobotics/ign-gazebo/issues/55 + // rotating. See https://github.com/gazebosim/gz-sim/issues/55 EXPECT_GT(batComp->Data(), 0); }; diff --git a/test/integration/breadcrumbs.cc b/test/integration/breadcrumbs.cc index 17624884f4..5530b64d56 100644 --- a/test/integration/breadcrumbs.cc +++ b/test/integration/breadcrumbs.cc @@ -147,8 +147,8 @@ TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(DeployAtOffset)) node.Advertise("/model/vehicle_blue/breadcrumbs/B1/deploy"); std::size_t iterTestStart = 1000; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Start moving the vehicle // After 1000 iterations, stop the vehicle, spawn a breadcrumb @@ -212,8 +212,8 @@ TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(MaxDeployments)) node.Advertise("/model/vehicle_blue/breadcrumbs/B1/deploy"); std::size_t iterTestStart = 1000; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Start moving the vehicle // Every 1000 iterations, deploy @@ -270,8 +270,8 @@ TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(FuelDeploy)) const std::size_t nIters = iterTestStart + 2500; const std::size_t maxDeployments = 5; std::size_t deployCount = 0; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Start moving the vehicle // Every 500 iterations, deploy @@ -324,8 +324,8 @@ TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Performer)) const std::size_t nIters = iterTestStart + 10000; std::optional initialPose; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Deploy a performer breadcrumb on a tile that's on a level, and ensure // that it keeps the tile from being unloaded. @@ -397,8 +397,8 @@ TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PerformerSetVolume)) const std::size_t nIters = iterTestStart + 2000; std::optional initialPose; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Deploy a performer breadcrumb on a tile that's on the default a level, // and check that it causes tile_1 to be loaded since the performer's volume @@ -450,8 +450,8 @@ TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(DeployDisablePhysics)) node.Advertise("/model/vehicle_blue/breadcrumbs/B2/deploy"); std::size_t iterTestStart = 1000; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Start moving the vehicle // After 1000 iterations, stop the vehicle, spawn a breadcrumb @@ -551,7 +551,7 @@ TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(AllowRenaming)) ///////////////////////////////////////////////// /// Return a list of model entities whose names match the given regex std::vector ModelsByNameRegex( - const gazebo::EntityComponentManager &_ecm, const std::regex &_re) + const EntityComponentManager &_ecm, const std::regex &_re) { std::vector entities; _ecm.Each( @@ -586,8 +586,8 @@ TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelLoadUnload)) std::regex reTile1{"tile_1"}; std::regex reBreadcrumb{"B1_.*"}; testSystem.OnPostUpdate( - [&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Ensure that tile_1 is loaded at the start, deploy a breadcrumb if (_info.iterations == iterTestStart) diff --git a/test/integration/buoyancy.cc b/test/integration/buoyancy.cc index 8713c1087f..41456aa412 100644 --- a/test/integration/buoyancy.cc +++ b/test/integration/buoyancy.cc @@ -181,8 +181,8 @@ TEST_F(BuoyancyTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(UniformWorldMovement)) bool finished = false; test::Relay testSystem; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Check pose Entity submarine = _ecm.EntityByComponents( @@ -217,7 +217,7 @@ TEST_F(BuoyancyTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(UniformWorldMovement)) auto submarineCenterOfVolume = _ecm.Component(submarineLink); ASSERT_NE(submarineCenterOfVolume, nullptr); - EXPECT_EQ(ignition::math::Vector3d(0, 0, 0), + EXPECT_EQ(math::Vector3d(0, 0, 0), submarineCenterOfVolume->Data()); // Get the submarine buoyant link @@ -235,7 +235,7 @@ TEST_F(BuoyancyTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(UniformWorldMovement)) auto submarineBuoyantCenterOfVolume = _ecm.Component(submarineBuoyantLink); ASSERT_NE(submarineBuoyantCenterOfVolume, nullptr); - EXPECT_EQ(ignition::math::Vector3d(0, 0, 0), + EXPECT_EQ(math::Vector3d(0, 0, 0), submarineBuoyantCenterOfVolume->Data()); // Get the submarine sinking link @@ -253,7 +253,7 @@ TEST_F(BuoyancyTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(UniformWorldMovement)) auto submarineSinkingCenterOfVolume = _ecm.Component(submarineSinkingLink); ASSERT_NE(submarineSinkingCenterOfVolume, nullptr); - EXPECT_EQ(ignition::math::Vector3d(0, 0, 0), + EXPECT_EQ(math::Vector3d(0, 0, 0), submarineSinkingCenterOfVolume->Data()); // Get the duck link @@ -269,7 +269,7 @@ TEST_F(BuoyancyTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(UniformWorldMovement)) auto duckCenterOfVolume = _ecm.Component(duckLink); ASSERT_NE(duckCenterOfVolume, nullptr); - EXPECT_EQ(ignition::math::Vector3d(0, 0, -0.4), + EXPECT_EQ(math::Vector3d(0, 0, -0.4), duckCenterOfVolume->Data()); auto submarinePose = _ecm.Component(submarine); @@ -464,8 +464,8 @@ TEST_F(BuoyancyTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(OffsetAndRotation)) std::size_t iterations{0}; fixture.OnPostUpdate([&]( - const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &, + const EntityComponentManager &_ecm) { // Get links auto noOffsets = entitiesFromScopedName("no_offset::link", _ecm); diff --git a/test/integration/camera_video_record_system.cc b/test/integration/camera_video_record_system.cc index e21b71fc98..13396cb3df 100644 --- a/test/integration/camera_video_record_system.cc +++ b/test/integration/camera_video_record_system.cc @@ -51,7 +51,7 @@ TEST_F(CameraVideoRecorderTest, IGN_UTILS_TEST_DISABLED_ON_MAC(RecordVideo)) // Run server server.Run(true, 1, false); - ignition::transport::Node node; + transport::Node node; std::vector services; bool hasService = false; @@ -75,8 +75,8 @@ TEST_F(CameraVideoRecorderTest, IGN_UTILS_TEST_DISABLED_ON_MAC(RecordVideo)) } EXPECT_TRUE(hasService); - ignition::msgs::VideoRecord videoRecordMsg; - ignition::msgs::Boolean res; + msgs::VideoRecord videoRecordMsg; + msgs::Boolean res; bool result = false; unsigned int timeout = 5000; diff --git a/test/integration/components.cc b/test/integration/components.cc index 93a507e83e..6393eacc66 100644 --- a/test/integration/components.cc +++ b/test/integration/components.cc @@ -120,7 +120,7 @@ TEST_F(ComponentsTest, Actor) comp3.Deserialize(istr); EXPECT_EQ("abc", comp3.Data().Name()); EXPECT_EQ("def", comp3.Data().SkinFilename()); - EXPECT_EQ(ignition::math::Pose3d(3, 2, 1, 0, 0, 0), comp3.Data().RawPose()); + EXPECT_EQ(math::Pose3d(3, 2, 1, 0, 0, 0), comp3.Data().RawPose()); } ///////////////////////////////////////////////// @@ -183,7 +183,7 @@ TEST_F(ComponentsTest, AirPressureSensor) sdf::Sensor data1; data1.SetName("abc"); data1.SetType(sdf::SensorType::AIR_PRESSURE); - data1.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0, 0, 0)); + data1.SetRawPose(math::Pose3d(1, 2, 3, 0, 0, 0)); sdf::AirPressure airPressure1; data1.SetAirPressureSensor(airPressure1); @@ -211,7 +211,7 @@ TEST_F(ComponentsTest, AirPressureSensor) comp3.Deserialize(istr); EXPECT_EQ("abc", comp3.Data().Name()); EXPECT_EQ(sdf::SensorType::AIR_PRESSURE, comp3.Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(1, 2, 3, 0, 0, 0), comp3.Data().RawPose()); + EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 0), comp3.Data().RawPose()); } ///////////////////////////////////////////////// @@ -474,7 +474,7 @@ TEST_F(ComponentsTest, Imu) data1.SetType(sdf::SensorType::IMU); data1.SetUpdateRate(100); data1.SetTopic("imu_data"); - data1.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0, 0, 0)); + data1.SetRawPose(math::Pose3d(1, 2, 3, 0, 0, 0)); sdf::Imu imu1; data1.SetImuSensor(imu1); @@ -505,7 +505,7 @@ TEST_F(ComponentsTest, Imu) EXPECT_EQ(sdf::SensorType::IMU, comp3.Data().Type()); EXPECT_EQ("imu_data", comp3.Data().Topic()); EXPECT_DOUBLE_EQ(100, comp3.Data().UpdateRate()); - EXPECT_EQ(ignition::math::Pose3d(1, 2, 3, 0, 0, 0), comp3.Data().RawPose()); + EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 0), comp3.Data().RawPose()); } ///////////////////////////////////////////////// @@ -1100,7 +1100,7 @@ TEST_F(ComponentsTest, Magnetometer) data1.SetType(sdf::SensorType::MAGNETOMETER); data1.SetUpdateRate(12.4); data1.SetTopic("grape"); - data1.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0, 0, 0)); + data1.SetRawPose(math::Pose3d(1, 2, 3, 0, 0, 0)); sdf::Magnetometer mag1; data1.SetMagnetometerSensor(mag1); @@ -1130,7 +1130,7 @@ TEST_F(ComponentsTest, Magnetometer) EXPECT_EQ(sdf::SensorType::MAGNETOMETER, comp3.Data().Type()); EXPECT_EQ("grape", comp3.Data().Topic()); EXPECT_DOUBLE_EQ(12.4, comp3.Data().UpdateRate()); - EXPECT_EQ(ignition::math::Pose3d(1, 2, 3, 0, 0, 0), comp3.Data().RawPose()); + EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 0), comp3.Data().RawPose()); } ///////////////////////////////////////////////// diff --git a/test/integration/depth_camera.cc b/test/integration/depth_camera.cc index b05d0db4ec..3e36c0013f 100644 --- a/test/integration/depth_camera.cc +++ b/test/integration/depth_camera.cc @@ -104,9 +104,9 @@ TEST_F(DepthCameraTest, IGN_UTILS_TEST_DISABLED_ON_MAC(DepthCameraBox)) // Lock access to buffer and don't release it mutex.lock(); - EXPECT_DOUBLE_EQ(depthBuffer[left], ignition::math::INF_D); + EXPECT_DOUBLE_EQ(depthBuffer[left], math::INF_D); EXPECT_NEAR(depthBuffer[mid], expectedRangeAtMidPointBox1, DEPTH_TOL); - EXPECT_DOUBLE_EQ(depthBuffer[right], ignition::math::INF_D); + EXPECT_DOUBLE_EQ(depthBuffer[right], math::INF_D); delete[] depthBuffer; } diff --git a/test/integration/detachable_joint.cc b/test/integration/detachable_joint.cc index 02005b0ae0..f17d636f22 100644 --- a/test/integration/detachable_joint.cc +++ b/test/integration/detachable_joint.cc @@ -71,8 +71,8 @@ TEST_F(DetachableJointTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StartConnected)) auto poseRecorder = [](const std::string &_modelName, std::vector &_poses) { - return [&, _modelName](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + return [&, _modelName](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( [&](const Entity &_entity, const components::Model *, @@ -149,8 +149,8 @@ TEST_F(DetachableJointTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LinksInSameModel)) auto poseRecorder = [](const std::string &_linkName, std::vector &_poses) { - return [&, _linkName](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + return [&, _linkName](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( [&](const Entity &_entity, const components::Link *, diff --git a/test/integration/diff_drive_system.cc b/test/integration/diff_drive_system.cc index 51d1b5b330..882683d10b 100644 --- a/test/integration/diff_drive_system.cc +++ b/test/integration/diff_drive_system.cc @@ -65,8 +65,8 @@ class DiffDriveTest : public InternalFixture<::testing::TestWithParam> test::Relay testSystem; std::vector poses; - testSystem.OnPostUpdate([&poses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&poses](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto id = _ecm.EntityByComponents( components::Model(), @@ -128,8 +128,8 @@ class DiffDriveTest : public InternalFixture<::testing::TestWithParam> double desiredLinVel = movementDirection * 10.5; double desiredAngVel = 0.2; velocityRamp.OnPreUpdate( - [&](const gazebo::UpdateInfo &/*_info*/, - const gazebo::EntityComponentManager &) + [&](const UpdateInfo &/*_info*/, + const EntityComponentManager &) { msgs::Set(msg.mutable_linear(), math::Vector3d(desiredLinVel, 0, 0)); @@ -249,8 +249,8 @@ TEST_P(DiffDriveTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SkidPublishCmd)) test::Relay testSystem; std::vector poses; - testSystem.OnPostUpdate([&poses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&poses](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto id = _ecm.EntityByComponents( components::Model(), @@ -351,8 +351,8 @@ TEST_P(DiffDriveTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(EnableDisableCmd)) test::Relay testSystem; std::vector poses; - testSystem.OnPostUpdate([&poses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&poses](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto id = _ecm.EntityByComponents( components::Model(), diff --git a/test/integration/each_new_removed.cc b/test/integration/each_new_removed.cc index 353b4080bc..5c2777aadd 100644 --- a/test/integration/each_new_removed.cc +++ b/test/integration/each_new_removed.cc @@ -49,7 +49,7 @@ class EachNewRemovedFixture : public InternalFixture<::testing::Test> TEST_F(EachNewRemovedFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(EachNewEachRemovedInSystem)) { - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; gazebo::Server server; diff --git a/test/integration/elevator_system.cc b/test/integration/elevator_system.cc index ab5aa80304..5889143bb5 100644 --- a/test/integration/elevator_system.cc +++ b/test/integration/elevator_system.cc @@ -40,7 +40,7 @@ class ElevatorTestFixture : public ::testing::Test // Documentation inherited protected: void SetUp() override { - ignition::common::Console::SetVerbosity(4); + common::Console::SetVerbosity(4); setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", (std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1); } diff --git a/test/integration/entity_erase.cc b/test/integration/entity_erase.cc index 7bab7a0908..cd1118ae6e 100644 --- a/test/integration/entity_erase.cc +++ b/test/integration/entity_erase.cc @@ -38,12 +38,12 @@ class PhysicsSystemFixture : public InternalFixture<::testing::Test> TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CreatePhysicsWorld)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); - gazebo::Server server(serverConfig); + Server server(serverConfig); EXPECT_TRUE(server.HasEntity("box")); EXPECT_TRUE(server.HasEntity("capsule")); EXPECT_TRUE(server.HasEntity("cylinder")); diff --git a/test/integration/examples_build.cc b/test/integration/examples_build.cc index c6376de6cb..2868b6b704 100644 --- a/test/integration/examples_build.cc +++ b/test/integration/examples_build.cc @@ -28,7 +28,7 @@ #include "../helpers/EnvTestFixture.hh" // File copied from -// https://github.com/ignitionrobotics/ign-gui/raw/ign-gui3/test/integration/ExamplesBuild_TEST.cc +// https://github.com/gazebosim/gz-gui/raw/ign-gui3/test/integration/ExamplesBuild_TEST.cc using namespace ignition; @@ -138,14 +138,14 @@ void ExamplesBuild::Build(const std::string &_type) // Path to examples of the given type auto examplesDir = std::string(PROJECT_SOURCE_PATH) + "/examples/" + _type; - ASSERT_TRUE(ignition::common::exists(examplesDir)); + ASSERT_TRUE(common::exists(examplesDir)); // Iterate over directory - ignition::common::DirIter endIter; - for (ignition::common::DirIter dirIter(examplesDir); + common::DirIter endIter; + for (common::DirIter dirIter(examplesDir); dirIter != endIter; ++dirIter) { - auto base = ignition::common::basename(*dirIter); + auto base = common::basename(*dirIter); math::SemanticVersion cmakeVersion{std::string(CMAKE_VERSION)}; if (cmakeVersion < math::SemanticVersion(3, 11, 0) && @@ -161,13 +161,13 @@ void ExamplesBuild::Build(const std::string &_type) // Source directory for this example auto sourceDir = examplesDir; sourceDir += "/" + base; - ASSERT_TRUE(ignition::common::exists(sourceDir)); + ASSERT_TRUE(common::exists(sourceDir)); igndbg << "Source: " << sourceDir << std::endl; // Create a temp build directory std::string tmpBuildDir; ASSERT_TRUE(createAndSwitchToTempDir(tmpBuildDir)); - EXPECT_TRUE(ignition::common::exists(tmpBuildDir)); + EXPECT_TRUE(common::exists(tmpBuildDir)); igndbg << "Build directory: " << tmpBuildDir<< std::endl; char cmd[1024]; diff --git a/test/integration/gpu_lidar.cc b/test/integration/gpu_lidar.cc index a1f3368a43..8597db0348 100644 --- a/test/integration/gpu_lidar.cc +++ b/test/integration/gpu_lidar.cc @@ -100,9 +100,9 @@ TEST_F(GpuLidarTest, IGN_UTILS_TEST_DISABLED_ON_MAC(GpuLidarBox)) double expectedRangeAtMidPointBox1 = 0.45; // Sensor 1 should see TestBox1 - EXPECT_DOUBLE_EQ(lastMsg.ranges(0), ignition::math::INF_D); + EXPECT_DOUBLE_EQ(lastMsg.ranges(0), math::INF_D); EXPECT_NEAR(lastMsg.ranges(mid), expectedRangeAtMidPointBox1, LASER_TOL); - EXPECT_DOUBLE_EQ(lastMsg.ranges(last), ignition::math::INF_D); + EXPECT_DOUBLE_EQ(lastMsg.ranges(last), math::INF_D); EXPECT_EQ("gpu_lidar::gpu_lidar_link::gpu_lidar", lastMsg.frame()); } diff --git a/test/integration/imu_system.cc b/test/integration/imu_system.cc index 2a21938e12..6c912f9d3d 100644 --- a/test/integration/imu_system.cc +++ b/test/integration/imu_system.cc @@ -136,15 +136,15 @@ TEST_F(ImuTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(ModelFalling)) std::vector poses; std::vector accelerations; std::vector angularVelocities; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Imu *, const components::Name *_name, const components::WorldPose *_worldPose, @@ -175,7 +175,7 @@ TEST_F(ImuTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(ModelFalling)) }); _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Gravity *_gravity) -> bool { // gtest is having a hard time with ASSERTs inside nested lambdas diff --git a/test/integration/joint_controller_system.cc b/test/integration/joint_controller_system.cc index f14a798f73..402b1d3af8 100644 --- a/test/integration/joint_controller_system.cc +++ b/test/integration/joint_controller_system.cc @@ -70,7 +70,7 @@ TEST_F(JointControllerTestFixture, test::Relay testSystem; std::vector angularVelocities; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { auto link = _ecm.EntityByComponents(components::Link(), components::Name(linkName)); @@ -82,12 +82,12 @@ TEST_F(JointControllerTestFixture, } }); - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Link *, const components::Name *_name, const components::AngularVelocity *_angularVel) -> bool @@ -168,7 +168,7 @@ TEST_F(JointControllerTestFixture, test::Relay testSystem; math::Vector3d angularVelocity; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { auto link = _ecm.EntityByComponents(components::Link(), components::Name(linkName)); @@ -180,12 +180,12 @@ TEST_F(JointControllerTestFixture, } }); - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Link *, const components::Name *_name, const components::AngularVelocity *_angularVel) -> bool diff --git a/test/integration/joint_position_controller_system.cc b/test/integration/joint_position_controller_system.cc index 7e6f4e4afa..b679799a5b 100644 --- a/test/integration/joint_position_controller_system.cc +++ b/test/integration/joint_position_controller_system.cc @@ -71,7 +71,7 @@ TEST_F(JointPositionControllerTestFixture, test::Relay testSystem; std::vector currentPosition; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { auto joint = _ecm.EntityByComponents(components::Joint(), components::Name(jointName)); @@ -83,12 +83,12 @@ TEST_F(JointPositionControllerTestFixture, } }); - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Joint *, const components::Name *_name, const components::JointPosition *_position) -> bool diff --git a/test/integration/level_manager.cc b/test/integration/level_manager.cc index 5e3466943b..cc40b3e561 100644 --- a/test/integration/level_manager.cc +++ b/test/integration/level_manager.cc @@ -73,15 +73,15 @@ class ModelMover: public test::Relay poseCmd = std::move(_pose); } - public: gazebo::Entity Id() const + public: Entity Id() const { return entity; } /// \brief Sets the pose component of the entity to the commanded pose. This /// function meant to be called in the preupdate phase - private: void MoveModel(const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + private: void MoveModel(const UpdateInfo &, + EntityComponentManager &_ecm) { if (this->poseCmd) { @@ -93,7 +93,7 @@ class ModelMover: public test::Relay /// \brief Entity to move - private: gazebo::Entity entity; + private: Entity entity; /// \brief Pose command private: std::optional poseCmd; }; @@ -106,7 +106,7 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> { InternalFixture::SetUp(); - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; // Except tile_0, which is on the default level, every tile belongs to a // level. The name of the level corresponds to the tile in its suffix, i.e., @@ -116,12 +116,12 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> serverConfig.SetUseLevels(true); EXPECT_EQ(nullptr, this->server); - this->server = std::make_unique(serverConfig); + this->server = std::make_unique(serverConfig); test::Relay testSystem; // Check entities loaded on the default level - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( [&](const Entity &, const components::Model *, @@ -170,7 +170,7 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> this->server->Run(true, 1, false); } - public: std::unique_ptr server; + public: std::unique_ptr server; public: std::vector loadedModels; public: std::vector unloadedModels; public: std::vector loadedLights; @@ -187,8 +187,8 @@ TEST_F(LevelManagerFixture, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(DefaultLevel)) test::Relay recorder; // Check entities loaded on the default level - recorder.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + recorder.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( [&](const Entity &, const components::DefaultLevel *, diff --git a/test/integration/level_manager_runtime_performers.cc b/test/integration/level_manager_runtime_performers.cc index 68ef368ee7..db317d4408 100644 --- a/test/integration/level_manager_runtime_performers.cc +++ b/test/integration/level_manager_runtime_performers.cc @@ -70,15 +70,15 @@ class ModelMover: public test::Relay poseCmd = std::move(_pose); } - public: gazebo::Entity Id() const + public: Entity Id() const { return entity; } /// \brief Sets the pose component of the entity to the commanded pose. This /// function meant to be called in the preupdate phase - private: void MoveModel(const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + private: void MoveModel(const UpdateInfo &, + EntityComponentManager &_ecm) { if (this->poseCmd) { @@ -90,7 +90,7 @@ class ModelMover: public test::Relay /// \brief Entity to move - private: gazebo::Entity entity; + private: Entity entity; /// \brief Pose command private: std::optional poseCmd; }; @@ -103,7 +103,7 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> { InternalFixture::SetUp(); - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; // Except tile_0, which is on the default level, every tile belongs to a // level. The name of the level corresponds to the tile in its suffix, i.e., @@ -112,7 +112,7 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> "/test/worlds/levels_no_performers.sdf"); serverConfig.SetUseLevels(true); - server = std::make_unique(serverConfig); + server = std::make_unique(serverConfig); // Add in the "box" performer using a service call transport::Node node; @@ -145,8 +145,8 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> test::Relay testSystem; // Check entities loaded on the default level - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { Entity sphere = _ecm.EntityByComponents(components::Name("sphere")); EXPECT_EQ(1u, @@ -198,7 +198,7 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> this->server->Run(true, 1, false); } - public: std::unique_ptr server; + public: std::unique_ptr server; public: std::vector loadedModels; public: std::vector unloadedModels; public: std::vector loadedLights; @@ -214,8 +214,8 @@ TEST_F(LevelManagerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(DefaultLevel)) test::Relay recorder; // Check entities loaded on the default level - recorder.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + recorder.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( [&](const Entity &, const components::DefaultLevel *, diff --git a/test/integration/lift_drag_system.cc b/test/integration/lift_drag_system.cc index 75d1b2ddc2..4a0d439ec0 100644 --- a/test/integration/lift_drag_system.cc +++ b/test/integration/lift_drag_system.cc @@ -110,7 +110,7 @@ TEST_P(VerticalForceParamFixture, std::vector linearVelocities; std::vector forces; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { // Create velocity and acceleration components if they dont't exist. // This signals physics system to populate the component @@ -130,7 +130,7 @@ TEST_P(VerticalForceParamFixture, const double kp = 100.0; // Set a constant velocity to the prismatic joint testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { auto joint = _ecm.EntityByComponents(components::Joint(), components::Name(jointName)); @@ -161,8 +161,8 @@ TEST_P(VerticalForceParamFixture, // drag system. This is needed to capture the wrench set by the lift drag // system. This assumption may not hold when systems are run in parallel. test::Relay wrenchRecorder; - wrenchRecorder.OnPreUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + wrenchRecorder.OnPreUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto bladeLink = firstEntityFromScopedName(bladeName, _ecm); auto bodyLink = firstEntityFromScopedName(bodyName, _ecm); diff --git a/test/integration/log_system.cc b/test/integration/log_system.cc index 9177378dc0..325b7c2988 100644 --- a/test/integration/log_system.cc +++ b/test/integration/log_system.cc @@ -330,7 +330,7 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogDefaults)) std::string homeOrig; common::env(IGN_HOMEDIR, homeOrig); std::string homeFake = common::joinPaths(this->logsDir, "default"); - EXPECT_TRUE(ignition::common::setenv(IGN_HOMEDIR, homeFake.c_str())); + EXPECT_TRUE(common::setenv(IGN_HOMEDIR, homeFake.c_str())); // Test case 1: // No path specified on command line. This does not go through @@ -417,7 +417,7 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogDefaults)) #endif // Revert environment variable after test is done - EXPECT_TRUE(ignition::common::setenv(IGN_HOMEDIR, homeOrig.c_str())); + EXPECT_TRUE(common::setenv(IGN_HOMEDIR, homeOrig.c_str())); } ///////////////////////////////////////////////// @@ -473,7 +473,7 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogPaths)) std::string homeOrig; common::env(IGN_HOMEDIR, homeOrig); std::string homeFake = common::joinPaths(this->logsDir, "default"); - EXPECT_TRUE(ignition::common::setenv(IGN_HOMEDIR, homeFake.c_str())); + EXPECT_TRUE(common::setenv(IGN_HOMEDIR, homeFake.c_str())); // Store number of files before running auto logPath = common::joinPaths(homeFake.c_str(), ".ignition", "gazebo", @@ -686,7 +686,7 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogPaths)) #endif // Revert environment variable after test is done - EXPECT_TRUE(ignition::common::setenv(IGN_HOMEDIR, homeOrig.c_str())); + EXPECT_TRUE(common::setenv(IGN_HOMEDIR, homeOrig.c_str())); this->RemoveLogsDir(); } @@ -1089,7 +1089,7 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogOverwrite)) // ign gazebo. server_main.cc is deprecated and does not have overwrite // renaming implemented. So will always overwrite. Will not test (#) type of // renaming on OS X until ign gazebo is fixed: - // https://github.com/ignitionrobotics/ign-gazebo/issues/25 + // https://github.com/gazebosim/gz-sim/issues/25 // New log files were created EXPECT_TRUE(common::exists(this->logDir + "(1)")); @@ -1497,7 +1497,7 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogResources)) std::string homeOrig; common::env(IGN_HOMEDIR, homeOrig); std::string homeFake = common::joinPaths(this->logsDir, "default"); - EXPECT_TRUE(ignition::common::setenv(IGN_HOMEDIR, homeFake.c_str())); + EXPECT_TRUE(common::setenv(IGN_HOMEDIR, homeFake.c_str())); const std::string recordPath = this->logDir; std::string statePath = common::joinPaths(recordPath, "state.tlog"); @@ -1523,7 +1523,7 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogResources)) // Recorded models should exist EXPECT_GT(entryCount(recordPath), 2); EXPECT_TRUE(common::exists(common::joinPaths(recordPath, homeFake, - ".ignition", "fuel", "fuel.ignitionrobotics.org", "openrobotics", + ".ignition", "fuel", "fuel.gazebosim.org", "openrobotics", "models", "x2 config 1"))); // Remove artifacts. Recreate new directory @@ -1558,11 +1558,11 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogResources)) EXPECT_GT(entryCount(recordPath), 1); #endif EXPECT_TRUE(common::exists(common::joinPaths(recordPath, homeFake, - ".ignition", "fuel", "fuel.ignitionrobotics.org", "openrobotics", + ".ignition", "fuel", "fuel.gazebosim.org", "openrobotics", "models", "x2 config 1"))); // Revert environment variable after test is done - EXPECT_TRUE(ignition::common::setenv(IGN_HOMEDIR, homeOrig.c_str())); + EXPECT_TRUE(common::setenv(IGN_HOMEDIR, homeOrig.c_str())); // Remove artifacts this->RemoveLogsDir(); @@ -1584,7 +1584,7 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogTopics)) std::string homeOrig; common::env(IGN_HOMEDIR, homeOrig); std::string homeFake = common::joinPaths(this->logsDir, "default"); - EXPECT_TRUE(ignition::common::setenv(IGN_HOMEDIR, homeFake.c_str())); + EXPECT_TRUE(common::setenv(IGN_HOMEDIR, homeFake.c_str())); const std::string recordPath = this->logDir; std::string statePath = common::joinPaths(recordPath, "state.tlog"); diff --git a/test/integration/logical_audio_sensor_plugin.cc b/test/integration/logical_audio_sensor_plugin.cc index 741c7dcfb6..321afee8e1 100644 --- a/test/integration/logical_audio_sensor_plugin.cc +++ b/test/integration/logical_audio_sensor_plugin.cc @@ -65,10 +65,10 @@ TEST_F(LogicalAudioTest, EXPECT_FALSE(*server.Running(0)); // helper variables for checking the validity of the ECM - const ignition::math::Pose3d sourcePose(0, 0, 0, 0, 0, 0); + const math::Pose3d sourcePose(0, 0, 0, 0, 0, 0); const auto zeroSeconds = std::chrono::seconds(0); - const ignition::math::Pose3d micClosePose(0.5, 0, 0, 0, 0, 0); - const ignition::math::Pose3d micFarPose(0, 0, 0, 0, 0, 0); + const math::Pose3d micClosePose(0.5, 0, 0, 0, 0, 0); + const math::Pose3d micFarPose(0, 0, 0, 0, 0, 0); std::chrono::steady_clock::duration sourceStartTime; bool firstTime{true}; diff --git a/test/integration/logical_camera_system.cc b/test/integration/logical_camera_system.cc index e9716dc52c..b69291335b 100644 --- a/test/integration/logical_camera_system.cc +++ b/test/integration/logical_camera_system.cc @@ -93,11 +93,11 @@ TEST_F(LogicalCameraTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogicalCameraBox)) // Create a system that checks sensor topics test::Relay testSystem; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::LogicalCamera *, const components::Name *_name) -> bool { @@ -177,22 +177,22 @@ TEST_F(LogicalCameraTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogicalCameraBox)) math::Pose3d boxPose(1, 0, 0.5, 0, 0, 0); math::Pose3d sensor1Pose(0.05, 0.05, 0.55, 0, 0, 0); mutex.lock(); - ignition::msgs::LogicalCameraImage img1 = logicalCamera1Msgs.back(); - EXPECT_EQ(sensor1Pose, ignition::msgs::Convert(img1.pose())); + msgs::LogicalCameraImage img1 = logicalCamera1Msgs.back(); + EXPECT_EQ(sensor1Pose, msgs::Convert(img1.pose())); EXPECT_EQ(1, img1.model().size()); EXPECT_EQ(boxName, img1.model(0).name()); - ignition::math::Pose3d boxPoseCamera1Frame = boxPose - sensor1Pose; - EXPECT_EQ(boxPoseCamera1Frame, ignition::msgs::Convert(img1.model(0).pose())); + math::Pose3d boxPoseCamera1Frame = boxPose - sensor1Pose; + EXPECT_EQ(boxPoseCamera1Frame, msgs::Convert(img1.model(0).pose())); mutex.unlock(); // Sensor 2 should see box too - note different sensor pose. math::Pose3d sensor2Pose(0.05, -0.45, 0.55, 0, 0, 0); mutex.lock(); - ignition::msgs::LogicalCameraImage img2 = logicalCamera2Msgs.back(); - EXPECT_EQ(sensor2Pose, ignition::msgs::Convert(img2.pose())); + msgs::LogicalCameraImage img2 = logicalCamera2Msgs.back(); + EXPECT_EQ(sensor2Pose, msgs::Convert(img2.pose())); EXPECT_EQ(1, img2.model().size()); EXPECT_EQ(boxName, img2.model(0).name()); - ignition::math::Pose3d boxPoseCamera2Frame = boxPose - sensor2Pose; - EXPECT_EQ(boxPoseCamera2Frame, ignition::msgs::Convert(img2.model(0).pose())); + math::Pose3d boxPoseCamera2Frame = boxPose - sensor2Pose; + EXPECT_EQ(boxPoseCamera2Frame, msgs::Convert(img2.model(0).pose())); mutex.unlock(); } diff --git a/test/integration/magnetometer_system.cc b/test/integration/magnetometer_system.cc index 9c332f24ba..31a7f8b288 100644 --- a/test/integration/magnetometer_system.cc +++ b/test/integration/magnetometer_system.cc @@ -83,13 +83,13 @@ TEST_F(MagnetometerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(RotatedMagnetometer)) test::Relay testSystem; std::vector poses; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Magnetometer *, const components::Name *_name, const components::WorldPose *_worldPose) -> bool @@ -130,7 +130,7 @@ TEST_F(MagnetometerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(RotatedMagnetometer)) // Hardcoded SDF values math::Vector3d worldMagneticField(0.94, 0.76, -0.12); - ignition::math::Vector3d field = poses.back().Rot().Inverse().RotateVector( + math::Vector3d field = poses.back().Rot().Inverse().RotateVector( worldMagneticField); mutex.lock(); EXPECT_NEAR(magnetometerMsgs.back().mutable_field_tesla()->x(), diff --git a/test/integration/multicopter.cc b/test/integration/multicopter.cc index 669a2cfe47..79611ca6b9 100644 --- a/test/integration/multicopter.cc +++ b/test/integration/multicopter.cc @@ -82,7 +82,7 @@ TEST_F(MulticopterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(CommandedMotorSpeed)) const std::size_t iterTestStart{100}; const std::size_t nIters{500}; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &_info, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &_info, EntityComponentManager &_ecm) { // Create components, if the don't exist, on the first iteration if (_info.iterations == 1) @@ -98,8 +98,8 @@ TEST_F(MulticopterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(CommandedMotorSpeed)) }); testSystem.OnPostUpdate( - [&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Command a motor speed // After nIters iterations, check angular velocity of each of the rotors @@ -148,7 +148,7 @@ TEST_F(MulticopterTest, const std::size_t nIters{2000}; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &_info, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &_info, EntityComponentManager &_ecm) { // Create components, if the don't exist, on the first iteration if (_info.iterations == 1) @@ -186,8 +186,8 @@ TEST_F(MulticopterTest, }; testSystem.OnPostUpdate( - [&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { if (!iterTestStart.has_value()) { @@ -256,7 +256,7 @@ TEST_F(MulticopterTest, auto cmdVel = node.Advertise("/X3/gazebo/command/twist"); testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &_info, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &_info, EntityComponentManager &_ecm) { // Create components, if the don't exist, on the first iteration if (_info.iterations == 1) @@ -290,8 +290,8 @@ TEST_F(MulticopterTest, node.Advertise("/X3/gazebo/command/motor_speed"); testSystem.OnPostUpdate( - [&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, + const EntityComponentManager &_ecm) { // Publish a motor speed command { diff --git a/test/integration/network_handshake.cc b/test/integration/network_handshake.cc index 5d35984787..b828f2734c 100644 --- a/test/integration/network_handshake.cc +++ b/test/integration/network_handshake.cc @@ -45,8 +45,8 @@ uint64_t testPaused(bool _paused) bool paused = !_paused; uint64_t iterations = 0; - std::function cb = - [&](const ignition::msgs::WorldStatistics &_msg) + std::function cb = + [&](const msgs::WorldStatistics &_msg) { std::unique_lock lock(mutex); paused = _msg.paused(); @@ -148,7 +148,7 @@ TEST_F(NetworkHandshake, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Updates)) configPrimary.SetUseLevels(true); // Can only test one secondary running physics, because running 2 physics in // the same process causes a segfault, see - // https://github.com/ignitionrobotics/ign-gazebo/issues/18 + // https://github.com/gazebosim/gz-sim/issues/18 configPrimary.SetNetworkSecondaries(1); configPrimary.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/performers.sdf"); @@ -178,8 +178,8 @@ TEST_F(NetworkHandshake, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Updates)) // Subscribe to pose updates, which should come from the primary transport::Node node; std::vector zPos; - std::function cb = - [&](const ignition::msgs::Pose_V &_msg) + std::function cb = + [&](const msgs::Pose_V &_msg) { for (int i = 0; i < _msg.pose().size(); ++i) { diff --git a/test/integration/performer_detector.cc b/test/integration/performer_detector.cc index 63838697cd..b5d5e0784c 100644 --- a/test/integration/performer_detector.cc +++ b/test/integration/performer_detector.cc @@ -201,8 +201,8 @@ TEST_F(PerformerDetectorTest, auto server = this->StartServer("/test/worlds/performer_detector.sdf", true); test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &_info, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &_info, + EntityComponentManager &_ecm) { Entity vehicle = _ecm.EntityByComponents( components::Model(), components::Name("vehicle_blue")); diff --git a/test/integration/physics_system.cc b/test/integration/physics_system.cc index f2aff19a24..7730302e55 100644 --- a/test/integration/physics_system.cc +++ b/test/integration/physics_system.cc @@ -100,12 +100,12 @@ class PhysicsSystemFixtureWithDart6_10 : public PhysicsSystemFixture ///////////////////////////////////////////////// TEST_F(PhysicsSystemFixture, CreatePhysicsWorld) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ns); @@ -122,7 +122,7 @@ TEST_F(PhysicsSystemFixture, CreatePhysicsWorld) // See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(FallingObject)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/falling.sdf"; @@ -133,22 +133,22 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(FallingObject)) const sdf::World *world = root.WorldByIndex(0); const sdf::Model *model = world->ModelByIndex(0); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1us); const std::string modelName = "sphere"; - std::vector spherePoses; + std::vector spherePoses; // Create a system that records the poses of the sphere test::Relay testSystem; testSystem.OnPostUpdate( - [modelName, &spherePoses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [modelName, &spherePoses](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, const components::Model *, + [&](const Entity &, const components::Model *, const components::Name *_name, const components::Pose *_pose)->bool { if (_name->Data() == modelName) { @@ -191,7 +191,7 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(FallingObject)) // must be correct. TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CanonicalLink)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/canonical.sdf"; @@ -203,7 +203,7 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CanonicalLink)) serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1us); @@ -212,7 +212,7 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CanonicalLink)) const sdf::Model *model = world->ModelByIndex(0); - std::unordered_map expectedLinPoses; + std::unordered_map expectedLinPoses; for (auto &linkName : linksToCheck) expectedLinPoses[linkName] = model->LinkByName(linkName)->RawPose(); ASSERT_EQ(3u, expectedLinPoses.size()); @@ -220,14 +220,14 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CanonicalLink)) // Create a system that records the poses of the links after physics test::Relay testSystem; - std::unordered_map postUpLinkPoses; + std::unordered_map postUpLinkPoses; testSystem.OnPostUpdate( - [&modelName, &postUpLinkPoses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [&modelName, &postUpLinkPoses](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, const components::Link *, + [&](const Entity &, const components::Link *, const components::Name *_name, const components::Pose *_pose, const components::ParentEntity *_parent)->bool { @@ -263,7 +263,7 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CanonicalLink)) TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(NonDefaultCanonicalLink)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/nondefault_canonical.sdf"; @@ -275,7 +275,7 @@ TEST_F(PhysicsSystemFixture, serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ns); @@ -284,13 +284,13 @@ TEST_F(PhysicsSystemFixture, // Create a system that records the pose of the model. test::Relay testSystem; - std::vector modelPoses; + std::vector modelPoses; testSystem.OnPostUpdate( - [&modelName, &modelPoses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [&modelName, &modelPoses](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, const components::Model *, + [&](const Entity &, const components::Model *, const components::Name *_name, const components::Pose *_pose)->bool { if (_name->Data() == modelName) @@ -318,7 +318,7 @@ TEST_F(PhysicsSystemFixture, // Test physics integration with revolute joints TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(RevoluteJoint)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/revolute_joint.sdf"; @@ -330,7 +330,7 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(RevoluteJoint)) serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1us); @@ -347,11 +347,11 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(RevoluteJoint)) // arm is in its initial position. The minimum distance is when the arm is in // line with the support arm. testSystem.OnPostUpdate( - [&rotatingLinkName, &armDistances](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [&rotatingLinkName, &armDistances](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, const components::Link *, + [&](const Entity &, const components::Link *, const components::Name *_name, const components::Pose *_pose)->bool { if (rotatingLinkName == _name->Data()) @@ -397,8 +397,8 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(RevoluteJoint)) ///////////////////////////////////////////////// TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CreateRuntime)) { - ignition::gazebo::ServerConfig serverConfig; - gazebo::Server server(serverConfig); + ServerConfig serverConfig; + Server server(serverConfig); server.SetPaused(false); // Create a system just to get the ECM @@ -408,8 +408,8 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CreateRuntime)) // shared pointer owned by the SimulationRunner. EntityComponentManager *ecm{nullptr}; test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &_ecm) { ecm = &_ecm; }); @@ -481,29 +481,29 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CreateRuntime)) TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(SetFrictionCoefficient)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/friction.sdf"; serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ns); std::map boxParams{ {"box1", 0.01}, {"box2", 0.1}, {"box3", 1.0}}; - std::map> poses; + std::map> poses; // Create a system that records the poses of the 3 boxes test::Relay testSystem; testSystem.OnPostUpdate( - [&boxParams, &poses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [&boxParams, &poses](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, const components::Model *, + [&](const Entity &, const components::Model *, const components::Name *_name, const components::Pose *_pose)->bool { if (boxParams.find(_name->Data()) != boxParams.end()) { @@ -567,23 +567,23 @@ TEST_F(PhysicsSystemFixture, TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(MultiAxisJointPosition)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/demo_joint_types.sdf"; serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(0ns); test::Relay testSystem; // Create JointPosition components if they don't already exist testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, components::Joint *) -> bool { auto posComp = _ecm.Component(_entity); @@ -598,10 +598,10 @@ TEST_F(PhysicsSystemFixture, std::map jointPosDof; testSystem.OnPostUpdate( - [&](const gazebo::UpdateInfo &, const gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Joint *, const components::Name *_name, const components::JointPosition *_jointPos) -> bool @@ -647,7 +647,7 @@ TEST_F(PhysicsSystemFixture, TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ResetPositionComponent)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/revolute_joint.sdf"; @@ -659,7 +659,7 @@ TEST_F(PhysicsSystemFixture, serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ms); @@ -673,10 +673,10 @@ TEST_F(PhysicsSystemFixture, bool firstRun = true; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Joint *, components::Name *_name) -> bool { EXPECT_NE(nullptr, _name); @@ -711,11 +711,11 @@ TEST_F(PhysicsSystemFixture, std::vector positions; testSystem.OnPostUpdate([&]( - const gazebo::UpdateInfo &, const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &, const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Joint *, const components::Name *_name, const components::JointPosition *_pos) @@ -747,7 +747,7 @@ TEST_F(PhysicsSystemFixture, TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ResetVelocityComponent)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/revolute_joint.sdf"; @@ -759,7 +759,7 @@ TEST_F(PhysicsSystemFixture, serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ms); @@ -773,10 +773,10 @@ TEST_F(PhysicsSystemFixture, bool firstRun = true; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Joint *, components::Name *_name) -> bool { if (_name->Data() == rotatingJointName) @@ -809,12 +809,12 @@ TEST_F(PhysicsSystemFixture, std::vector velocities; testSystem.OnPostUpdate([&]( - const gazebo::UpdateInfo &, const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &, const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Joint *, const components::Name *_name, const components::JointVelocity *_vel) @@ -845,7 +845,7 @@ TEST_F(PhysicsSystemFixture, /// Test joint position limit command component TEST_F(PhysicsSystemFixtureWithDart6_10, JointPositionLimitsCommandComponent) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/revolute_joint.sdf"; @@ -857,7 +857,7 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointPositionLimitsCommandComponent) serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ms); @@ -878,10 +878,10 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointPositionLimitsCommandComponent) // commands do not break the positional limit. testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Joint *, components::Name *_name) -> bool { if (_name->Data() == rotatingJointName) @@ -934,12 +934,12 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointPositionLimitsCommandComponent) std::vector positions; testSystem.OnPostUpdate([&]( - const gazebo::UpdateInfo &, const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &, const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Joint *, const components::Name *_name, const components::JointPosition *_pos) @@ -968,7 +968,7 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointPositionLimitsCommandComponent) /// Test joint velocity limit command component TEST_F(PhysicsSystemFixtureWithDart6_10, JointVelocityLimitsCommandComponent) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/revolute_joint.sdf"; @@ -980,7 +980,7 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointVelocityLimitsCommandComponent) serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ms); @@ -1001,10 +1001,10 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointVelocityLimitsCommandComponent) // commands do not break the velocity limit. testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Joint *, components::Name *_name) -> bool { if (_name->Data() == rotatingJointName) @@ -1057,12 +1057,12 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointVelocityLimitsCommandComponent) std::vector velocities; testSystem.OnPostUpdate([&]( - const gazebo::UpdateInfo &, const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &, const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Joint *, const components::Name *_name, const components::JointVelocity *_vel) @@ -1092,7 +1092,7 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointVelocityLimitsCommandComponent) /// Test joint effort limit command component TEST_F(PhysicsSystemFixtureWithDart6_10, JointEffortLimitsCommandComponent) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/revolute_joint_equilibrium.sdf"; @@ -1104,7 +1104,7 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointEffortLimitsCommandComponent) serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ms); @@ -1125,10 +1125,10 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointEffortLimitsCommandComponent) // commands do not break the effort limit. testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Joint *, components::Name *_name) -> bool { if (_name->Data() == rotatingJointName) @@ -1186,12 +1186,12 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointEffortLimitsCommandComponent) std::vector positions; testSystem.OnPostUpdate([&]( - const gazebo::UpdateInfo &, const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &, const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Joint *, const components::Name *_name, const components::JointPosition *_pos) @@ -1219,28 +1219,28 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointEffortLimitsCommandComponent) ///////////////////////////////////////////////// TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(GetBoundingBox)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/contact.sdf"; serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ns); // a map of model name to its axis aligned box - std::map bbox; + std::map bbox; // Create a system that records the bounding box of a model test::Relay testSystem; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, + EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, const components::Model *, + [&](const Entity &_entity, const components::Model *, const components::Name *_name, const components::Static *)->bool { // create axis aligned box to be filled by physics @@ -1258,13 +1258,13 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(GetBoundingBox)) }); testSystem.OnPostUpdate( - [&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, + const EntityComponentManager &_ecm) { // store models that have axis aligned box computed _ecm.Each( - [&](const ignition::gazebo::Entity &, const components::Model *, + [&](const Entity &, const components::Model *, const components::Name *_name, const components::Static *, const components::AxisAlignedBox *_aabb)->bool { @@ -1279,9 +1279,9 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(GetBoundingBox)) EXPECT_EQ(1u, bbox.size()); EXPECT_EQ("box1", bbox.begin()->first); - EXPECT_EQ(ignition::math::AxisAlignedBox( - ignition::math::Vector3d(-1.25, -2, 0), - ignition::math::Vector3d(-0.25, 2, 1)), + EXPECT_EQ(math::AxisAlignedBox( + math::Vector3d(-1.25, -2, 0), + math::Vector3d(-0.25, 2, 1)), bbox.begin()->second); } @@ -1290,7 +1290,7 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(GetBoundingBox)) // This tests whether nested models can be loaded correctly TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(NestedModel)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/nested_model.sdf"; @@ -1302,22 +1302,22 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(NestedModel)) serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1us); // Create a system that records the poses of the links after physics test::Relay testSystem; - std::unordered_map postUpModelPoses; - std::unordered_map postUpLinkPoses; + std::unordered_map postUpModelPoses; + std::unordered_map postUpLinkPoses; std::unordered_map parents; testSystem.OnPostUpdate( - [&postUpModelPoses, &postUpLinkPoses, &parents](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [&postUpModelPoses, &postUpLinkPoses, &parents](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, const components::Model *, + [&](const Entity &_entity, const components::Model *, const components::Name *_name, const components::Pose *_pose)->bool { // store model pose @@ -1336,7 +1336,7 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(NestedModel)) _ecm.Each( - [&](const ignition::gazebo::Entity &, const components::Link *, + [&](const Entity &, const components::Link *, const components::Name *_name, const components::Pose *_pose, const components::ParentEntity *_parent)->bool { diff --git a/test/integration/play_pause.cc b/test/integration/play_pause.cc index 92a9e6d398..ed7b2241f3 100644 --- a/test/integration/play_pause.cc +++ b/test/integration/play_pause.cc @@ -36,13 +36,13 @@ uint64_t kIterations; // Send a world control message. void worldControl(bool _paused, uint64_t _steps) { - std::function cb = - [&](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [&](const msgs::Boolean &/*_rep*/, const bool _result) { EXPECT_TRUE(_result); }; - ignition::msgs::WorldControl req; + msgs::WorldControl req; req.set_pause(_paused); req.set_multi_step(_steps); transport::Node node; @@ -58,8 +58,8 @@ void testPaused(bool _paused) transport::Node node; bool paused = !_paused; - std::function cb = - [&](const ignition::msgs::WorldStatistics &_msg) + std::function cb = + [&](const msgs::WorldStatistics &_msg) { std::unique_lock lock(mutex); paused = _msg.paused(); @@ -81,8 +81,8 @@ uint64_t iterations() transport::Node node; uint64_t iterations = 0; - std::function cb = - [&](const ignition::msgs::WorldStatistics &_msg) + std::function cb = + [&](const msgs::WorldStatistics &_msg) { std::unique_lock lock(mutex); iterations = _msg.iterations(); diff --git a/test/integration/pose_publisher_system.cc b/test/integration/pose_publisher_system.cc index f620734a9d..c9f6729f61 100644 --- a/test/integration/pose_publisher_system.cc +++ b/test/integration/pose_publisher_system.cc @@ -143,8 +143,8 @@ TEST_F(PosePublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd)) [&modelName, &baseName, &lowerLinkName, &upperLinkName, &sensorName, &poses, &basePoses, &lowerLinkPoses, &upperLinkPoses, &sensorPoses, ×tamps]( - const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // get our double pendulum model auto id = _ecm.EntityByComponents( @@ -191,7 +191,7 @@ TEST_F(PosePublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd)) // timestamps auto simTimeSecNsec = - ignition::math::durationToSecNsec(_info.simTime); + math::durationToSecNsec(_info.simTime); timestamps.push_back( math::secNsecToTimePoint( simTimeSecNsec.first, @@ -240,7 +240,7 @@ TEST_F(PosePublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd)) // sort the pose msgs according to timestamp std::sort(poseMsgs.begin(), poseMsgs.end(), []( - const ignition::msgs::Pose &_l, const ignition::msgs::Pose &_r) + const msgs::Pose &_l, const msgs::Pose &_r) { std::chrono::steady_clock::time_point lt = math::secNsecToTimePoint( @@ -440,8 +440,8 @@ TEST_F(PosePublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StaticPosePublisher)) [&modelName, &baseName, &lowerLinkName, &upperLinkName, &sensorName, &poses, &basePoses, &lowerLinkPoses, &upperLinkPoses, &sensorPoses, ×tamps, &staticPoseTimestamps]( - const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // get our double pendulum model auto id = _ecm.EntityByComponents( @@ -488,7 +488,7 @@ TEST_F(PosePublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StaticPosePublisher)) // timestamps auto simTimeSecNsec = - ignition::math::durationToSecNsec(_info.simTime); + math::durationToSecNsec(_info.simTime); timestamps.push_back( math::secNsecToTimePoint( simTimeSecNsec.first, simTimeSecNsec.second)); diff --git a/test/integration/rgbd_camera.cc b/test/integration/rgbd_camera.cc index 2bd7a8e0f8..6194e3b564 100644 --- a/test/integration/rgbd_camera.cc +++ b/test/integration/rgbd_camera.cc @@ -104,9 +104,9 @@ TEST_F(RgbdCameraTest, IGN_UTILS_TEST_DISABLED_ON_MAC(RgbdCameraBox)) // Lock access to buffer and don't release it mutex.lock(); - EXPECT_DOUBLE_EQ(depthBuffer[left], ignition::math::INF_D); + EXPECT_DOUBLE_EQ(depthBuffer[left], math::INF_D); EXPECT_NEAR(depthBuffer[mid], expectedRangeAtMidPointBox1, DEPTH_TOL); - EXPECT_DOUBLE_EQ(depthBuffer[right], ignition::math::INF_D); + EXPECT_DOUBLE_EQ(depthBuffer[right], math::INF_D); delete[] depthBuffer; } diff --git a/test/integration/save_world.cc b/test/integration/save_world.cc index 329182edea..0eaf3654e6 100644 --- a/test/integration/save_world.cc +++ b/test/integration/save_world.cc @@ -115,7 +115,7 @@ TEST_F(SdfGeneratorFixture, // This has to be different from the backpack in order to test SDFormat // generation for a Fuel URI that was not known when simulation started. const std::string groundPlaneUri = - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/ground plane"; + "https://fuel.gazebosim.org/1.0/OpenRobotics/models/ground plane"; transport::Node node; { diff --git a/test/integration/scene_broadcaster_system.cc b/test/integration/scene_broadcaster_system.cc index 53fb52b802..ac452e6955 100644 --- a/test/integration/scene_broadcaster_system.cc +++ b/test/integration/scene_broadcaster_system.cc @@ -57,7 +57,7 @@ class SceneBroadcasterTest TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PoseInfo)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); @@ -107,7 +107,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PoseInfo)) TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneInfo)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); @@ -124,7 +124,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneInfo)) bool result{false}; unsigned int timeout{5000}; - ignition::msgs::Scene res; + msgs::Scene res; EXPECT_TRUE(node.Request("/world/default/scene/info", timeout, res, result)); EXPECT_TRUE(result); @@ -142,7 +142,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneInfo)) } // Repeat the request to make sure the same information is returned - ignition::msgs::Scene res2; + msgs::Scene res2; EXPECT_TRUE(node.Request("/world/default/scene/info", timeout, res2, result)); EXPECT_TRUE(result); @@ -153,7 +153,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneInfo)) TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneGraph)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); @@ -170,7 +170,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneGraph)) bool result{false}; unsigned int timeout{5000}; - ignition::msgs::StringMsg res; + msgs::StringMsg res; EXPECT_TRUE(node.Request("/world/default/scene/graph", timeout, res, result)); EXPECT_TRUE(result); @@ -193,7 +193,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneGraph)) TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneTopic)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); @@ -225,7 +225,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneTopic)) bool result{false}; unsigned int timeout{5000}; - ignition::msgs::Scene msg; + msgs::Scene msg; EXPECT_TRUE(node.Request("/world/default/scene/info", timeout, msg, result)); EXPECT_TRUE(result); @@ -238,7 +238,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneTopicSensors)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/altimeter_with_pose.sdf"); @@ -270,7 +270,7 @@ TEST_P(SceneBroadcasterTest, bool result{false}; unsigned int timeout{5000}; - ignition::msgs::Scene msg; + msgs::Scene msg; EXPECT_TRUE(node.Request("/world/altimeter_sensor/scene/info", timeout, msg, result)); @@ -289,7 +289,7 @@ TEST_P(SceneBroadcasterTest, TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(DeletedTopic)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); @@ -350,7 +350,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(DeletedTopic)) TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SpawnedModel)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); @@ -396,8 +396,8 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SpawnedModel)) // Check that the model is in the scene/infor response { - ignition::msgs::Empty req; - ignition::msgs::Scene rep; + msgs::Empty req; + msgs::Scene rep; bool result; unsigned int timeout = 2000; EXPECT_TRUE(node.Request("/world/default/scene/info", req, timeout, @@ -420,7 +420,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SpawnedModel)) TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(State)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); @@ -511,7 +511,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(State)) std::string reqSrv = "/state_async_callback_test"; node.Advertise(reqSrv, cbAsync); - ignition::msgs::StringMsg req; + msgs::StringMsg req; req.set_data(reqSrv); node.Request("/world/default/state_async", req); @@ -531,7 +531,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(State)) TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StateStatic)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/empty.sdf"); diff --git a/test/integration/sdf_frame_semantics.cc b/test/integration/sdf_frame_semantics.cc index cdb579e224..77ac574b12 100644 --- a/test/integration/sdf_frame_semantics.cc +++ b/test/integration/sdf_frame_semantics.cc @@ -64,7 +64,7 @@ class SdfFrameSemanticsTest : public InternalFixture<::testing::Test> EXPECT_FALSE(*this->server->Running(0)); // A pointer to the ecm. This will be valid once we run the mock system relay->OnPreUpdate( - [this](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [this](const UpdateInfo &, EntityComponentManager &_ecm) { this->ecm = &_ecm; }); @@ -97,9 +97,9 @@ class SdfFrameSemanticsTest : public InternalFixture<::testing::Test> this->creator->SetParent(modelEntity, worldEntity); } - public: gazebo::Model GetModel(const std::string &_name) + public: Model GetModel(const std::string &_name) { - return gazebo::Model(this->ecm->EntityByComponents( + return Model(this->ecm->EntityByComponents( components::Model(), components::Name(_name))); } @@ -164,8 +164,8 @@ TEST_F(SdfFrameSemanticsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LinkRelativeTo)) EXPECT_NE(link2, kNullEntity); // Expect the pose of L2 relative to model to be 0 0 1 0 0 pi - ignition::math::Pose3d expRelPose(0, 0, 1, 0, 0, IGN_PI); - ignition::math::Pose3d expWorldPose(0, 0, 3, 0, 0, IGN_PI); + math::Pose3d expRelPose(0, 0, 1, 0, 0, IGN_PI); + math::Pose3d expWorldPose(0, 0, 3, 0, 0, IGN_PI); EXPECT_EQ(expRelPose, this->GetPose(link2)); @@ -231,7 +231,7 @@ TEST_F(SdfFrameSemanticsTest, JointRelativeTo) // Expect the pose of J1 relative to model to be the same as L2 (default // behavior) - ignition::math::Pose3d expWorldPose(1, 0, 2, 0, 0, 0); + math::Pose3d expWorldPose(1, 0, 2, 0, 0, 0); // Expect the pose of J2 relative to model to be the same as L2 (non default // behavior due to "relative_to='L2'") @@ -286,7 +286,7 @@ TEST_F(SdfFrameSemanticsTest, VisualCollisionRelativeTo) // Expect the pose of v1 and relative to L2 (their parent link) to be the same // as the pose of L1 relative to L2 - ignition::math::Pose3d expPose(0, 0, -1, 0, 0, 0); + math::Pose3d expPose(0, 0, -1, 0, 0, 0); EXPECT_EQ(expPose, this->GetPose(visual)); EXPECT_EQ(expPose, this->GetPose(collision)); @@ -334,13 +334,13 @@ TEST_F(SdfFrameSemanticsTest, ExplicitFramesWithLinks) // Expect the pose of L1 and relative to M to be the same // as the pose of F1 relative to M - ignition::math::Pose3d link1ExpRelativePose(0, 0, 1, 0, 0, 0); + math::Pose3d link1ExpRelativePose(0, 0, 1, 0, 0, 0); EXPECT_EQ(link1ExpRelativePose, this->GetPose(link1)); // Expect the pose of L2 and relative to M to be the same // as the pose of F2, which is at the origin of M - ignition::math::Pose3d link2ExpRelativePose = ignition::math::Pose3d::Zero; + math::Pose3d link2ExpRelativePose = math::Pose3d::Zero; EXPECT_EQ(link2ExpRelativePose, this->GetPose(link2)); @@ -389,7 +389,7 @@ TEST_F(SdfFrameSemanticsTest, ExplicitFramesWithJoints) this->server->Run(true, 1, false); // Expect the pose of J1 relative to model to be the same as F1 in world - ignition::math::Pose3d expWorldPose(1, 0, 2, 0, 0, 0); + math::Pose3d expWorldPose(1, 0, 2, 0, 0, 0); // TODO(anyone) Enable the following expectation when a joint's WorldPose // can be computed by ign-physics. // EXPECT_EQ(expWorldPose, this->GetWorldPose(joint1)); @@ -440,7 +440,7 @@ TEST_F(SdfFrameSemanticsTest, ExplicitFramesWithVisualAndCollision) // Expect the pose of v1 and relative to L1 (their parent link) to be the same // as the pose of F1 relative to L1 - ignition::math::Pose3d expPose(0, 0, 1, 0, 0, 0); + math::Pose3d expPose(0, 0, 1, 0, 0, 0); EXPECT_EQ(expPose, this->GetPose(visual)); EXPECT_EQ(expPose, this->GetPose(collision)); diff --git a/test/integration/sdf_include.cc b/test/integration/sdf_include.cc index dd9e5caadb..133810d197 100644 --- a/test/integration/sdf_include.cc +++ b/test/integration/sdf_include.cc @@ -39,13 +39,13 @@ TEST_F(SdfInclude, IGN_UTILS_TEST_DISABLED_ON_WIN32(DownloadFromFuel)) std::string path = common::cwd() + "/test_cache"; // Configure the gazebo server, which will cause a model to be downloaded. - gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetResourceCache(path); serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/include.sdf"); - gazebo::Server server(serverConfig); + Server server(serverConfig); EXPECT_TRUE(common::exists(path + - "/fuel.ignitionrobotics.org/openrobotics/models/ground plane" + + "/fuel.gazebosim.org/openrobotics/models/ground plane" + "/1/model.sdf")); } diff --git a/test/integration/sensors_system.cc b/test/integration/sensors_system.cc index 789d57fefd..b843da142b 100644 --- a/test/integration/sensors_system.cc +++ b/test/integration/sensors_system.cc @@ -111,7 +111,7 @@ class SensorsFixture : public InternalFixture> systemPtr->QueryInterface()); } - public: ignition::gazebo::SystemPluginPtr systemPtr; + public: gazebo::SystemPluginPtr systemPtr; public: gazebo::MockSystem *mockSystem; private: gazebo::SystemLoader sm; @@ -162,7 +162,7 @@ void testDefaultTopics() /// are removed and then added back TEST_F(SensorsFixture, IGN_UTILS_TEST_DISABLED_ON_MAC(HandleRemovedEntities)) { - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; const std::string sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/sensor.sdf"; diff --git a/test/integration/thermal_system.cc b/test/integration/thermal_system.cc index 68d1e566ec..ba9308f88a 100644 --- a/test/integration/thermal_system.cc +++ b/test/integration/thermal_system.cc @@ -67,11 +67,11 @@ TEST_F(ThermalTest, IGN_UTILS_TEST_DISABLED_ON_MAC(TemperatureComponent)) std::map entityTempRange; std::map heatSignatures; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_id, + [&](const Entity &_id, const components::Temperature *_temp, const components::Name *_name) -> bool { diff --git a/test/integration/touch_plugin.cc b/test/integration/touch_plugin.cc index f1ae4745ad..36eedfb8c7 100644 --- a/test/integration/touch_plugin.cc +++ b/test/integration/touch_plugin.cc @@ -100,7 +100,7 @@ TEST_F(TouchPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(OneLink)) std::this_thread::sleep_for(std::chrono::milliseconds(30)); } // Known to fail on OSX, see -// https://github.com/ignitionrobotics/ign-gazebo/issues/22 +// https://github.com/gazebosim/gz-sim/issues/22 #if !defined (__APPLE__) EXPECT_TRUE(whiteTouched); #endif @@ -180,7 +180,7 @@ TEST_F(TouchPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StartDisabled)) std::this_thread::sleep_for(std::chrono::milliseconds(30)); } // Known to fail on OSX, see -// https://github.com/ignitionrobotics/ign-gazebo/issues/22 +// https://github.com/gazebosm/gz-sim/issues/22 #if !defined (__APPLE__) EXPECT_TRUE(blueTouched); #endif diff --git a/test/integration/tracked_vehicle_system.cc b/test/integration/tracked_vehicle_system.cc index d98434d463..2d8180bf29 100644 --- a/test/integration/tracked_vehicle_system.cc +++ b/test/integration/tracked_vehicle_system.cc @@ -70,7 +70,7 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> bool &_shouldSkip) { #if __APPLE__ - // until https://github.com/ignitionrobotics/ign-gazebo/issues/806 is fixed + // until https://github.com/gazebosim/gz-sim/issues/806 is fixed _shouldSkip = true; #else _shouldSkip = false; @@ -90,7 +90,7 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> << "Failed to find plugin [" << *pluginLib << "]"; // Load engine plugin - ignition::plugin::Loader pluginLoader; + plugin::Loader pluginLoader; auto plugins = pluginLoader.LoadLib(pathToLib); ASSERT_FALSE(plugins.empty()) << "Unable to load the [" << pathToLib << "] library"; @@ -133,8 +133,8 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> // Create a system that records the vehicle poses test::Relay ecmGetterSystem; EntityComponentManager* ecm {nullptr}; - ecmGetterSystem.OnPreUpdate([&ecm](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + ecmGetterSystem.OnPreUpdate([&ecm](const UpdateInfo &, + EntityComponentManager &_ecm) { if (ecm == nullptr) ecm = &_ecm; @@ -156,8 +156,8 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> test::Relay testSystem; Entity modelEntity {kNullEntity}; std::vector poses; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { modelEntity = _ecm.EntityByComponents( components::Model(), @@ -253,7 +253,7 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> poses.clear(); - gazebo::Model model(modelEntity); + Model model(modelEntity); // Move the robot somewhere to free space without obstacles. model.SetWorldPoseCmd(*ecm, math::Pose3d(10, 10, 0.1, 0, 0, 0)); @@ -455,8 +455,8 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> // Create a system that records the vehicle poses test::Relay ecmGetterSystem; EntityComponentManager* ecm {nullptr}; - ecmGetterSystem.OnPreUpdate([&ecm](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + ecmGetterSystem.OnPreUpdate([&ecm](const UpdateInfo &, + EntityComponentManager &_ecm) { if (ecm == nullptr) ecm = &_ecm; @@ -478,8 +478,8 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> test::Relay testSystem; Entity boxEntity {kNullEntity}; std::vector poses; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { boxEntity = _ecm.EntityByComponents( components::Model(), diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index 4a37616c6f..47b2f7f219 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -75,8 +75,8 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Create)) // shared pointer owned by the SimulationRunner. EntityComponentManager *ecm{nullptr}; test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &_ecm) { ecm = &_ecm; }); @@ -354,8 +354,8 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Remove)) // shared pointer owned by the SimulationRunner. EntityComponentManager *ecm{nullptr}; test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &_ecm) { ecm = &_ecm; }); @@ -538,8 +538,8 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Pose)) // Create a system just to get the ECM EntityComponentManager *ecm{nullptr}; test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &_ecm) { ecm = &_ecm; }); @@ -712,8 +712,8 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PoseVector)) // Create a system just to get the ECM EntityComponentManager *ecm{nullptr}; test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &_ecm) { ecm = &_ecm; }); @@ -1047,8 +1047,8 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Physics)) // Create a system just to get the ECM EntityComponentManager *ecm{nullptr}; test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &_ecm) { ecm = &_ecm; }); diff --git a/test/integration/velocity_control_system.cc b/test/integration/velocity_control_system.cc index 6925dbca76..31ac1d6f1a 100644 --- a/test/integration/velocity_control_system.cc +++ b/test/integration/velocity_control_system.cc @@ -58,8 +58,8 @@ class VelocityControlTest test::Relay testSystem; std::vector poses; - testSystem.OnPostUpdate([&poses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&poses](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto id = _ecm.EntityByComponents( components::Model(), @@ -145,8 +145,8 @@ class VelocityControlTest std::vector modelPoses; std::vector linkPoses; testSystem.OnPostUpdate([&linkPoses, &modelPoses]( - const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &, + const EntityComponentManager &_ecm) { auto modelId = _ecm.EntityByComponents( components::Model(), diff --git a/test/integration/wheel_slip.cc b/test/integration/wheel_slip.cc index 24a9f3e697..a08991c360 100644 --- a/test/integration/wheel_slip.cc +++ b/test/integration/wheel_slip.cc @@ -82,7 +82,7 @@ class WheelSlipTest : public InternalFixture<::testing::Test> public: double drumSpeed = 0.0; /// \brief Steer angle to apply. - public: ignition::math::Angle steer; + public: math::Angle steer; /// \brief Suspension force to apply in N. public: double suspForce = 0.0; @@ -120,10 +120,10 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TireDrum)) EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); - gazebo::EntityComponentManager *ecm = nullptr; + EntityComponentManager *ecm = nullptr; test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &_ecm) { ecm = &_ecm; }); @@ -141,7 +141,7 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TireDrum)) Entity worldEntity = ecm->EntityByComponents(components::World()); - EXPECT_NE(gazebo::kNullEntity, worldEntity); + EXPECT_NE(kNullEntity, worldEntity); // Get both models Entity tireEntity = @@ -152,8 +152,8 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TireDrum)) ecm->EntityByComponents(components::Model(), components::Name("drum")); - EXPECT_NE(gazebo::kNullEntity, tireEntity); - EXPECT_NE(gazebo::kNullEntity, drumEntity); + EXPECT_NE(kNullEntity, tireEntity); + EXPECT_NE(kNullEntity, drumEntity); Entity wheelLinkEntity = ecm->EntityByComponents( components::ParentEntity(tireEntity), @@ -165,8 +165,8 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TireDrum)) components::Name("link"), components::Link()); - EXPECT_NE(gazebo::kNullEntity, wheelLinkEntity); - EXPECT_NE(gazebo::kNullEntity, drumLinkEntity); + EXPECT_NE(kNullEntity, wheelLinkEntity); + EXPECT_NE(kNullEntity, drumLinkEntity); auto wheelInertialComp = ecm->Component(wheelLinkEntity); @@ -193,8 +193,8 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TireDrum)) components::Name("collision"), components::Collision()); - EXPECT_NE(gazebo::kNullEntity, collisionWheelLinkEntity); - EXPECT_NE(gazebo::kNullEntity, collisionDrumLinkEntity); + EXPECT_NE(kNullEntity, collisionWheelLinkEntity); + EXPECT_NE(kNullEntity, collisionDrumLinkEntity); auto wheelCollisionComp = ecm->Component(collisionWheelLinkEntity); @@ -240,19 +240,16 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TireDrum)) // const double kp = surfaceContactOde->GetElement("kp")->Get(); // ASSERT_EQ(kp, 250e3); - double modelMass = 0.0; for (const auto &linkName : linksToCheck) { Entity linkEntity = ecm->EntityByComponents( components::ParentEntity(tireEntity), components::Name(linkName), components::Link()); - EXPECT_NE(gazebo::kNullEntity, linkEntity); + EXPECT_NE(kNullEntity, linkEntity); auto inertialComp = ecm->Component(linkEntity); EXPECT_NE(nullptr, inertialComp); - - modelMass += inertialComp->Data().MassMatrix().Mass(); } // Get axle wheel and steer joint of wheel model @@ -261,14 +258,14 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TireDrum)) components::Name("axle_wheel"), components::Joint()); - ASSERT_NE(gazebo::kNullEntity, wheelAxleJointEntity); + ASSERT_NE(kNullEntity, wheelAxleJointEntity); Entity wheelSteerJointEntity = ecm->EntityByComponents( components::ParentEntity(tireEntity), components::Name("steer"), components::Joint()); - ASSERT_NE(gazebo::kNullEntity, wheelSteerJointEntity); + ASSERT_NE(kNullEntity, wheelSteerJointEntity); const double wheelSpeed = -25.0 * metersPerMile / secondsPerHour / wheelRadius; @@ -382,10 +379,10 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TricyclesUphill)) EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); - gazebo::EntityComponentManager *ecm = nullptr; + EntityComponentManager *ecm = nullptr; test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &_ecm) { ecm = &_ecm; }); @@ -403,7 +400,7 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TricyclesUphill)) Entity worldEntity = ecm->EntityByComponents(components::World()); - EXPECT_NE(gazebo::kNullEntity, worldEntity); + EXPECT_NE(kNullEntity, worldEntity); auto gravity = ecm->Component(worldEntity); @@ -415,14 +412,14 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TricyclesUphill)) ecm->EntityByComponents(components::Model(), components::Name("trisphere_cycle0")); - EXPECT_NE(gazebo::kNullEntity, trisphereCycle0Entity); + EXPECT_NE(kNullEntity, trisphereCycle0Entity); Entity trisphereCycle1Entity = ecm->EntityByComponents(components::Model(), components::Name("trisphere_cycle1")); - EXPECT_NE(gazebo::kNullEntity, trisphereCycle1Entity); + EXPECT_NE(kNullEntity, trisphereCycle1Entity); // Check rear left wheel of first model Entity wheelRearLeftEntity = ecm->EntityByComponents( @@ -430,7 +427,7 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TricyclesUphill)) components::Name("wheel_rear_left"), components::Link()); - EXPECT_NE(gazebo::kNullEntity, wheelRearLeftEntity); + EXPECT_NE(kNullEntity, wheelRearLeftEntity); Entity wheelRearLeftCollisionEntity = ecm->EntityByComponents( components::ParentEntity(wheelRearLeftEntity), @@ -450,28 +447,28 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TricyclesUphill)) components::Name("wheel_rear_left_spin"), components::Joint()); - EXPECT_NE(gazebo::kNullEntity, wheelRearLeftSpin0Entity); + EXPECT_NE(kNullEntity, wheelRearLeftSpin0Entity); Entity wheelRearRightSpin0Entity = ecm->EntityByComponents( components::ParentEntity(trisphereCycle0Entity), components::Name("wheel_rear_right_spin"), components::Joint()); - EXPECT_NE(gazebo::kNullEntity, wheelRearRightSpin0Entity); + EXPECT_NE(kNullEntity, wheelRearRightSpin0Entity); Entity wheelRearLeftSpin1Entity = ecm->EntityByComponents( components::ParentEntity(trisphereCycle1Entity), components::Name("wheel_rear_left_spin"), components::Joint()); - EXPECT_NE(gazebo::kNullEntity, wheelRearLeftSpin1Entity); + EXPECT_NE(kNullEntity, wheelRearLeftSpin1Entity); Entity wheelRearRightSpin1Entity = ecm->EntityByComponents( components::ParentEntity(trisphereCycle1Entity), components::Name("wheel_rear_right_spin"), components::Joint()); - EXPECT_NE(gazebo::kNullEntity, wheelRearRightSpin1Entity); + EXPECT_NE(kNullEntity, wheelRearRightSpin1Entity); // Set speed of both models const double angularSpeed = 6.0; @@ -526,8 +523,8 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TricyclesUphill)) } test::Relay testSlipSystem; - testSlipSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &) + testSlipSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &) { auto wheelRearLeftVelocity0Cmd = ecm->Component(wheelRearLeftSpin0Entity); diff --git a/test/integration/wind_effects.cc b/test/integration/wind_effects.cc index bd49f777f8..8c4e11b9a6 100644 --- a/test/integration/wind_effects.cc +++ b/test/integration/wind_effects.cc @@ -85,7 +85,7 @@ class LinkComponentRecorder if (_createComp) { this->mockSystem->preUpdateCallback = - [this](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [this](const UpdateInfo &, EntityComponentManager &_ecm) { auto linkEntity = _ecm.EntityByComponents( components::Link(), components::Name(this->linkName)); @@ -101,8 +101,8 @@ class LinkComponentRecorder } this->mockSystem->postUpdateCallback = - [this](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [this](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto linkEntity = _ecm.EntityByComponents( components::Link(), components::Name(this->linkName)); diff --git a/test/performance/level_manager.cc b/test/performance/level_manager.cc index ccd9032c31..022dbe0da2 100644 --- a/test/performance/level_manager.cc +++ b/test/performance/level_manager.cc @@ -38,10 +38,10 @@ TEST(LevelManagerPerfrormance, IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelVsNoLevel)) common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", + common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/level_performance.sdf"); math::Stopwatch watch; @@ -53,7 +53,7 @@ TEST(LevelManagerPerfrormance, IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelVsNoLevel)) // measuring time differences between levels and no levels. { serverConfig.SetUseLevels(true); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ns); server.Run(true, 1, false); @@ -62,7 +62,7 @@ TEST(LevelManagerPerfrormance, IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelVsNoLevel)) // Server with levels { serverConfig.SetUseLevels(true); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ns); watch.Start(true); @@ -74,7 +74,7 @@ TEST(LevelManagerPerfrormance, IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelVsNoLevel)) // Server without levels { serverConfig.SetUseLevels(false); - gazebo::Server serverNoLevels(serverConfig); + Server serverNoLevels(serverConfig); serverNoLevels.SetUpdatePeriod(1ns); watch.Start(true); diff --git a/test/performance/sdf_runner.cc b/test/performance/sdf_runner.cc index b2fdfe1818..0fbb754926 100644 --- a/test/performance/sdf_runner.cc +++ b/test/performance/sdf_runner.cc @@ -33,7 +33,7 @@ using namespace gazebo; ////////////////////////////////////////////////// int main(int _argc, char** _argv) { - ignition::common::Console::SetVerbosity(4); + common::Console::SetVerbosity(4); std::string sdfFile{""}; if (_argc >= 2) @@ -56,7 +56,7 @@ int main(int _argc, char** _argv) } igndbg << "Update rate: " << updateRate << std::endl; - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; if (!serverConfig.SetSdfFile(sdfFile)) { ignerr << "Failed to set SDF file [" << sdfFile << "]" << std::endl; @@ -68,23 +68,23 @@ int main(int _argc, char** _argv) serverConfig.SetUpdateRate(updateRate); // Create the Gazebo server - ignition::gazebo::Server server(serverConfig); + Server server(serverConfig); - ignition::transport::Node node; + transport::Node node; - std::vector msgs; + std::vector msgs; msgs.reserve(iterations); - std::function cb = - [&](const ignition::msgs::Clock &_msg) + std::function cb = + [&](const msgs::Clock &_msg) { msgs.push_back(_msg); }; double progress = 0; - std::function cb2 = - [&](const ignition::msgs::WorldStatistics &_msg) + std::function cb2 = + [&](const msgs::WorldStatistics &_msg) { double nIters = static_cast(_msg.iterations()); nIters = nIters / iterations * 100; diff --git a/test/plugins/TestSystem.cc b/test/plugins/TestSystem.cc index 94896f5185..2c362db0b8 100644 --- a/test/plugins/TestSystem.cc +++ b/test/plugins/TestSystem.cc @@ -32,6 +32,6 @@ TestSystem::TestSystem() TestSystem::~TestSystem() = default; // Register this plugin -IGNITION_ADD_PLUGIN(TestSystem, ignition::gazebo::System) +IGNITION_ADD_PLUGIN(TestSystem, System) IGNITION_ADD_PLUGIN_ALIAS(TestSystem, "ignition::gazebo::TestSystem") diff --git a/test/worlds/breadcrumbs.sdf b/test/worlds/breadcrumbs.sdf index a8b75f9899..bbc2bac8e6 100644 --- a/test/worlds/breadcrumbs.sdf +++ b/test/worlds/breadcrumbs.sdf @@ -481,7 +481,7 @@ -2.2 0 5 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Cardboard box + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Cardboard box diff --git a/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.sdf b/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.sdf new file mode 100644 index 0000000000..b9386ade65 --- /dev/null +++ b/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.sdf @@ -0,0 +1,5 @@ + + + + + diff --git a/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.world b/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.world new file mode 100644 index 0000000000..b9386ade65 --- /dev/null +++ b/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.world @@ -0,0 +1,5 @@ + + + + + diff --git a/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/thumbnails/1.png b/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/thumbnails/1.png new file mode 100644 index 0000000000000000000000000000000000000000..a72d5aa96bff8d0820bac6184f5e3d8370725889 GIT binary patch literal 6279 zcmc(kWmpu^zsCnf=@3y`8WAJ}q(i!-k(83|j-^GULt0vPX;@YomJ&gbTpFoGL_lHz z=~}qseRbd5cmMm`d7d-#%sl7J%sKOm&+j|2+M3EFgtUYJ0FbDvDCmO6Rj_5@-v##@ zQaice0oPkjRUaSRg7Ix)z;gl*6=QDzAnpCva5A__>A;ILK8i*@dhT{U{#IVLfWN;# zucMo@x3!grEw8(meeSL#EdWsCsw&9p2jpRvARY@d`FQ(`_z`6)I>o$`;_x(adiBgT z?xcJTYYEph4##@O`G(0Qmu5kXrauzXG`TeDVwWSuA(1<`dy?!T(H7Q_Z$25zFzc5( z@A`&alTtOa`m&Tw4a%!aLGS@r<<<`wmoah;wJ9s2%+SKFqc5l7c%~LBD>zIsvlby( z$P0W|iD^H7fZ2yA>K^m^FZ?XU8-_yk>W|bp+Yo(yV%%6b&1o!`| z(-vm;%e(3-L{)ngVw+pHwXXWWkc8~HkGpl&ZtDyFPg4Hpi!!Qf)x*_fs626RPl?M0 zJxgklw`)eXhiWg21^PYvFgqyhm&10oPSn#OQaAfBKMMNN|2f;AVz7w6l8A%zkh|~D zUp9S^-wog*6tN#(hL6WWRmgFf?TiF&nKrsLcvAO~wCs<*=L37Me$CV9TzrlRbh$nV zc7+Nny&Dg?nA%jYf{RcRI_50oCi4YQk>WR%&Mqk~5eZIk4cvX%j7mp^> zItYi!kvdn}Nqoge%pyh!Hlt8T6k%z3YZ!;)3%y6HnU-Oe;mwiuQqgGRg}Au1(@i-B z)|G+^@4K&{UVPEUz1W19&9W`JF>I2cj3lFc{WgCT~@{&sb=GR_P3I2JK+>5JKHn(WEvNjWJB+t+{klr1vx#vS-iGAT1(KjnS;Xr#{e zykw2I=T9F;|3R6383S6;-8zOOqYtsIf=wyJi+C&YHRW?DydGog2tkTrd$ta?BB`(h z5#;xIlw+-^MLyLvc-;cR2?V&4L^)uNot4nR?5#j?q(r6Nx?MrWpi^VuUk~hxA%ks_ zCqych?R{k&m;EcnjKftr#^paWJLeKQl+#eoRLl~_0#Q?bEnH-B9=~UHl=BhLdz>-i zxIVK{5WL%X76<^2j*c#Hm|x3`js!74b#eFdgy!h3rg<5Emj@~EMeFj|HQ%*%jaF^d z6eSJ&y+6?>yhXPagahD*n=1Fh@RF}hgUMGJqyt){Pz9&X74%7wm=Vl~fBujL^6{a9 zPJ%{L`opZwe9o9y{a5;8iFa9>{WKaf_!Ab2>znIYdZPx5y-J@SIw?B7=gw$)oSYXN z%{E|LA-P!)EZRxh?->X&F46s)yUB+<1;_M0$5duzajS8o)f?fOW$_<1)^l~m$cgp) zW}nd}ghC+0&;8!qUQ#%{7v-6I=GY~F0girOd^o0GLNi%fTnH)9ve@UX77gR!d%|c~ zpOt>T)=}Obo8PRd)9lIj?F3BGLya08dD-$70H&MGR z7w9iXyb#8PVR8AQ56q!+*?RW8d105qrTzn#Ex}@_!%W-dgV=v<{I8CKlbcD?M;^HC zH{01%GY;9)N2GeqI1HbBKYzP9iQrspl$KMBK?NUV-@p;@o1$^cox9D za~EdUhH5d1Iam(|Y0zc)&|wYcKr6PMZ~V ziUHuNp)19T+RVg+Hb~~OA$LV=mE!}K02iM!Oh=>Am1pzexm0y!O=pd~=}aw&L$z~z zwwv0G5m!94+)txzm$uJ|b0jY0AujV;h*DJ#zgvU>%*=DjvS-IkOPNj2;PuI~?;QHC z-Dd5LGE1612W{I4(U$#Q<7Dh`{#`t|$$~4}ySpB%!182I(1an%^L|}@ouOnn9r0an zU02g4gv+3dK(or43R|l8W^$If$=)4^4mp7gX11U2^gP7hY|BWUpL&s%&y;88o5Jyw zldnq`81oLKVbdvvp;wd77nWl2GR7@`BQM%C!59VrKfmVX>*{sP8P5@f#ja*2aBQ6Y zJ|obfd=3ClhaM&-B|o$?5xksCs4A>Fzmk^sHa+}HW+HtS$V6=!PZZa`R@fDUUD9f7 zXm0-l3vp@U2}**NzuMDqb#$-r)@YL^Yrc8m{M=+Vmi00ErM`c!nC_sL3(gmKTUc-d z$~4_jNR~Xn8fEtrca+0+uC8WecqI5C@PZsS#5?Ga8;l3)l!}m7T(5R$lwjSWf2Xp` zLYdu7KN#{`n7+D%jiN{QVxi@CfqlVic`Agtq@{4SDg2>xm)MA;`xxCvaw>sHIp+H0 zleKYTGYaB63==l$0?fkt;-Ug)BUT&yxpptN1#*X3XMDDcW!*oirvBap@<(y07b5Ie zm>527|2(Ey&)S<{K0qvCu3rlN5Ovjr)a4WKA2JK4dtS!Z?{?mfVT!z%zYx)#6TZb{9(H`Z(cE@lVqoGR z)zi;PINsLyHs5}2bWma->nf*z0(=_1aY}O$by2zgaNVheKkGrFl12olgMK7eHOF*< zIl@0zV|`!(I)Ro9DzJwiE3(|H3v21>mD;Ew#=R8;+AuqQgeGnZ+bbItxWVO1rO5y* zbE^#{cS%d*%$$!oKYF~Xr7047d40?AGqk(9I{jI<7Zd**2hHbS{3pS1pQvK2k|hOS zOi;u+ZLm~GkEtj1o)LUR>1hDfaFMpk;|!t$!u94rI<;skg(@!;QV=0zcAla?TEBrk z*n!#exg7iDGt*n~Y7l)Rd4tT(rgHU{-*kyJh z4iG@qQA%efqB#s%e?$=7a}MR~LlYf*v+p{y?J#H5w8d6!Ztgu{pk@$VEyI#TF!h@M zQA;gee$y2E`jxqF3AEvB;~Zv(vP~c%#i4hn44Vi5FF#aJ-1&PN8AqNrU6@xOsfhO{ z@VxHX?2p`UcfQpR%qM6j2%kAD->YzGGz#l9DMUl|^0l;3FT)J3)wv(XL8A!xeP4!G zc!L-@Z7_2!l#w;~^fJp?&ZV3lcp>k&2<+Eqo@64?MQFrf@GlWN0_f+8=7IxB1TtXl zS3D8={o@xWc#0>jb8WvvuHI#mUAwq=?TFZG7Mx@4nws@?2ECQ4zRj~@hY#B!V`4@h zs@>Qqm~R(_vxc7k=>1WNm@qxz>6f0>&dKfwItjc#4U(rQSP-bEO{Ven;iWLe;H#!e z1LVIh(ig@j|6<9cuYdk=3Q_sTF3_M)ml6XJEyhqLij8IQo5nkPUmr8`#;~bgOglA3 zgF}IE&bZ&{L0d%b9hWnLr%*n!95aZ`Q(n$pnnL>I3^To&oWY5~SOwq9=u3491~{0% zX@QoUat$Wxv8W%~+4>+?1X4`j2F~Os8Ku|E4y1W4>{OfEEzER626Wb`@mh}YiePQl zH=n%sA)6)DP|iv`WxOt{q0b|w2bE&srtSv2e>TrbIpf%5$zNykY^&*n>Zohljkd?> z6FfrnultD6fv&#EX~ko>+!g3I(CnkzIkz*sGj!Z|?5>XZOcdR-1scp&RDKU%B&$_h z&?j`B!9i}+2(fxzi zX>f&Nqnfeu*aruO!S?ockBL|RoRx7+kzVC@b z!qavKeq58|b{iV%clrJPnL>9ENSnwJ*s$WTeO-w)`}diW!Bq2zH2P2&xs?CLkW>!` zc-beRT=jzgCw_Df!43aFbneOPOWO>!2e*Kq5VR1#fOdNM$naG{Fg~~VAUy#JgS~=$9RFStd$?S)laJ?$jSpQ7=(v`2QRHLR+(Jk=zBNoP3Qdiu2Q3aV<8A1 zC%+Zl40dz>%BBm_CM-VI4F2_ebJ?ePq0wr%!LIKsXB@Q2y&NIbsd?p5UtC^136>P9 zwzCb~D-alJFP>-C(bqbbR~D_T9; z@o^1iIQP(l8w8y^*v$nCp{0op_0E#EuPrSNAN#yqYW0P4hY6D7dPY~?=ukH5iY=w1 zGq=1WqDkqIvZ=)uTzK-`gasRV7hO*W`H%%_9mihCyr5z$e&7XCtmFCgcI@AmH6 zX(X6tib~znN_bEEOk~$`Q2-6>^xnN>S$CsZL+^6czN?)zHSyd%9;roz|bfv0+p&U@VzLuOw5t(rbD-uev@x9Ni-;3PZQ)m-U zpvg=K*Q}z;8VsFhB${crmp-YVv)RpT=H}teAahp_4h6G`Wq?b-Hyr_YE%OQfN>yKN zb2~AE+-f(L6bGAcA55yo-L_NML&M~D^7*pV?w}3{+;1;xfa`+;fXYPe7Y{4mFt^ar zTfhrJpQlEx#;x3P8TP0{ZOZ3F9?k&^GK+fvu>UmhjVma8eAii55jTb!Am}qe+T9Mk z7^&NdyD-6=M5Rnr(+f`$yBcd`U`$XKKet5)?I@(>4d-zX_qm&H{Bpdo1A+H&an++1{m)FO!TCC4AhTAnQz+p z5&WCyEWiuT(7)AJ;`X4za7=Q7Q7=KkMNGAZ3S}BT^0-zsv}L&%(7A$lntk}L=#%vi zvAhXv>8R(%X3%UsUVjZ4=pEmJAA5{D2u*5TlBuqBvMwCL8+u3 zW$kfW93yFpSQLV4ungzWq=KX_;`ee@qj98(q-&^Al=Kr*wq3;hjpoGNQyp|cyUbvm zf~oz2g#ybx0ms{b!={7SPy5}gpglWkCE$BKBJVie&5r{=qKXSat2(0@IvIX-cT>pP zWY39=TRn+U{Mv1Cy!L3sAANNKQcqrasDGIMTr`~V`W?Ovb zXPgXN(-wVF+}qO|%hER_QC1YA)lEw-3(JCIhs~!|VQS6Xj74#V#wMFC9doplxXjmb z!8cA8?pCN;e^k(VVSntm{Dz$Q} z_2+toAWIlAA@Hf8+-KU)>(zr-qaJKme4wTi#)ltq@8`^_ae*Sr7!2=@68Q!qexQ07 zrmn7Tt+zCT)qbV3W)m^&yo6m^zNe@|;^F*fufRKORLcMKu!k#yYwB~?iVR-Jv4M5yUBp8lDp=ah^2fBIsfLn)r7+w);92 z`qfgi*9-R2=fgvD*>j!8E*qhaV9gEL8LMUd9$g*#r$KxJ*3XCyO@wi5R(x@jYro#w zMj^~xHx4I5vFSlh$-&vM;b%=Vt;^{_T%g%mZv=qm-ja>yUuIwG`VRIEFEeDQBt?ZS zpDG|fM;}j!Hc>=EunkdKS1K`Hl4+yVuZ*GZ-vj{8IKnIpx9RM$N~Z0TjYvU1lCexH z)AVK97Fr$h*wM~Wwb_O$=H4hTT-mXzX{SQXszb^Rs^;(VqGD3npwdAAgfroL3NDN8 qfBO1Q!WMn0_@Asx{tu+@v#?6*EEdsJA9C=g0idd=sZb+l8S!6Umjes{ literal 0 HcmV?d00001 diff --git a/test/worlds/include.sdf b/test/worlds/include.sdf index ed6f427d9a..1d00bc2dc0 100644 --- a/test/worlds/include.sdf +++ b/test/worlds/include.sdf @@ -6,7 +6,7 @@ - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/ground plane/1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/ground plane/1 diff --git a/test/worlds/log_record_resources.sdf b/test/worlds/log_record_resources.sdf index c0e2761c55..2c596b9d9d 100644 --- a/test/worlds/log_record_resources.sdf +++ b/test/worlds/log_record_resources.sdf @@ -56,7 +56,7 @@ false staging_area 0 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/X2 Config 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/X2 Config 1 diff --git a/test/worlds/save_world.sdf b/test/worlds/save_world.sdf index 055dd32d4e..7919821f10 100644 --- a/test/worlds/save_world.sdf +++ b/test/worlds/save_world.sdf @@ -39,17 +39,17 @@ - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack backpack1 1 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack backpack2 1 2 3 0.1 0.2 0.3 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/2 backpack3 2 0 0 0.1 0.2 0.3 diff --git a/tutorials/battery.md b/tutorials/battery.md index 4b235125c3..aacfaff581 100644 --- a/tutorials/battery.md +++ b/tutorials/battery.md @@ -53,7 +53,7 @@ Next, you can find a description of the SDF parameters used: * ``: Power load on battery (W). -* ``: As reported [here](https://github.com/ignitionrobotics/ign-gazebo/issues/225), +* ``: As reported [here](https://github.com/gazebosim/gz-sim/issues/225), there are some issues affecting batteries in Ignition Blueprint and Citadel. This parameter fixes the issues. Feel free to omit the parameter if you have legacy code and want to preserve the old behavior. diff --git a/tutorials/detachable_joints.md b/tutorials/detachable_joints.md index 70a2456b8d..38f2d0d5a3 100644 --- a/tutorials/detachable_joints.md +++ b/tutorials/detachable_joints.md @@ -8,7 +8,7 @@ kinematic topology has to be a tree, i.e., kinematic loops are not currently supported. This affects the choice of the parent link, and therefore, the parent model, which is the model that contains the `DetachableJoint` system. -For example, [detachable_joint.sdf](https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo2/examples/worlds/detachable_joint.sdf) +For example, [detachable_joint.sdf](https://github.com/gazebosim/gz-sim/blob/ign-gazebo2/examples/worlds/detachable_joint.sdf) demonstrates a four wheel vehicle that holds three objects that are later detached from the vehicle. As seen in this example, the parent model is the vehicle. The kinematic topology is the following. diff --git a/tutorials/distributed_simulation.md b/tutorials/distributed_simulation.md index 5395d72fd1..26918a3671 100644 --- a/tutorials/distributed_simulation.md +++ b/tutorials/distributed_simulation.md @@ -106,7 +106,7 @@ keeps all performers loaded, but performs no physics simulation. Stepping happens in 2 stages: the primary update and the secondaries update, according to the diagram below: - + 1. The primary publishes a `SimulationStep` message on the `/step` topic, containing: diff --git a/tutorials/erb_template.md b/tutorials/erb_template.md index 1814d024dc..b289d5a9d5 100644 --- a/tutorials/erb_template.md +++ b/tutorials/erb_template.md @@ -17,7 +17,7 @@ Some of them are listed below and demonstrated in this [example ERB file](https: ## Set up Ruby Firstly, Ruby needs to be installed. -If you have gone through [Ignition's installation guide](https://ignitionrobotics.org/docs/latest/install), it's most likely you already have Ruby installed. +If you have gone through [Ignition's installation guide](https://gazebosim.org/docs/latest/install), it's most likely you already have Ruby installed. To check if Ruby is installed, use ```{.sh} ruby --version @@ -102,7 +102,7 @@ Each box model also has a different name and pose to ensure they show up as indi %> ``` -[Here](https://github.com/ignitionrobotics/ign-gazebo/blob/main/examples/worlds/shapes_population.sdf.erb) is a complete shapes simulation world example. +[Here](https://github.com/gazebosim/gz-sim/blob/main/examples/worlds/shapes_population.sdf.erb) is a complete shapes simulation world example. Instead of simple shapes, you can also use a nested loop to generate 100 actors spaced out evenly in a simulation world. @@ -116,11 +116,11 @@ Instead of simple shapes, you can also use a nested loop to generate 100 actors - 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 diff --git a/tutorials/gui_config.md b/tutorials/gui_config.md index d7cecc59f4..faf7e8ae9c 100644 --- a/tutorials/gui_config.md +++ b/tutorials/gui_config.md @@ -1,9 +1,9 @@ \page gui_config GUI Configuration Ignition Gazebo's graphical user interface is powered by -[Ignition GUI](https://ignitionrobotics.org/libs/gui). Therefore, Gazebo's +[Ignition GUI](https://gazebosim.org/libs/gui). Therefore, Gazebo's GUI layout can be defined in -[Ignition GUI configuration files](https://ignitionrobotics.org/api/gui/2.1/config.html). +[Ignition GUI configuration files](https://gazebosim.org/api/gui/2.1/config.html). These are XML files that describe what plugins to be loaded and with what settings. @@ -104,11 +104,11 @@ favorite editor and save this file as `fuel_preview.sdf`: - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Sun + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Sun - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Gazebo + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Gazebo diff --git a/tutorials/levels.md b/tutorials/levels.md index c2f62b8667..f8f1f98df5 100644 --- a/tutorials/levels.md +++ b/tutorials/levels.md @@ -77,7 +77,7 @@ being added and removed. Take a look at the 2D example below. This example focuses on a single performer, but the same logic can be extended to multiple performers. - + * The **green area** represents the area of the world which this simulation is expected to take place in. @@ -115,23 +115,23 @@ Let's take a look at how levels are loaded / unloaded as the performer moves: * `M1` and `M3`, because they belong to the level. * `M6`, because it is global. - + 2. The performer moves south towards `L3` and enters its buffer zone, triggering a load of that level's models, `M4` and `M5`. Note that at this moment, both `L1` and `L3` are loaded. - + 3. The performer moves further south, exiting `L1` and entering `L3`. However, `L1` is still loaded, since `R1` is still within its buffer zone. - + 4. Eventually `R1` moves beyond `L1`'s buffer, triggering an unload of `L1`. The main effect is unloading `M1`. - + ## SDF elements @@ -248,7 +248,7 @@ ign service -s /world/levels/level/set_performer --reqtype ignition.msgs.StringM The following is a world file that could be an instance of the world shown in the figure - + ```xml diff --git a/tutorials/log.md b/tutorials/log.md index 2de76ff76a..fcac96bf70 100644 --- a/tutorials/log.md +++ b/tutorials/log.md @@ -8,7 +8,7 @@ Ignition records two types of information to files: * Always recorded * Simulation state * Entity poses, insertion and deletion - * Logged to an [Ignition Transport `state.tlog` file](https://ignitionrobotics.org/api/transport/7.0/logging.html) + * Logged to an [Ignition Transport `state.tlog` file](https://gazebosim.org/api/transport/7.0/logging.html) * Recording must be enabled from the command line or the C++ API * Can be played back using the command line or the C++ API diff --git a/tutorials/logical_audio_sensor.md b/tutorials/logical_audio_sensor.md index 0a1e776e47..526ece535a 100644 --- a/tutorials/logical_audio_sensor.md +++ b/tutorials/logical_audio_sensor.md @@ -8,7 +8,7 @@ The logical audio plugin does not play actual audio to a device like speakers, b ## Setup -Let's take a look at [logical_audio_sensor_plugin.sdf](https://github.com/ignitionrobotics/ign-gazebo/blob/460d2b1cfbf0addf05a1e61c05e1f7a675a83785/examples/worlds/logical_audio_sensor_plugin.sdf), which defines a simulation world with 4 models (in this case, boxes) that have an audio object attached to them. +Let's take a look at [logical_audio_sensor_plugin.sdf](https://github.com/gazebosim/gz-sim/blob/460d2b1cfbf0addf05a1e61c05e1f7a675a83785/examples/worlds/logical_audio_sensor_plugin.sdf), which defines a simulation world with 4 models (in this case, boxes) that have an audio object attached to them. This world attaches logical audio sources to the `red_box` and `blue_box` models, and attaches logical microphones to the `green_box` and `yellow_box` models. Let's take a look at the SDF relevant to the source for `red_box` to understand how to define a logical audio source in SDF: @@ -30,7 +30,7 @@ Let's take a look at the SDF relevant to the source for `red_box` to understand ``` As we can see, we use a `` tag to define an audio source. -An explanation of all of the tags can be found in the [plugin documentation](https://github.com/ignitionrobotics/ign-gazebo/blob/314477419d2aa946f384204dc99b17d9fcd963b3/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh#L35-L130), but there are a few important things to point out: +An explanation of all of the tags can be found in the [plugin documentation](https://github.com/gazebosim/gz-sim/blob/314477419d2aa946f384204dc99b17d9fcd963b3/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh#L35-L130), but there are a few important things to point out: * `` is used to identify this source when operating on it via services (services will be discussed later). Since a model can have multiple sources and microphones attached to it, each source attached to a particular model must have a unique ID. This means that no other sources attached to `red_box` can have an ID of 1, but sources attached to other models can have an ID of 1 (assuming that other models don't already have a source with an ID of 1 attached to it). @@ -55,7 +55,7 @@ Let's now take a look at the SDF relevant to the microphone for `green_box` to u ``` The same rules regarding `` and `` for a logical audio source also apply to a logical microphone. -You can also take a look at the [microphone documentation](https://github.com/ignitionrobotics/ign-gazebo/blob/314477419d2aa946f384204dc99b17d9fcd963b3/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh#L35-L130) for a detailed explanation of the tags embedded in the `` tag. +You can also take a look at the [microphone documentation](https://github.com/gazebosim/gz-sim/blob/314477419d2aa946f384204dc99b17d9fcd963b3/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh#L35-L130) for a detailed explanation of the tags embedded in the `` tag. ## Testing Source and Microphone Behavior diff --git a/tutorials/mesh_to_fuel.md b/tutorials/mesh_to_fuel.md index b3667a1353..e543a75f60 100644 --- a/tutorials/mesh_to_fuel.md +++ b/tutorials/mesh_to_fuel.md @@ -1,17 +1,17 @@ \page meshtofuel Importing a Mesh to Fuel -This tutorial will explain how to import a mesh to the [Ignition Fuel](https://app.ignitionrobotics.org) web application. +This tutorial will explain how to import a mesh to the [Ignition Fuel](https://app.gazebosim.org) web application. Adding models and/or worlds to Fuel will make your content readily available to the open source robotics simulation community, and easier to use with the Ignition GUI. ## Prerequisites To import meshes to Fuel, you need to have a user account. -Go to [app.ignitionrobotics.org](https://app.ignitionrobotics.org) and click Login in the top right corner of the screen, then click Sign Up. +Go to [app.gazebosim.org](https://app.gazebosim.org) and click Login in the top right corner of the screen, then click Sign Up. Once you verify your email address, your account will be ready. You'll need a mesh ready before trying to import to Fuel. There are several ways to acquire a mesh. -To save time, we'll use this [Electrical Box model](https://app.ignitionrobotics.org/openrobotics/fuel/models/Electrical%20Box) that you can download from Fuel. +To save time, we'll use this [Electrical Box model](https://app.gazebosim.org/openrobotics/fuel/models/Electrical%20Box) that you can download from Fuel. ## Model Directory Structure @@ -126,17 +126,17 @@ Click the `Add folders` button, or drag and drop the `Electrical Box` folder you All the files in your model description will be listed there. Press `Upload`, and the "Fuel Model Info" page for your model will open. -![Electrical Box Test](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/mesh_to_fuel/model_info2.png) +![Electrical Box Test](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/mesh_to_fuel/model_info2.png) You can always delete a model by clicking the "Edit model" button and then selecting "Delete model" at the bottom of the page -![Delete model](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/mesh_to_fuel/delete2.png) +![Delete model](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/mesh_to_fuel/delete2.png) ## Include the Model in a World With your mesh successfully uploaded to Fuel, you can now easily include it in a world SDF file. -Copy [this example world code](https://github.com/ignitionrobotics/ign-gazebo/raw/main/examples/worlds/import_mesh.sdf) into a text editor and save it as `import_mesh.sdf`. +Copy [this example world code](https://github.com/gazebosim/gz-sim/raw/main/examples/worlds/import_mesh.sdf) into a text editor and save it as `import_mesh.sdf`. This is a simple world SDF file, which you can learn more about on the [SDF website](http://sdformat.org/). Scroll all the way to the bottom of the file until you see the `include` tag section following the `` comment line. @@ -156,7 +156,7 @@ Scroll all the way to the bottom of the file until you see the `include` tag sec true Electrical Box 0 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Electrical Box + https://fuel.gazebosim.org/1.0/openrobotics/models/Electrical Box @@ -171,7 +171,7 @@ Change `Electrical Box` to `Electrical Box Test`. The syntax for including any model from Fuel is: ```xml -https://fuel.ignitionrobotics.org/1.0//models/ +https://fuel.gazebosim.org/1.0//models/ ``` ### Launch World @@ -182,4 +182,4 @@ To launch the world and see your mesh, run Ignition from inside the directory wh ign gazebo import_mesh.sdf ``` -![Launch sample world with mesh](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/mesh_to_fuel/launch_world2.png) +![Launch sample world with mesh](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/mesh_to_fuel/launch_world2.png) diff --git a/tutorials/migrating_ardupilot_plugin.md b/tutorials/migrating_ardupilot_plugin.md index 021ee9adc4..c92a196615 100644 --- a/tutorials/migrating_ardupilot_plugin.md +++ b/tutorials/migrating_ardupilot_plugin.md @@ -22,7 +22,7 @@ documentation](https://ardupilot.org/dev/docs/using-gazebo-simulator-with-sitl.h As context to understand what we're migrating, here's a system diagram for how the ArduPilot Gazebo plugin works is used: - + *UAV icon credit: By Julian Herzog, CC BY 4.0, https://commons.wikimedia.org/w/index.php?curid=60965475* @@ -224,8 +224,8 @@ To better understand the ECS pattern as it is used in Ignition, it's helpful to learn about the EntityComponentManager (ECM), which is responsible for managing the ECS graph. A great resource to understand the logic under the hood of the ECM is the `SdfEntityCreator` class -([header](https://github.com/ignitionrobotics/ign-gazebo/blob/main/include/ignition/gazebo/SdfEntityCreator.hh), -[source](https://github.com/ignitionrobotics/ign-gazebo/blob/main/src/SdfEntityCreator.cc)). +([header](https://github.com/gazebosim/gz-sim/blob/main/include/ignition/gazebo/SdfEntityCreator.hh), +[source](https://github.com/gazebosim/gz-sim/blob/main/src/SdfEntityCreator.cc)). This class is responsible for mapping the content of an SDF file to the entities and components that form the graph handled by the ECM. For example, if you wonder which components can be accessed by default from the plugin, this diff --git a/tutorials/migration_link_api.md b/tutorials/migration_link_api.md index 8a610a9c87..6d6c2d020c 100644 --- a/tutorials/migration_link_api.md +++ b/tutorials/migration_link_api.md @@ -14,7 +14,7 @@ class. If you're trying to use some API which doesn't have an equivalent on Ignition yet, feel free to -[ticket an issue](https://github.com/ignitionrobotics/ign-gazebo/issues/). +[ticket an issue](https://github.com/gazebosim/gz-sim/issues/). ## Link API diff --git a/tutorials/migration_model_api.md b/tutorials/migration_model_api.md index de79a30bc0..a4f6b05cb7 100644 --- a/tutorials/migration_model_api.md +++ b/tutorials/migration_model_api.md @@ -14,7 +14,7 @@ class. If you're trying to use some API which doesn't have an equivalent on Ignition yet, feel free to -[ticket an issue](https://github.com/ignitionrobotics/ign-gazebo/issues/). +[ticket an issue](https://github.com/gazebosim/gz-sim/issues/). ## Model API diff --git a/tutorials/migration_sdf.md b/tutorials/migration_sdf.md index 30d3978bff..d49e0c326e 100644 --- a/tutorials/migration_sdf.md +++ b/tutorials/migration_sdf.md @@ -198,7 +198,7 @@ sure you're loading the correct plugins. Both simulators are installed with several built-in plugins. [Gazebo classic's plugins](https://github.com/osrf/gazebo/tree/gazebo11/plugins) and -[Ignition Gazebo's plugins](https://github.com/ignitionrobotics/ign-gazebo/tree/main/src/systems) +[Ignition Gazebo's plugins](https://github.com/gazebosim/gz-sim/tree/main/src/systems) have different file names. For example, to use Gazebo classic's differential drive plugin, the user can refer to it as follows: diff --git a/tutorials/migration_world_api.md b/tutorials/migration_world_api.md index a377214b35..230bac2dbe 100644 --- a/tutorials/migration_world_api.md +++ b/tutorials/migration_world_api.md @@ -14,7 +14,7 @@ class. If you're trying to use some API which doesn't have an equivalent on Ignition yet, feel free to -[ticket an issue](https://github.com/ignitionrobotics/ign-gazebo/issues/). +[ticket an issue](https://github.com/gazebosim/gz-sim/issues/). ## World API diff --git a/tutorials/physics.md b/tutorials/physics.md index e1cac1a129..42d374e1ac 100644 --- a/tutorials/physics.md +++ b/tutorials/physics.md @@ -2,7 +2,7 @@ Ignition Gazebo supports choosing what physics engine to use at runtime. This is made possible by -[Ignition Physics](https://ignitionrobotics.org/libs/physics)' abstraction +[Ignition Physics](https://gazebosim.org/libs/physics)' abstraction layer. Ignition Gazebo uses the [DART](https://dartsim.github.io/) physics engine @@ -10,7 +10,7 @@ by default. Downstream developers may also integrate other physics engines by creating new Ignition Physics engine plugins. See -[Ignition Physics](https://ignitionrobotics.org/api/physics/2.0/tutorials.html)'s +[Ignition Physics](https://gazebosim.org/api/physics/2.0/tutorials.html)'s tutorials to learn how to integrate a new engine. ## How Gazebo finds engines diff --git a/tutorials/point_cloud_to_mesh.md b/tutorials/point_cloud_to_mesh.md index cd7fff694b..91af03aec4 100644 --- a/tutorials/point_cloud_to_mesh.md +++ b/tutorials/point_cloud_to_mesh.md @@ -20,7 +20,7 @@ After installing, open CloudCompare and import your point cloud file by going to Depending on the number of points in your point cloud, this could take several minutes. Once loaded, you should see the following tunnel section: -![Opening the point cloud](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/cloudcompare2.png) +![Opening the point cloud](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/cloudcompare2.png) Many 3D scans will be composed of millions, sometimes hundreds of millions of points. Converting a scan to a 3D model with that many points would be very difficult due to the number of polygons that would be created and the long processing time necessary to compute the normals. @@ -34,13 +34,13 @@ We'll still walk through reducing points, however, to make the process quicker. To reduce the number of points in your cloud, click on the tunnel so a yellow cube outline appears around it, then go to `Edit` > `Subsample`. -![Min. space between points](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/min_space.png) +![Min. space between points](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/min_space.png) The number you will need to enter in the `min. space between points` field will vary depending on your point cloud. A value of .01 was sufficient to bring our point cloud to an easy-to-manage 1 million points. Point count is visible in the `Properties` window on the lower left side of the screen. -![Point count of subsample](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/properties.png) +![Point count of subsample](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/properties.png) How many points you reduce down to will largely depend on how long you are willing to wait for the point cloud to be converted into a mesh. The more points you start with, the longer it will take to compute the normals and create the mesh. @@ -48,7 +48,7 @@ The more points you start with, the longer it will take to compute the normals a After the operation is complete you’ll have two clouds in your scene: the original point cloud and your subsampled point cloud. Most operations in CloudCompare will create new point clouds and keep the original, so make sure that you have the new point cloud selected before running an operation. -![Selecting the new point cloud](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/secondcloud.png) +![Selecting the new point cloud](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/secondcloud.png) ### Create a Polygonal Mesh @@ -59,7 +59,7 @@ A normal is essentially the direction a polygon is facing. To do this, go to `Edit` > `Normals` > `Compute`. You'll see this dialog box: -![Choose Triangulation surface model](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/compute_normals.png) +![Choose Triangulation surface model](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/compute_normals.png) You’ll see various options in the dialog box that appears. The main thing you’ll want to consider is what `Local surface model` to use. @@ -72,7 +72,7 @@ Now we get to actually convert our point cloud to a mesh. To do this go to `Plugins` > `PoissonRecon`. You'll see this dialog box: -![Octree depth and output density selection](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/outputdensity.png) +![Octree depth and output density selection](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/outputdensity.png) The value you enter in the `Octree depth` field will determine the polygon count of the created model. You may have to run the surface reconstruction a couple times with varying values before you land on a polygon count that is suitable for your needs. @@ -93,18 +93,18 @@ Our tunnel has turned into a blob shape. This is because the mesh that CloudCompare creates will always be water tight even if it has to add polygons where there are no points. We just want our tunnels, though, so we need to remove those unnecessary polygons. -![The blob shape](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/blob2.png) +![The blob shape](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/blob2.png) This is where our scalar field comes in. In the mesh's `Properties` window go to `SF display params` and take the left handle in the graph and drag it to the right until it hits the area where the bulk of the scalar field starts. -![Adjusting scalar filed params](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/sf_display.png) +![Adjusting scalar filed params](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/sf_display.png) This will display only the polygons that were created from the point cloud and hide the polygons used to make the model watertight. The polygons are only hidden however. We still need to actually remove them. -![Display original polygons](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/hidden_polygons2.png) +![Display original polygons](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/hidden_polygons2.png) To remove the hidden polygons go to `Edit` > `Scalar fields` > `Filter By Value`. @@ -113,7 +113,7 @@ Hitting export will simply export the mesh within that range. Instead, we'll hit `Split` to create two meshes. One with the polygons inside our specified range and one containing polygons outside that range. -![Splitting the mesh](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/split.png) +![Splitting the mesh](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/split.png) ### The Completed Model @@ -121,6 +121,6 @@ By hitting `Split` we can view the model before exporting by simply going to `Fi Remember to have the correct mesh selected (`.part`) since choosing `Split` will give you two new meshes, plus you will still have your original, complete mesh. Your file format will depend on the software you want to use but `.obj` is a widely supported format that should work in most 3D applications. -![The completed mesh](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/complete2.png) +![The completed mesh](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/complete2.png) You can find more information on CloudCompare and a more in depth look at the tools we used in this tutorial on [the CloudCompare website](https://www.cloudcompare.org/) and the [CloudCompare wiki](https://www.cloudcompare.org/doc/wiki/index.php?title=Main_Page). diff --git a/tutorials/rendering_plugins.md b/tutorials/rendering_plugins.md index ead63d9e38..0acc5bd7f5 100644 --- a/tutorials/rendering_plugins.md +++ b/tutorials/rendering_plugins.md @@ -4,11 +4,11 @@ This tutorial will go over how to write Ignition Gazebo plugins that alter the 3D scene's visual appearance using Ignition Rendering APIs. This is not to be confused with integrating a new rendering engine. See -[How to write your own rendering engine plugin](https://ignitionrobotics.org/api/rendering/4.2/renderingplugin.html) +[How to write your own rendering engine plugin](https://gazebosim.org/api/rendering/4.2/renderingplugin.html) for that. This tutorial will go over a couple of example plugins that are located at -https://github.com/ignitionrobotics/ign-gazebo/tree/ign-gazebo6/examples/plugin/rendering_plugins. +https://github.com/gazebosim/gz-sim/tree/ign-gazebo6/examples/plugin/rendering_plugins. ## Scenes @@ -45,10 +45,10 @@ To interact with the server-side scene, you'll need to write an See [Create System Plugins](createsystemplugins.html). To interact with the client-side scene, you'll need to write an -[ignition::gui::Plugin](https://ignitionrobotics.org/api/gui/4.1/classignition_1_1gui_1_1Plugin.html), +[ignition::gui::Plugin](https://gazebosim.org/api/gui/4.1/classignition_1_1gui_1_1Plugin.html), or a more specialized `ignition::gazebo::GuiSystem` if you need to access entities and components. -See the [GUI system plugin example](https://github.com/ignitionrobotics/ign-gazebo/tree/ign-gazebo6/examples/plugin/gui_system_plugin). +See the [GUI system plugin example](https://github.com/gazebosim/gz-sim/tree/main/examples/plugin/gui_system_plugin). ## Getting the scene @@ -72,7 +72,7 @@ different for each plugin type. ### Render events on the GUI The GUI plugin will need to listen to -[ignition::gui::events::Render](https://ignitionrobotics.org/api/gui/4.1/classignition_1_1gui_1_1events_1_1Render.html) +[ignition::gui::events::Render](https://gazebosim.org/api/gui/4.1/classignition_1_1gui_1_1events_1_1Render.html) events. Here's how to do it: 1. Include the GUI events header: @@ -123,7 +123,7 @@ Here's how to do it: ## Running examples Follow the build instructions on the rendering plugins -[README](https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo6/examples/plugin/rendering_plugins) +[README](https://github.com/gazebosim/gz-sim/blob/main/examples/plugin/rendering_plugins) and you'll generate both plugins: * `RenderingGuiPlugin`: GUI plugin that updates the GUI scene's ambient light with a random color at each click. diff --git a/tutorials/resources.md b/tutorials/resources.md index a086a4fba4..9e735f345b 100644 --- a/tutorials/resources.md +++ b/tutorials/resources.md @@ -44,14 +44,14 @@ Ignition will look for system plugins on the following paths, in order: ### Ignition GUI plugins -Each [Ignition GUI](https://ignitionrobotics.org/libs/rendering) plugin +Each [Ignition GUI](https://gazebosim.org/libs/rendering) plugin defines a widget. GUI plugins may be loaded through: * Tags in SDF world files, where `filename` is the shared library: * `` -* Tags in [GUI config files](https://ignitionrobotics.org/api/gui/4.2/config.html), +* Tags in [GUI config files](https://gazebosim.org/api/gui/3.0/config.html), where `filename` is the shared library: * `` * The plugin menu on the top-right of the screen. @@ -59,27 +59,27 @@ GUI plugins may be loaded through: Ignition will look for GUI plugins on the following paths, in order: 1. All paths set on the `IGN_GUI_PLUGIN_PATH` environment variable -2. [GUI plugins that are installed with Ignition Gazebo](https://github.com/ignitionrobotics/ign-gazebo/tree/main/src/gui/plugins) +2. [GUI plugins that are installed with Ignition Gazebo](https://github.com/gazebosim/gz-sim/tree/main/src/gui/plugins) 3. Other paths added by calling `ignition::gui::App()->AddPluginPath` 4. `~/.ignition/gui/plugins` -5. [Plugins which are installed with Ignition GUI](https://ignitionrobotics.org/api/gui/4.2/namespaceignition_1_1gui_1_1plugins.html) +5. [Plugins which are installed with Ignition GUI](https://gazebosim.org/api/gui/4.2/namespaceignition_1_1gui_1_1plugins.html) ### Physics engines -[Ignition Physics](https://ignitionrobotics.org/libs/physics) +[Ignition Physics](https://gazebosim.org/libs/physics) uses a plugin architecture and its physics engines are built as plugins that are loaded at run time using -[Ignition Plugin](https://ignitionrobotics.org/libs/plugin). +[Ignition Plugin](https://gazebosim.org/libs/plugin). See the [Physics engines](physics.html) tutorial for more details. ### Rendering engines -[Ignition Rendering](https://ignitionrobotics.org/libs/rendering) +[Ignition Rendering](https://gazebosim.org/libs/rendering) uses a plugin architecture and its render engines are built as plugins that are loaded at run time using -[Ignition Plugin](https://ignitionrobotics.org/libs/plugin). +[Ignition Plugin](https://gazebosim.org/libs/plugin). At the moment, Ignition Rendering will only look for render engine plugin shared libraries installed within its `/lib` directory. @@ -89,9 +89,9 @@ Rendering's `/share` directory. ### Sensors Each unique type of sensor in -[Ignition Sensors](https://ignitionrobotics.org/libs/sensors) is a plugin. When +[Ignition Sensors](https://gazebosim.org/libs/sensors) is a plugin. When a particular sensor type is requested, the relevant plugin is loaded by -[Ignition Plugin](https://ignitionrobotics.org/libs/plugin) and a +[Ignition Plugin](https://gazebosim.org/libs/plugin) and a sensor object is instantiated from it. At the moment, Ignition Sensors will only look for sensor plugin @@ -119,7 +119,7 @@ Ignition will look for URIs (path / URL) in the following, in order: 1. All paths on the `IGN_GAZEBO_RESOURCE_PATH`\* environment variable (if path is URI, scheme is stripped) 2. Current running path / absolute path -3. [Ignition Fuel](https://app.ignitionrobotics.org/fuel/models) +3. [Ignition Fuel](https://app.gazebosim.org/fuel/models) 1. Cache (i.e. `$HOME/.ignition/fuel`) 2. Web server @@ -147,7 +147,7 @@ Ignition will look for URIs (path / URL) in the following, in order: ### GUI configuration Ignition Gazebo's -[GUI configuration](https://ignitionrobotics.org/api/gui/4.2/config.html) +[GUI configuration](https://gazebosim.org/api/gui/4.2/config.html) can come from the following, in order: 1. The command line option `--gui-config ` diff --git a/tutorials/server_config.md b/tutorials/server_config.md index a9a27830f1..9faab891f6 100644 --- a/tutorials/server_config.md +++ b/tutorials/server_config.md @@ -114,11 +114,11 @@ favorite editor and save this file as `fuel_preview.sdf`: - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Sun + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Sun - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Cone + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Construction Cone @@ -182,12 +182,12 @@ Let's start by saving this simple world with a camera sensor as - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Sun + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Sun 0 0 1 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Gazebo + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Gazebo diff --git a/tutorials/terminology.md b/tutorials/terminology.md index 3742a569fe..806ad26f8a 100644 --- a/tutorials/terminology.md +++ b/tutorials/terminology.md @@ -66,7 +66,7 @@ to developers touching the source code. * **[Event manager](classignition_1_1gazebo_1_1EventManager.html)**: Manages events that can be sent across systems and the server. Plugins can create and emit custom - [Event](https://ignitionrobotics.org/api/common/3.0/classignition_1_1common_1_1Event.html)s + [Event](https://gazebosim.org/api/common/3.0/classignition_1_1common_1_1Event.html)s and / or emit / listen to events from Ignition Gazebo. * **Simulation runner**: Runs a whole world or some levels of a world, but no diff --git a/tutorials/test_fixture.md b/tutorials/test_fixture.md index 4b9b5611a4..3ba5b40178 100644 --- a/tutorials/test_fixture.md +++ b/tutorials/test_fixture.md @@ -10,7 +10,7 @@ using Continuous Integration (CI). Gazebo can be used for testing using any testing library. We provide an example of how to setup some test cases using [Google Test](https://github.com/google/googletest) in -[ign-gazebo/examples/standalone/gtest_setup](https://github.com/ignitionrobotics/ign-gazebo/tree/ign-gazebo6/examples/standalone/gtest_setup). +[ign-gazebo/examples/standalone/gtest_setup](https://github.com/gazebosim/gz-sim/tree/ign-gazebo6/examples/standalone/gtest_setup). The instructions on that example's `README` can be followed to compile and run those tests. Also be sure to go through the source code for comments with diff --git a/tutorials/triggered_publisher.md b/tutorials/triggered_publisher.md index ff4759c3ef..c783d428cc 100644 --- a/tutorials/triggered_publisher.md +++ b/tutorials/triggered_publisher.md @@ -16,10 +16,10 @@ Publisher systems can be chained together by showing how the falling of the box can trigger another box to fall. Last, it covers how a service call can be triggered to reset the robot pose. The finished world SDFormat file for this tutorial can be found in -[examples/worlds/triggered_publisher.sdf](https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo2/examples/worlds/triggered_publisher.sdf) +[examples/worlds/triggered_publisher.sdf](https://github.com/gazebosim/gz-sim/blob/ign-gazebo2/examples/worlds/triggered_publisher.sdf) We will use the differential drive vehicle from -[examples/worlds/diff_drive.sdf](https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo2/examples/worlds/diff_drive.sdf), +[examples/worlds/diff_drive.sdf](https://github.com/gazebosim/gz-sim/blob/ign-gazebo2/examples/worlds/diff_drive.sdf), but modify the input topic of the `DiffDrive` system to `cmd_vel`. A snippet of the change to the `DiffDrive` system is shown below: diff --git a/tutorials/video_recorder.md b/tutorials/video_recorder.md index c786dba6d0..dd6f899f9b 100644 --- a/tutorials/video_recorder.md +++ b/tutorials/video_recorder.md @@ -38,7 +38,7 @@ the [GUI Configuration](gui_config.html) tutorial for more information. If you launched Ignition Gazebo with the `video_record_dbl_pendulum.sdf` demo world, the GUI configurations are embedded in the world SDF file so you will need to download a copy of the -[sdf file](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/examples/worlds/video_record_dbl_pendulum.sdf). +[sdf file](https://raw.githubusercontent.com/gazebosim/gz-sim/main/examples/worlds/video_record_dbl_pendulum.sdf). and modify the GUI configuration in that file. On the other hand, if you launched Ignition Gazebo with a world file that does not have GUI configurations, you will need to specify the settings in
Documentation:" "" - "" - "https://ignitionrobotics.org/libs/gazebo" + "https://gazebosim.org/libs/sim" "" "
" - "" - "https://ignitionrobotics.org/docs/" + "https://gazebosim.org/docs/" "" "