From 1b1ac04c62ce10c3d865a5b590b6b84470a4146c Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Fri, 12 May 2023 13:46:39 -0700 Subject: [PATCH 1/5] Use gui 6.8 Signed-off-by: Nate Koenig --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 93a00ee84d..8d04ff2326 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -100,7 +100,7 @@ set(IGN_FUEL_TOOLS_VER ${ignition-fuel_tools7_VERSION_MAJOR}) #-------------------------------------- # Find ignition-gui -ign_find_package(ignition-gui6 REQUIRED VERSION 6.5) +ign_find_package(ignition-gui6 REQUIRED VERSION 6.8) set(IGN_GUI_VER ${ignition-gui6_VERSION_MAJOR}) ign_find_package (Qt5 COMPONENTS From bd5353f622d91bb784a6703ecbf9c3395abf2ea4 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 17 May 2023 20:45:18 -0700 Subject: [PATCH 2/5] Fix visibility Signed-off-by: Nate Koenig --- include/gz/sim/gui/GuiSystem.hh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/gz/sim/gui/GuiSystem.hh b/include/gz/sim/gui/GuiSystem.hh index c519a9835a..2940d107fb 100644 --- a/include/gz/sim/gui/GuiSystem.hh +++ b/include/gz/sim/gui/GuiSystem.hh @@ -41,7 +41,7 @@ namespace gazebo /// GUI systems are different from `gz::sim::System`s because they /// don't run in the same process as the physics. Instead, they run in a /// separate process that is stepped by updates coming through the network - class IGNITION_GAZEBO_VISIBLE GuiSystem : public gz::gui::Plugin + class IGNITION_GAZEBO_GUI_VISIBLE GuiSystem : public gz::gui::Plugin { Q_OBJECT From a0234e946dbde868eab735868ae2aea189de8193 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 24 May 2023 05:57:47 -0700 Subject: [PATCH 3/5] Fixed headers and most comments Signed-off-by: Nate Koenig --- include/gz/sim/Actor.hh | 10 +- include/gz/sim/Joint.hh | 16 +-- include/gz/sim/Light.hh | 18 +-- include/gz/sim/Primitives.hh | 4 +- include/gz/sim/Sensor.hh | 10 +- include/gz/sim/comms/Broker.hh | 6 +- include/gz/sim/comms/ICommsModel.hh | 8 +- include/gz/sim/comms/MsgManager.hh | 10 +- include/gz/sim/components/BatteryPowerLoad.hh | 6 +- .../gz/sim/components/BoundingBoxCamera.hh | 8 +- include/gz/sim/components/CMakeLists.txt | 2 +- include/gz/sim/components/CanonicalLink.hh | 1 + include/gz/sim/components/CustomSensor.hh | 8 +- include/gz/sim/components/Factory.hh | 2 +- include/gz/sim/components/ForceTorque.hh | 10 +- include/gz/sim/components/HaltMotion.hh | 6 +- .../sim/components/JointTransmittedWrench.hh | 10 +- include/gz/sim/components/LightCmd.hh | 12 +- include/gz/sim/components/LightType.hh | 8 +- include/gz/sim/components/NavSat.hh | 10 +- include/gz/sim/components/ParticleEmitter.hh | 10 +- include/gz/sim/components/Recreate.hh | 6 +- .../components/RenderEngineServerHeadless.hh | 8 +- .../gz/sim/components/SegmentationCamera.hh | 8 +- include/gz/sim/components/SemanticLabel.hh | 8 +- .../gz/sim/components/SphericalCoordinates.hh | 12 +- include/gz/sim/components/SystemPluginInfo.hh | 10 +- include/gz/sim/components/TemperatureRange.hh | 8 +- include/gz/sim/components/Visibility.hh | 6 +- include/gz/sim/components/VisualCmd.hh | 12 +- include/gz/sim/components/WheelSlipCmd.hh | 12 +- include/gz/sim/config.hh.in | 2 +- include/gz/sim/detail/BaseView.hh | 6 +- include/gz/sim/gui/GuiEvents.hh | 4 +- src/Actor.cc | 12 +- src/Actor_TEST.cc | 10 +- src/BaseView.cc | 6 +- src/ComponentFactory.cc | 2 +- src/EntityComponentManager.cc | 2 +- src/Joint.cc | 46 +++---- src/Joint_TEST.cc | 12 +- src/Light.cc | 18 +-- src/Light_TEST.cc | 12 +- src/ModelCommandAPI_TEST.cc | 2 +- src/Primitives.cc | 6 +- src/Primitives_TEST.cc | 2 +- src/SdfEntityCreator_TEST.cc | 2 +- src/SdfGenerator_TEST.cc | 2 +- src/Sensor.cc | 12 +- src/Sensor_TEST.cc | 10 +- src/SimulationRunner.cc | 2 +- src/SystemInternal.hh | 6 +- src/SystemManager.cc | 6 +- src/SystemManager.hh | 14 +-- src/SystemManager_TEST.cc | 12 +- src/World.cc | 18 +-- src/WorldControl.hh | 2 +- src/comms/Broker.cc | 16 +-- src/comms/Broker_TEST.cc | 10 +- src/comms/ICommsModel.cc | 12 +- src/comms/MsgManager.cc | 10 +- src/comms/MsgManager_TEST.cc | 4 +- src/gui/GuiEvents.cc | 2 +- src/gui/GuiEvents_TEST.cc | 4 +- src/gui/Gui_clean_exit_TEST.cc | 10 +- src/gui/plugins/align_tool/AlignTool.cc | 6 +- .../banana_for_scale/BananaForScale.cc | 16 +-- .../banana_for_scale/BananaForScale.hh | 2 +- .../component_inspector/ComponentInspector.cc | 2 +- .../component_inspector/ComponentInspector.hh | 2 +- .../component_inspector/SystemPluginInfo.cc | 6 +- .../component_inspector/SystemPluginInfo.hh | 2 +- .../component_inspector_editor/AirPressure.cc | 6 +- .../component_inspector_editor/Altimeter.cc | 4 +- .../ComponentInspectorEditor.cc | 112 +++++++++--------- .../ComponentInspectorEditor.hh | 10 +- .../plugins/component_inspector_editor/Imu.cc | 6 +- .../component_inspector_editor/JointType.cc | 10 +- .../component_inspector_editor/Lidar.cc | 6 +- .../Magnetometer.cc | 4 +- .../component_inspector_editor/ModelEditor.cc | 26 ++-- .../component_inspector_editor/ModelEditor.hh | 2 +- .../component_inspector_editor/Pose3d.cc | 12 +- .../component_inspector_editor/Pose3d.hh | 2 +- .../component_inspector_editor/Types.hh | 2 +- src/gui/plugins/copy_paste/CopyPaste.cc | 18 +-- src/gui/plugins/copy_paste/CopyPaste.hh | 4 +- .../EntityContextMenuPlugin.cc | 18 +-- .../EntityContextMenuPlugin.hh | 6 +- src/gui/plugins/lights/Lights.cc | 22 ++-- src/gui/plugins/lights/Lights.hh | 2 +- src/gui/plugins/plotting/Plotting.cc | 42 +++---- src/gui/plugins/plotting/Plotting.hh | 16 +-- .../resource_spawner/ResourceSpawner.cc | 2 +- src/gui/plugins/scene3d/Scene3D.cc | 2 +- .../plugins/scene_manager/GzSceneManager.cc | 30 ++--- .../plugins/scene_manager/GzSceneManager.hh | 2 +- .../plugins/select_entities/SelectEntities.cc | 28 ++--- .../plugins/select_entities/SelectEntities.hh | 2 +- src/gui/plugins/spawn/Spawn.cc | 46 +++---- src/gui/plugins/spawn/Spawn.hh | 4 +- .../transform_control/TransformControl.cc | 10 +- .../plugins/video_recorder/VideoRecorder.cc | 14 +-- .../VisualizationCapabilities.cc | 104 ++++++++-------- .../VisualizationCapabilities.hh | 2 +- .../visualize_contacts/VisualizeContacts.cc | 36 +++--- .../visualize_contacts/VisualizeContacts.hh | 4 +- .../plugins/visualize_lidar/VisualizeLidar.cc | 54 ++++----- .../plugins/visualize_lidar/VisualizeLidar.hh | 6 +- src/network/PeerTracker_TEST.cc | 4 +- src/rendering/MarkerManager.cc | 2 +- src/systems/buoyancy/Buoyancy.cc | 2 +- src/systems/buoyancy_engine/BuoyancyEngine.cc | 16 +-- src/systems/buoyancy_engine/BuoyancyEngine.hh | 2 +- src/systems/comms_endpoint/CommsEndpoint.cc | 14 +-- src/systems/comms_endpoint/CommsEndpoint.hh | 4 +- .../detachable_joint/DetachableJoint.cc | 11 +- src/systems/follow_actor/FollowActor.cc | 14 +-- src/systems/follow_actor/FollowActor.hh | 4 +- src/systems/force_torque/ForceTorque.cc | 42 +++---- src/systems/force_torque/ForceTorque.hh | 4 +- src/systems/hydrodynamics/Hydrodynamics.cc | 22 ++-- src/systems/hydrodynamics/Hydrodynamics.hh | 2 +- .../JointTrajectoryController.cc | 38 +++--- .../JointTrajectoryController.hh | 2 +- src/systems/label/Label.cc | 14 +-- src/systems/label/Label.hh | 4 +- src/systems/log/LogPlayback.cc | 1 - .../LogicalAudioSensorPlugin.cc | 2 +- src/systems/mecanum_drive/MecanumDrive.cc | 28 ++--- src/systems/mecanum_drive/MecanumDrive.hh | 2 +- .../model_photo_shoot/ModelPhotoShoot.cc | 34 +++--- .../model_photo_shoot/ModelPhotoShoot.hh | 2 +- .../MulticopterMotorModel.cc | 2 +- src/systems/navsat/NavSat.cc | 28 ++--- src/systems/navsat/NavSat.hh | 6 +- .../odometry_publisher/OdometryPublisher.cc | 28 ++--- .../odometry_publisher/OdometryPublisher.hh | 2 +- .../OpticalTactilePlugin.cc | 30 ++--- .../OpticalTactilePlugin.hh | 2 +- .../optical_tactile_plugin/Visualization.cc | 6 +- .../optical_tactile_plugin/Visualization.hh | 8 +- .../particle_emitter/ParticleEmitter.cc | 32 ++--- .../particle_emitter/ParticleEmitter.hh | 2 +- .../particle_emitter2/ParticleEmitter2.cc | 22 ++-- .../particle_emitter2/ParticleEmitter2.hh | 2 +- src/systems/perfect_comms/PerfectComms.cc | 10 +- src/systems/perfect_comms/PerfectComms.hh | 6 +- .../physics/CanonicalLinkModelTracker.hh | 10 +- src/systems/rf_comms/RFComms.cc | 20 ++-- src/systems/rf_comms/RFComms.hh | 6 +- src/systems/shader_param/ShaderParam.cc | 24 ++-- src/systems/shader_param/ShaderParam.hh | 2 +- src/systems/thermal/ThermalSensor.cc | 14 +-- src/systems/thermal/ThermalSensor.hh | 6 +- src/systems/thruster/Thruster.cc | 42 +++---- src/systems/thruster/Thruster.hh | 2 +- .../trajectory_follower/TrajectoryFollower.cc | 30 ++--- .../trajectory_follower/TrajectoryFollower.hh | 2 +- test/integration/ModelPhotoShootTest.hh | 34 +++--- test/integration/actor.cc | 20 ++-- test/integration/actor_trajectory.cc | 20 ++-- test/integration/buoyancy_engine.cc | 26 ++-- .../camera_sensor_background_from_scene.cc | 12 +- test/integration/deprecated_TEST.cc | 2 +- test/integration/distortion_camera.cc | 16 +-- test/integration/entity_system.cc | 24 ++-- test/integration/follow_actor_system.cc | 22 ++-- test/integration/force_torque_system.cc | 24 ++-- test/integration/fuel_cached_server.cc | 6 +- test/integration/halt_motion.cc | 26 ++-- test/integration/hydrodynamics.cc | 32 ++--- test/integration/hydrodynamics_flags.cc | 32 ++--- test/integration/joint.cc | 54 ++++----- .../joint_trajectory_controller_system.cc | 26 ++-- test/integration/light.cc | 34 +++--- .../logical_audio_sensor_plugin.cc | 2 +- .../model_photo_shoot_default_joints.cc | 2 +- .../model_photo_shoot_random_joints.cc | 2 +- test/integration/multicopter.cc | 2 +- test/integration/multiple_servers.cc | 6 +- test/integration/navsat_system.cc | 32 ++--- test/integration/nested_model_physics.cc | 26 ++-- test/integration/odometry_publisher.cc | 32 ++--- test/integration/optical_tactile_plugin.cc | 18 +-- test/integration/particle_emitter.cc | 26 ++-- test/integration/particle_emitter2.cc | 24 ++-- test/integration/perfect_comms.cc | 10 +- test/integration/play_pause.cc | 2 +- test/integration/recreate_entities.cc | 32 ++--- test/integration/rf_comms.cc | 12 +- test/integration/sensor.cc | 24 ++-- test/integration/sensors_system_battery.cc | 18 +-- test/integration/shader_param_system.cc | 14 +-- test/integration/spherical_coordinates.cc | 30 ++--- test/integration/thermal_sensor_system.cc | 28 ++--- test/integration/thruster.cc | 40 +++---- test/integration/triggered_camera.cc | 20 ++-- test/integration/world_control_state.cc | 14 +-- test/performance/sdf_runner.cc | 2 +- test/plugins/TestVisualSystem.cc | 2 +- test/plugins/TestVisualSystem.hh | 10 +- 202 files changed, 1366 insertions(+), 1361 deletions(-) diff --git a/include/gz/sim/Actor.hh b/include/gz/sim/Actor.hh index 50460891a0..e19f154a0a 100644 --- a/include/gz/sim/Actor.hh +++ b/include/gz/sim/Actor.hh @@ -21,14 +21,14 @@ #include #include -#include +#include #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" +#include "gz/sim/config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Types.hh" namespace ignition { diff --git a/include/gz/sim/Joint.hh b/include/gz/sim/Joint.hh index e8b8ab31f3..e58ed60264 100644 --- a/include/gz/sim/Joint.hh +++ b/include/gz/sim/Joint.hh @@ -25,18 +25,18 @@ #include #include -#include -#include -#include +#include +#include +#include #include #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Types.hh" +#include "gz/sim/config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Types.hh" namespace ignition { diff --git a/include/gz/sim/Light.hh b/include/gz/sim/Light.hh index f3680991dd..130809bac3 100644 --- a/include/gz/sim/Light.hh +++ b/include/gz/sim/Light.hh @@ -24,15 +24,15 @@ #include -#include -#include -#include -#include - -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" +#include +#include +#include +#include + +#include "gz/sim/config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Types.hh" namespace ignition { diff --git a/include/gz/sim/Primitives.hh b/include/gz/sim/Primitives.hh index eff9a97b83..cb68727af3 100644 --- a/include/gz/sim/Primitives.hh +++ b/include/gz/sim/Primitives.hh @@ -18,8 +18,8 @@ #ifndef IGNITION_GAZEBO_PRIMITIVES_HH_ #define IGNITION_GAZEBO_PRIMITIVES_HH_ -#include -#include +#include +#include #include diff --git a/include/gz/sim/Sensor.hh b/include/gz/sim/Sensor.hh index af677f252b..ee08c8a814 100644 --- a/include/gz/sim/Sensor.hh +++ b/include/gz/sim/Sensor.hh @@ -23,14 +23,14 @@ #include -#include +#include #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" +#include "gz/sim/config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Types.hh" namespace ignition { diff --git a/include/gz/sim/comms/Broker.hh b/include/gz/sim/comms/Broker.hh index bf06cdf383..f25646d575 100644 --- a/include/gz/sim/comms/Broker.hh +++ b/include/gz/sim/comms/Broker.hh @@ -20,10 +20,10 @@ #include -#include +#include #include -#include "ignition/gazebo/comms/MsgManager.hh" -#include "ignition/gazebo/config.hh" +#include "gz/sim/comms/MsgManager.hh" +#include "gz/sim/config.hh" namespace ignition { diff --git a/include/gz/sim/comms/ICommsModel.hh b/include/gz/sim/comms/ICommsModel.hh index 367cbe975b..e91ee63335 100644 --- a/include/gz/sim/comms/ICommsModel.hh +++ b/include/gz/sim/comms/ICommsModel.hh @@ -20,11 +20,11 @@ #include -#include +#include #include -#include "ignition/gazebo/comms/MsgManager.hh" -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/System.hh" +#include "gz/sim/comms/MsgManager.hh" +#include "gz/sim/config.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/include/gz/sim/comms/MsgManager.hh b/include/gz/sim/comms/MsgManager.hh index aa5bde7f4d..68ebfbd54b 100644 --- a/include/gz/sim/comms/MsgManager.hh +++ b/include/gz/sim/comms/MsgManager.hh @@ -23,11 +23,11 @@ #include #include -#include -#include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/System.hh" +#include +#include +#include "gz/sim/config.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/include/gz/sim/components/BatteryPowerLoad.hh b/include/gz/sim/components/BatteryPowerLoad.hh index 6cfb191678..47764ca4b2 100644 --- a/include/gz/sim/components/BatteryPowerLoad.hh +++ b/include/gz/sim/components/BatteryPowerLoad.hh @@ -17,9 +17,9 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_BATTERYPOWERLOAD_HH_ #define IGNITION_GAZEBO_COMPONENTS_BATTERYPOWERLOAD_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/BoundingBoxCamera.hh b/include/gz/sim/components/BoundingBoxCamera.hh index 2451fd8f24..39d56f1d84 100644 --- a/include/gz/sim/components/BoundingBoxCamera.hh +++ b/include/gz/sim/components/BoundingBoxCamera.hh @@ -19,10 +19,10 @@ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/CMakeLists.txt b/include/gz/sim/components/CMakeLists.txt index 83f18ce69d..100786be0e 100644 --- a/include/gz/sim/components/CMakeLists.txt +++ b/include/gz/sim/components/CMakeLists.txt @@ -13,5 +13,5 @@ configure_file( install( FILES ${CMAKE_CURRENT_BINARY_DIR}/components.hh - DESTINATION ${IGN_INCLUDE_INSTALL_DIR_FULL}/ignition/${IGN_DESIGNATION} + DESTINATION ${IGN_INCLUDE_INSTALL_DIR_FULL}/gz/sim ) diff --git a/include/gz/sim/components/CanonicalLink.hh b/include/gz/sim/components/CanonicalLink.hh index 8577db427b..f9d43e01ca 100644 --- a/include/gz/sim/components/CanonicalLink.hh +++ b/include/gz/sim/components/CanonicalLink.hh @@ -20,6 +20,7 @@ #include #include #include +#include namespace ignition { diff --git a/include/gz/sim/components/CustomSensor.hh b/include/gz/sim/components/CustomSensor.hh index 9871249241..63b79d63d1 100644 --- a/include/gz/sim/components/CustomSensor.hh +++ b/include/gz/sim/components/CustomSensor.hh @@ -18,10 +18,10 @@ #define IGNITION_GAZEBO_COMPONENTS_CUSTOMSENSOR_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/Factory.hh b/include/gz/sim/components/Factory.hh index 10a2c88909..7883333888 100644 --- a/include/gz/sim/components/Factory.hh +++ b/include/gz/sim/components/Factory.hh @@ -284,7 +284,7 @@ namespace components void Register(const std::string &_type, ComponentDescriptorBase *_compDesc, RegistrationObjectId _regObjId) { - auto typeHash = ignition::common::hash64(_type); + auto typeHash = gz::common::hash64(_type); // Initialize static member variable - we need to set these // static members for every shared lib that uses the component, but we diff --git a/include/gz/sim/components/ForceTorque.hh b/include/gz/sim/components/ForceTorque.hh index 12da278077..98c42c1f67 100644 --- a/include/gz/sim/components/ForceTorque.hh +++ b/include/gz/sim/components/ForceTorque.hh @@ -19,12 +19,12 @@ #include -#include -#include +#include +#include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/HaltMotion.hh b/include/gz/sim/components/HaltMotion.hh index 2b44fa5bb8..ece6c659df 100644 --- a/include/gz/sim/components/HaltMotion.hh +++ b/include/gz/sim/components/HaltMotion.hh @@ -17,9 +17,9 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_HALT_MOTION_HH_ #define IGNITION_GAZEBO_COMPONENTS_HALT_MOTION_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/JointTransmittedWrench.hh b/include/gz/sim/components/JointTransmittedWrench.hh index a723fdc285..e082f1ab1a 100644 --- a/include/gz/sim/components/JointTransmittedWrench.hh +++ b/include/gz/sim/components/JointTransmittedWrench.hh @@ -17,12 +17,12 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ #define IGNITION_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/LightCmd.hh b/include/gz/sim/components/LightCmd.hh index fdba5858fc..b4e36b8ddd 100644 --- a/include/gz/sim/components/LightCmd.hh +++ b/include/gz/sim/components/LightCmd.hh @@ -19,13 +19,13 @@ #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include +#include namespace ignition { diff --git a/include/gz/sim/components/LightType.hh b/include/gz/sim/components/LightType.hh index 249eb8602f..ffc3ed62c7 100644 --- a/include/gz/sim/components/LightType.hh +++ b/include/gz/sim/components/LightType.hh @@ -20,10 +20,10 @@ #include #include #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/NavSat.hh b/include/gz/sim/components/NavSat.hh index ae3358b9b4..35c864563a 100644 --- a/include/gz/sim/components/NavSat.hh +++ b/include/gz/sim/components/NavSat.hh @@ -19,12 +19,12 @@ #include -#include -#include +#include +#include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/ParticleEmitter.hh b/include/gz/sim/components/ParticleEmitter.hh index 86fc36bd88..7d70532c22 100644 --- a/include/gz/sim/components/ParticleEmitter.hh +++ b/include/gz/sim/components/ParticleEmitter.hh @@ -17,11 +17,11 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ #define IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/Recreate.hh b/include/gz/sim/components/Recreate.hh index bb053fe5f9..d15ea5fdf4 100644 --- a/include/gz/sim/components/Recreate.hh +++ b/include/gz/sim/components/Recreate.hh @@ -17,9 +17,9 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_RECREATE_HH_ #define IGNITION_GAZEBO_COMPONENTS_RECREATE_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/RenderEngineServerHeadless.hh b/include/gz/sim/components/RenderEngineServerHeadless.hh index 9746e4b0aa..0f9ea36ebc 100644 --- a/include/gz/sim/components/RenderEngineServerHeadless.hh +++ b/include/gz/sim/components/RenderEngineServerHeadless.hh @@ -18,10 +18,10 @@ #define IGNITION_GAZEBO_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/SegmentationCamera.hh b/include/gz/sim/components/SegmentationCamera.hh index c476fc8ba8..b84658a6ef 100644 --- a/include/gz/sim/components/SegmentationCamera.hh +++ b/include/gz/sim/components/SegmentationCamera.hh @@ -19,10 +19,10 @@ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/SemanticLabel.hh b/include/gz/sim/components/SemanticLabel.hh index 3139b75310..9282751be8 100644 --- a/include/gz/sim/components/SemanticLabel.hh +++ b/include/gz/sim/components/SemanticLabel.hh @@ -17,10 +17,10 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_LABEL_HH_ #define IGNITION_GAZEBO_COMPONENTS_LABEL_HH_ -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/components/Component.hh" -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/config.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/components/Component.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/config.hh" namespace ignition { diff --git a/include/gz/sim/components/SphericalCoordinates.hh b/include/gz/sim/components/SphericalCoordinates.hh index 93ebd43fa8..1f98bf7331 100644 --- a/include/gz/sim/components/SphericalCoordinates.hh +++ b/include/gz/sim/components/SphericalCoordinates.hh @@ -17,12 +17,12 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ #define IGNITION_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/SystemPluginInfo.hh b/include/gz/sim/components/SystemPluginInfo.hh index 365886c1e4..4990b2a2ee 100644 --- a/include/gz/sim/components/SystemPluginInfo.hh +++ b/include/gz/sim/components/SystemPluginInfo.hh @@ -17,11 +17,11 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_SYSTEMINFO_HH_ #define IGNITION_GAZEBO_COMPONENTS_SYSTEMINFO_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/TemperatureRange.hh b/include/gz/sim/components/TemperatureRange.hh index 99e4a26151..668fa2a7ef 100644 --- a/include/gz/sim/components/TemperatureRange.hh +++ b/include/gz/sim/components/TemperatureRange.hh @@ -20,11 +20,11 @@ #include #include -#include +#include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/Visibility.hh b/include/gz/sim/components/Visibility.hh index 7a53ddbb3e..3465db7eaa 100644 --- a/include/gz/sim/components/Visibility.hh +++ b/include/gz/sim/components/Visibility.hh @@ -18,9 +18,9 @@ #define IGNITION_GAZEBO_COMPONENTS_VISIBILITY_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/VisualCmd.hh b/include/gz/sim/components/VisualCmd.hh index 794057aabb..71a424ec9b 100644 --- a/include/gz/sim/components/VisualCmd.hh +++ b/include/gz/sim/components/VisualCmd.hh @@ -17,13 +17,13 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_VISUALCMD_HH_ #define IGNITION_GAZEBO_COMPONENTS_VISUALCMD_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include +#include #include diff --git a/include/gz/sim/components/WheelSlipCmd.hh b/include/gz/sim/components/WheelSlipCmd.hh index 4daf7ee249..ec6ae1b3bb 100644 --- a/include/gz/sim/components/WheelSlipCmd.hh +++ b/include/gz/sim/components/WheelSlipCmd.hh @@ -17,13 +17,13 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ #define IGNITION_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include +#include namespace ignition { diff --git a/include/gz/sim/config.hh.in b/include/gz/sim/config.hh.in index 509d058cb0..72249e5b0c 100644 --- a/include/gz/sim/config.hh.in +++ b/include/gz/sim/config.hh.in @@ -11,7 +11,7 @@ #define IGNITION_GAZEBO_VERSION_NAMESPACE v${PROJECT_VERSION_MAJOR} -#define IGNITION_GAZEBO_VERSION_HEADER "Ignition Gazebo, version ${PROJECT_VERSION_FULL}\nCopyright (C) 2018 Open Source Robotics Foundation.\nReleased under the Apache 2.0 License.\n\n" +#define IGNITION_GAZEBO_VERSION_HEADER "Gazebo Sim, version ${PROJECT_VERSION_FULL}\nCopyright (C) 2018 Open Source Robotics Foundation.\nReleased under the Apache 2.0 License.\n\n" #define IGNITION_GAZEBO_GUI_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${IGN_DATA_INSTALL_DIR}/gui" #define IGNITION_GAZEBO_SYSTEM_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${IGN_DATA_INSTALL_DIR}/systems" diff --git a/include/gz/sim/detail/BaseView.hh b/include/gz/sim/detail/BaseView.hh index 9c1761d604..6452524bd8 100644 --- a/include/gz/sim/detail/BaseView.hh +++ b/include/gz/sim/detail/BaseView.hh @@ -22,9 +22,9 @@ #include #include -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/Types.hh" -#include "ignition/gazebo/config.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/Types.hh" +#include "gz/sim/config.hh" namespace ignition { diff --git a/include/gz/sim/gui/GuiEvents.hh b/include/gz/sim/gui/GuiEvents.hh index ff8a1e4b41..0c9be56991 100644 --- a/include/gz/sim/gui/GuiEvents.hh +++ b/include/gz/sim/gui/GuiEvents.hh @@ -192,7 +192,7 @@ namespace events /// \param[in] _type Entity type /// \param[in] _parent Parent entity. public: explicit ModelEditorAddEntity(QString _entity, QString _type, - ignition::gazebo::Entity _parent); + gz::sim::Entity _parent); /// \brief Get the entity to add public: QString Entity() const; @@ -202,7 +202,7 @@ namespace events /// \brief Get the parent entity to add the entity to - public: ignition::gazebo::Entity ParentEntity() const; + public: gz::sim::Entity ParentEntity() const; /// \brief Get the data map. /// \return the QMap of string, string holding custom data. diff --git a/src/Actor.cc b/src/Actor.cc index c84c1db01e..e76a387212 100644 --- a/src/Actor.cc +++ b/src/Actor.cc @@ -15,13 +15,13 @@ * */ -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Pose.hh" +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Pose.hh" -#include "ignition/gazebo/Actor.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Actor.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/Actor_TEST.cc b/src/Actor_TEST.cc index 94b761e077..0c8103a4f6 100644 --- a/src/Actor_TEST.cc +++ b/src/Actor_TEST.cc @@ -19,11 +19,11 @@ #include -#include "ignition/gazebo/Actor.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" +#include "gz/sim/Actor.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" ///////////////////////////////////////////////// TEST(ActorTest, Constructor) diff --git a/src/BaseView.cc b/src/BaseView.cc index 276b2ac175..d366d946c7 100644 --- a/src/BaseView.cc +++ b/src/BaseView.cc @@ -14,10 +14,10 @@ * limitations under the License. * */ -#include "ignition/gazebo/detail/BaseView.hh" +#include "gz/sim/detail/BaseView.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/Types.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/Types.hh" using namespace ignition; using namespace gazebo; diff --git a/src/ComponentFactory.cc b/src/ComponentFactory.cc index 52f5e55569..607e03dd1d 100644 --- a/src/ComponentFactory.cc +++ b/src/ComponentFactory.cc @@ -15,7 +15,7 @@ * */ -#include "ignition/gazebo/components/Factory.hh" +#include "gz/sim/components/Factory.hh" using Factory = ignition::gazebo::components::Factory; diff --git a/src/EntityComponentManager.cc b/src/EntityComponentManager.cc index 376e7dd6be..d768971aa4 100644 --- a/src/EntityComponentManager.cc +++ b/src/EntityComponentManager.cc @@ -15,7 +15,7 @@ * */ -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/EntityComponentManager.hh" #include #include diff --git a/src/Joint.cc b/src/Joint.cc index 511289ff8a..e579a208ca 100644 --- a/src/Joint.cc +++ b/src/Joint.cc @@ -15,29 +15,29 @@ * */ -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/JointEffortLimitsCmd.hh" -#include "ignition/gazebo/components/JointForceCmd.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/JointPositionLimitsCmd.hh" -#include "ignition/gazebo/components/JointPositionReset.hh" -#include "ignition/gazebo/components/JointTransmittedWrench.hh" -#include "ignition/gazebo/components/JointType.hh" -#include "ignition/gazebo/components/JointVelocity.hh" -#include "ignition/gazebo/components/JointVelocityCmd.hh" -#include "ignition/gazebo/components/JointVelocityLimitsCmd.hh" -#include "ignition/gazebo/components/JointVelocityReset.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/ParentLinkName.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/ThreadPitch.hh" - -#include "ignition/gazebo/Joint.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/JointEffortLimitsCmd.hh" +#include "gz/sim/components/JointForceCmd.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/JointPositionLimitsCmd.hh" +#include "gz/sim/components/JointPositionReset.hh" +#include "gz/sim/components/JointTransmittedWrench.hh" +#include "gz/sim/components/JointType.hh" +#include "gz/sim/components/JointVelocity.hh" +#include "gz/sim/components/JointVelocityCmd.hh" +#include "gz/sim/components/JointVelocityLimitsCmd.hh" +#include "gz/sim/components/JointVelocityReset.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/ParentLinkName.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/ThreadPitch.hh" + +#include "gz/sim/Joint.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/Joint_TEST.cc b/src/Joint_TEST.cc index 1dc8e0e56a..8bdf8fea9f 100644 --- a/src/Joint_TEST.cc +++ b/src/Joint_TEST.cc @@ -19,12 +19,12 @@ #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Joint.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Sensor.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Joint.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Sensor.hh" ///////////////////////////////////////////////// TEST(JointTest, Constructor) diff --git a/src/Light.cc b/src/Light.cc index a3337bf110..fab8a01acb 100644 --- a/src/Light.cc +++ b/src/Light.cc @@ -15,19 +15,19 @@ * */ -#include +#include #include -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/LightType.hh" -#include "ignition/gazebo/components/LightCmd.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Pose.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/LightType.hh" +#include "gz/sim/components/LightCmd.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Pose.hh" -#include "ignition/gazebo/Light.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Light.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/Light_TEST.cc b/src/Light_TEST.cc index c435f3acd8..e4ca49eb70 100644 --- a/src/Light_TEST.cc +++ b/src/Light_TEST.cc @@ -19,12 +19,12 @@ #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Light.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Sensor.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Light.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Sensor.hh" ///////////////////////////////////////////////// TEST(LightTest, Constructor) diff --git a/src/ModelCommandAPI_TEST.cc b/src/ModelCommandAPI_TEST.cc index bfcb8cf333..ade1bf9b5c 100644 --- a/src/ModelCommandAPI_TEST.cc +++ b/src/ModelCommandAPI_TEST.cc @@ -20,7 +20,7 @@ #include #include -#include +#include #include "gz/sim/Server.hh" #include "gz/sim/test_config.hh" // NOLINT(build/include) diff --git a/src/Primitives.cc b/src/Primitives.cc index 9e34eac618..2b9cd89282 100644 --- a/src/Primitives.cc +++ b/src/Primitives.cc @@ -15,9 +15,9 @@ * */ -#include -#include -#include "ignition/gazebo/Primitives.hh" +#include +#include +#include "gz/sim/Primitives.hh" using namespace ignition; using namespace gazebo; diff --git a/src/Primitives_TEST.cc b/src/Primitives_TEST.cc index b6635e6144..112e948097 100644 --- a/src/Primitives_TEST.cc +++ b/src/Primitives_TEST.cc @@ -17,7 +17,7 @@ #include -#include +#include #include using PrimitiveShape = ignition::gazebo::PrimitiveShape; diff --git a/src/SdfEntityCreator_TEST.cc b/src/SdfEntityCreator_TEST.cc index 2fbd0d553e..884330e124 100644 --- a/src/SdfEntityCreator_TEST.cc +++ b/src/SdfEntityCreator_TEST.cc @@ -48,7 +48,7 @@ #include "gz/sim/components/Physics.hh" #include "gz/sim/components/Pose.hh" #include "gz/sim/components/Transparency.hh" -#include "ignition/gazebo/components/Visibility.hh" +#include "gz/sim/components/Visibility.hh" #include "gz/sim/components/Visual.hh" #include "gz/sim/components/World.hh" #include "gz/sim/SdfEntityCreator.hh" diff --git a/src/SdfGenerator_TEST.cc b/src/SdfGenerator_TEST.cc index f41ff646b4..9eda70e7c0 100644 --- a/src/SdfGenerator_TEST.cc +++ b/src/SdfGenerator_TEST.cc @@ -21,7 +21,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/Sensor.cc b/src/Sensor.cc index fbba159b08..8842c463a9 100644 --- a/src/Sensor.cc +++ b/src/Sensor.cc @@ -15,13 +15,13 @@ * */ -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Sensor.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Sensor.hh" -#include "ignition/gazebo/Sensor.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Sensor.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/Sensor_TEST.cc b/src/Sensor_TEST.cc index f518809b23..96234a97d9 100644 --- a/src/Sensor_TEST.cc +++ b/src/Sensor_TEST.cc @@ -19,11 +19,11 @@ #include -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Sensor.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Sensor.hh" ///////////////////////////////////////////////// TEST(SensorTest, Constructor) diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc index c62148dc7d..f2d8dfb4ca 100644 --- a/src/SimulationRunner.cc +++ b/src/SimulationRunner.cc @@ -27,7 +27,7 @@ #include "gz/sim/components/Sensor.hh" #include "gz/sim/components/Visual.hh" #include "gz/sim/components/World.hh" -#include "ignition/gazebo/components/ParentEntity.hh" +#include "gz/sim/components/ParentEntity.hh" #include "gz/sim/components/Physics.hh" #include "gz/sim/components/PhysicsCmd.hh" #include "gz/sim/components/Recreate.hh" diff --git a/src/SystemInternal.hh b/src/SystemInternal.hh index 0f0e6ff4d7..8eb1dae337 100644 --- a/src/SystemInternal.hh +++ b/src/SystemInternal.hh @@ -22,9 +22,9 @@ #include #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/System.hh" -#include "ignition/gazebo/SystemPluginPtr.hh" +#include "gz/sim/config.hh" +#include "gz/sim/System.hh" +#include "gz/sim/SystemPluginPtr.hh" namespace ignition { diff --git a/src/SystemManager.cc b/src/SystemManager.cc index 1397fa9354..8332301ecb 100644 --- a/src/SystemManager.cc +++ b/src/SystemManager.cc @@ -18,10 +18,10 @@ #include #include -#include +#include -#include "ignition/gazebo/components/SystemPluginInfo.hh" -#include "ignition/gazebo/Conversions.hh" +#include "gz/sim/components/SystemPluginInfo.hh" +#include "gz/sim/Conversions.hh" #include "SystemManager.hh" using namespace ignition; diff --git a/src/SystemManager.hh b/src/SystemManager.hh index f6883da4de..75d997d469 100644 --- a/src/SystemManager.hh +++ b/src/SystemManager.hh @@ -17,20 +17,20 @@ #ifndef IGNITION_GAZEBO_SYSTEMMANAGER_HH_ #define IGNITION_GAZEBO_SYSTEMMANAGER_HH_ -#include +#include #include #include #include #include -#include +#include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/Types.hh" +#include "gz/sim/config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/Types.hh" #include "SystemInternal.hh" diff --git a/src/SystemManager_TEST.cc b/src/SystemManager_TEST.cc index 63bec9b571..02a2957334 100644 --- a/src/SystemManager_TEST.cc +++ b/src/SystemManager_TEST.cc @@ -17,12 +17,12 @@ #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/System.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/Types.hh" -#include "ignition/gazebo/components/SystemPluginInfo.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/System.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/Types.hh" +#include "gz/sim/components/SystemPluginInfo.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "SystemManager.hh" diff --git a/src/World.cc b/src/World.cc index 7c6aa87516..d1462b79b9 100644 --- a/src/World.cc +++ b/src/World.cc @@ -18,17 +18,17 @@ #include #include -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/Atmosphere.hh" -#include "ignition/gazebo/components/Gravity.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/MagneticField.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/Atmosphere.hh" +#include "gz/sim/components/Gravity.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/MagneticField.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" #include "gz/sim/components/ParentEntity.hh" -#include "ignition/gazebo/components/SphericalCoordinates.hh" +#include "gz/sim/components/SphericalCoordinates.hh" #include "gz/sim/components/World.hh" -#include "ignition/gazebo/World.hh" +#include "gz/sim/World.hh" class ignition::gazebo::WorldPrivate { diff --git a/src/WorldControl.hh b/src/WorldControl.hh index 9016e8c8f4..9e57ac458f 100644 --- a/src/WorldControl.hh +++ b/src/WorldControl.hh @@ -20,7 +20,7 @@ #include #include -#include "ignition/gazebo/config.hh" +#include "gz/sim/config.hh" namespace ignition { diff --git a/src/comms/Broker.cc b/src/comms/Broker.cc index 8c33c5fa21..3a78971b88 100644 --- a/src/comms/Broker.cc +++ b/src/comms/Broker.cc @@ -15,19 +15,19 @@ * */ -#include -#include -#include +#include +#include +#include #include #include #include -#include -#include "ignition/gazebo/comms/Broker.hh" -#include "ignition/gazebo/comms/MsgManager.hh" -#include "ignition/gazebo/Conversions.hh" -#include "ignition/gazebo/Util.hh" +#include +#include "gz/sim/comms/Broker.hh" +#include "gz/sim/comms/MsgManager.hh" +#include "gz/sim/Conversions.hh" +#include "gz/sim/Util.hh" /// \brief Private Broker data class. class ignition::gazebo::comms::Broker::Implementation diff --git a/src/comms/Broker_TEST.cc b/src/comms/Broker_TEST.cc index 66e263fa9b..0f84d14254 100644 --- a/src/comms/Broker_TEST.cc +++ b/src/comms/Broker_TEST.cc @@ -16,12 +16,12 @@ */ #include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/comms/Broker.hh" -#include "ignition/gazebo/comms/MsgManager.hh" +#include "gz/sim/comms/Broker.hh" +#include "gz/sim/comms/MsgManager.hh" #include "helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/src/comms/ICommsModel.cc b/src/comms/ICommsModel.cc index 7b0074821c..01a74ee965 100644 --- a/src/comms/ICommsModel.cc +++ b/src/comms/ICommsModel.cc @@ -20,13 +20,13 @@ #include #include -#include +#include #include -#include "ignition/gazebo/comms/Broker.hh" -#include "ignition/gazebo/comms/ICommsModel.hh" -#include "ignition/gazebo/comms/MsgManager.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/EventManager.hh" +#include "gz/sim/comms/Broker.hh" +#include "gz/sim/comms/ICommsModel.hh" +#include "gz/sim/comms/MsgManager.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/EventManager.hh" using namespace ignition; using namespace gazebo; diff --git a/src/comms/MsgManager.cc b/src/comms/MsgManager.cc index 4219588099..37575c897e 100644 --- a/src/comms/MsgManager.cc +++ b/src/comms/MsgManager.cc @@ -15,15 +15,15 @@ * */ -#include +#include #include #include -#include -#include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/comms/MsgManager.hh" +#include +#include +#include "gz/sim/config.hh" +#include "gz/sim/comms/MsgManager.hh" /// \brief Private MsgManager data class. class ignition::gazebo::comms::MsgManager::Implementation diff --git a/src/comms/MsgManager_TEST.cc b/src/comms/MsgManager_TEST.cc index b0e0989405..5986e6ff2c 100644 --- a/src/comms/MsgManager_TEST.cc +++ b/src/comms/MsgManager_TEST.cc @@ -16,11 +16,11 @@ */ #include -#include +#include #include -#include "ignition/gazebo/comms/MsgManager.hh" +#include "gz/sim/comms/MsgManager.hh" #include "helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/src/gui/GuiEvents.cc b/src/gui/GuiEvents.cc index b9ce7e8812..99237233f2 100644 --- a/src/gui/GuiEvents.cc +++ b/src/gui/GuiEvents.cc @@ -15,7 +15,7 @@ * */ -#include "ignition/gazebo/gui/GuiEvents.hh" +#include "gz/sim/gui/GuiEvents.hh" class ignition::gazebo::gui::events::GuiNewRemovedEntities::Implementation { diff --git a/src/gui/GuiEvents_TEST.cc b/src/gui/GuiEvents_TEST.cc index cb0bebc999..c0b5e13378 100644 --- a/src/gui/GuiEvents_TEST.cc +++ b/src/gui/GuiEvents_TEST.cc @@ -17,8 +17,8 @@ #include -#include "ignition/gazebo/test_config.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" +#include "gz/sim/test_config.hh" +#include "gz/sim/gui/GuiEvents.hh" using namespace ignition; using namespace gazebo; diff --git a/src/gui/Gui_clean_exit_TEST.cc b/src/gui/Gui_clean_exit_TEST.cc index 4e548ec80e..8dc8c30e52 100644 --- a/src/gui/Gui_clean_exit_TEST.cc +++ b/src/gui/Gui_clean_exit_TEST.cc @@ -20,13 +20,13 @@ #include #include #include -#include -#include +#include +#include #include "helpers/EnvTestFixture.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/gui/Gui.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/Server.hh" +#include "gz/sim/gui/Gui.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) using namespace ignition; diff --git a/src/gui/plugins/align_tool/AlignTool.cc b/src/gui/plugins/align_tool/AlignTool.cc index 765ab5b51b..5fdbcf4f62 100644 --- a/src/gui/plugins/align_tool/AlignTool.cc +++ b/src/gui/plugins/align_tool/AlignTool.cc @@ -16,7 +16,7 @@ */ #include -#include +#include #include #include @@ -27,7 +27,7 @@ #include #include -#include +#include #include #include #include @@ -37,7 +37,7 @@ #include #include #include -#include +#include #include #include "gz/sim/EntityComponentManager.hh" diff --git a/src/gui/plugins/banana_for_scale/BananaForScale.cc b/src/gui/plugins/banana_for_scale/BananaForScale.cc index 469a442950..a134466d00 100644 --- a/src/gui/plugins/banana_for_scale/BananaForScale.cc +++ b/src/gui/plugins/banana_for_scale/BananaForScale.cc @@ -21,16 +21,16 @@ #include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include -#include +#include +#include -#include "ignition/gazebo/gui/GuiEvents.hh" +#include "gz/sim/gui/GuiEvents.hh" namespace ignition::gazebo { diff --git a/src/gui/plugins/banana_for_scale/BananaForScale.hh b/src/gui/plugins/banana_for_scale/BananaForScale.hh index 7016e22392..36e71d28f5 100644 --- a/src/gui/plugins/banana_for_scale/BananaForScale.hh +++ b/src/gui/plugins/banana_for_scale/BananaForScale.hh @@ -20,7 +20,7 @@ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 6c366f1f84..c95a915ea4 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -234,7 +234,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const msgs::Light &_data) ////////////////////////////////////////////////// template<> -void gazebo::setData(QStandardItem *_item, +void ignition::gazebo::setData(QStandardItem *_item, const math::Vector3d &_data) { if (nullptr == _item) diff --git a/src/gui/plugins/component_inspector/ComponentInspector.hh b/src/gui/plugins/component_inspector/ComponentInspector.hh index 807b777a15..2060068510 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.hh +++ b/src/gui/plugins/component_inspector/ComponentInspector.hh @@ -34,7 +34,7 @@ #include "Types.hh" -#include +#include Q_DECLARE_METATYPE(ignition::gazebo::ComponentTypeId) diff --git a/src/gui/plugins/component_inspector/SystemPluginInfo.cc b/src/gui/plugins/component_inspector/SystemPluginInfo.cc index e8ecf8a932..6fbf8c7950 100644 --- a/src/gui/plugins/component_inspector/SystemPluginInfo.cc +++ b/src/gui/plugins/component_inspector/SystemPluginInfo.cc @@ -14,10 +14,10 @@ * limitations under the License. * */ -#include +#include -#include -#include +#include +#include #include "SystemPluginInfo.hh" #include "ComponentInspector.hh" diff --git a/src/gui/plugins/component_inspector/SystemPluginInfo.hh b/src/gui/plugins/component_inspector/SystemPluginInfo.hh index 43c2698c9c..80569ef76c 100644 --- a/src/gui/plugins/component_inspector/SystemPluginInfo.hh +++ b/src/gui/plugins/component_inspector/SystemPluginInfo.hh @@ -17,7 +17,7 @@ #ifndef IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_SYSTEMINFO_HH_ #define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_SYSTEMINFO_HH_ -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/EntityComponentManager.hh" #include #include diff --git a/src/gui/plugins/component_inspector_editor/AirPressure.cc b/src/gui/plugins/component_inspector_editor/AirPressure.cc index 5f8baf3d0a..65d3b10cf8 100644 --- a/src/gui/plugins/component_inspector_editor/AirPressure.cc +++ b/src/gui/plugins/component_inspector_editor/AirPressure.cc @@ -16,9 +16,9 @@ */ #include -#include -#include -#include +#include +#include +#include #include "AirPressure.hh" #include "ComponentInspectorEditor.hh" diff --git a/src/gui/plugins/component_inspector_editor/Altimeter.cc b/src/gui/plugins/component_inspector_editor/Altimeter.cc index 480a6c5eaa..672b617fa3 100644 --- a/src/gui/plugins/component_inspector_editor/Altimeter.cc +++ b/src/gui/plugins/component_inspector_editor/Altimeter.cc @@ -16,8 +16,8 @@ */ #include -#include -#include +#include +#include #include "Altimeter.hh" #include "ComponentInspectorEditor.hh" diff --git a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc index 8c14082c2a..6aacd3b4dc 100644 --- a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc +++ b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc @@ -22,62 +22,62 @@ #include #include -#include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/AngularAcceleration.hh" -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/BatterySoC.hh" -#include "ignition/gazebo/components/CastShadows.hh" -#include "ignition/gazebo/components/CenterOfVolume.hh" -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Gravity.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/LaserRetro.hh" -#include "ignition/gazebo/components/Level.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/LightCmd.hh" -#include "ignition/gazebo/components/LightType.hh" -#include "ignition/gazebo/components/LinearAcceleration.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/LinearVelocitySeed.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/MagneticField.hh" -#include "ignition/gazebo/components/Material.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/ParentLinkName.hh" -#include "ignition/gazebo/components/Performer.hh" -#include "ignition/gazebo/components/PerformerAffinity.hh" -#include "ignition/gazebo/components/Physics.hh" -#include "ignition/gazebo/components/PhysicsEnginePlugin.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Recreate.hh" -#include "ignition/gazebo/components/RenderEngineGuiPlugin.hh" -#include "ignition/gazebo/components/RenderEngineServerPlugin.hh" -#include "ignition/gazebo/components/SelfCollide.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/SourceFilePath.hh" -#include "ignition/gazebo/components/SphericalCoordinates.hh" -#include "ignition/gazebo/components/Static.hh" -#include "ignition/gazebo/components/ThreadPitch.hh" -#include "ignition/gazebo/components/Transparency.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/Volume.hh" -#include "ignition/gazebo/components/WindMode.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" -#include "ignition/gazebo/Util.hh" +#include +#include +#include +#include +#include +#include +#include + +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/AngularAcceleration.hh" +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/BatterySoC.hh" +#include "gz/sim/components/CastShadows.hh" +#include "gz/sim/components/CenterOfVolume.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Gravity.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/LaserRetro.hh" +#include "gz/sim/components/Level.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/LightCmd.hh" +#include "gz/sim/components/LightType.hh" +#include "gz/sim/components/LinearAcceleration.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/LinearVelocitySeed.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/MagneticField.hh" +#include "gz/sim/components/Material.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/ParentLinkName.hh" +#include "gz/sim/components/Performer.hh" +#include "gz/sim/components/PerformerAffinity.hh" +#include "gz/sim/components/Physics.hh" +#include "gz/sim/components/PhysicsEnginePlugin.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Recreate.hh" +#include "gz/sim/components/RenderEngineGuiPlugin.hh" +#include "gz/sim/components/RenderEngineServerPlugin.hh" +#include "gz/sim/components/SelfCollide.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/SourceFilePath.hh" +#include "gz/sim/components/SphericalCoordinates.hh" +#include "gz/sim/components/Static.hh" +#include "gz/sim/components/ThreadPitch.hh" +#include "gz/sim/components/Transparency.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/Volume.hh" +#include "gz/sim/components/WindMode.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/gui/GuiEvents.hh" +#include "gz/sim/Util.hh" #include "AirPressure.hh" #include "Altimeter.hh" diff --git a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.hh b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.hh index f4e2ac3b8d..a68c48f47e 100644 --- a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.hh +++ b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.hh @@ -26,13 +26,13 @@ #include #include -#include +#include -#include -#include -#include +#include +#include +#include -#include +#include #include "Types.hh" Q_DECLARE_METATYPE(ignition::gazebo::ComponentTypeId) diff --git a/src/gui/plugins/component_inspector_editor/Imu.cc b/src/gui/plugins/component_inspector_editor/Imu.cc index 4dbd6a099a..5a2b4beb04 100644 --- a/src/gui/plugins/component_inspector_editor/Imu.cc +++ b/src/gui/plugins/component_inspector_editor/Imu.cc @@ -16,9 +16,9 @@ */ #include -#include -#include -#include +#include +#include +#include #include "ComponentInspectorEditor.hh" #include "Imu.hh" diff --git a/src/gui/plugins/component_inspector_editor/JointType.cc b/src/gui/plugins/component_inspector_editor/JointType.cc index b8f70106fe..25191b0303 100644 --- a/src/gui/plugins/component_inspector_editor/JointType.cc +++ b/src/gui/plugins/component_inspector_editor/JointType.cc @@ -16,11 +16,11 @@ */ #include -#include -#include "ignition/gazebo/components/JointType.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Recreate.hh" -#include +#include +#include "gz/sim/components/JointType.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Recreate.hh" +#include #include "JointType.hh" #include "ComponentInspectorEditor.hh" diff --git a/src/gui/plugins/component_inspector_editor/Lidar.cc b/src/gui/plugins/component_inspector_editor/Lidar.cc index 36ae02162f..00cde19708 100644 --- a/src/gui/plugins/component_inspector_editor/Lidar.cc +++ b/src/gui/plugins/component_inspector_editor/Lidar.cc @@ -16,9 +16,9 @@ */ #include -#include -#include -#include +#include +#include +#include #include "ComponentInspectorEditor.hh" #include "Lidar.hh" diff --git a/src/gui/plugins/component_inspector_editor/Magnetometer.cc b/src/gui/plugins/component_inspector_editor/Magnetometer.cc index 3ba125ae70..0c2fa64ef3 100644 --- a/src/gui/plugins/component_inspector_editor/Magnetometer.cc +++ b/src/gui/plugins/component_inspector_editor/Magnetometer.cc @@ -16,8 +16,8 @@ */ #include -#include -#include +#include +#include #include "ComponentInspectorEditor.hh" #include "Magnetometer.hh" diff --git a/src/gui/plugins/component_inspector_editor/ModelEditor.cc b/src/gui/plugins/component_inspector_editor/ModelEditor.cc index 91699dd528..2f88fcd717 100644 --- a/src/gui/plugins/component_inspector_editor/ModelEditor.cc +++ b/src/gui/plugins/component_inspector_editor/ModelEditor.cc @@ -23,11 +23,11 @@ #include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include @@ -39,15 +39,15 @@ #include #include -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Recreate.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/SdfEntityCreator.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Recreate.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/SdfEntityCreator.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/gui/GuiEvents.hh" +#include "gz/sim/Util.hh" #include "ModelEditor.hh" diff --git a/src/gui/plugins/component_inspector_editor/ModelEditor.hh b/src/gui/plugins/component_inspector_editor/ModelEditor.hh index bfc09df897..8234dfb5ac 100644 --- a/src/gui/plugins/component_inspector_editor/ModelEditor.hh +++ b/src/gui/plugins/component_inspector_editor/ModelEditor.hh @@ -22,7 +22,7 @@ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/component_inspector_editor/Pose3d.cc b/src/gui/plugins/component_inspector_editor/Pose3d.cc index 42a349d8f8..e8a8d3d701 100644 --- a/src/gui/plugins/component_inspector_editor/Pose3d.cc +++ b/src/gui/plugins/component_inspector_editor/Pose3d.cc @@ -14,13 +14,13 @@ * limitations under the License. * */ -#include +#include -#include -#include -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Recreate.hh" -#include +#include +#include +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Recreate.hh" +#include #include "ComponentInspectorEditor.hh" #include "Pose3d.hh" diff --git a/src/gui/plugins/component_inspector_editor/Pose3d.hh b/src/gui/plugins/component_inspector_editor/Pose3d.hh index 5407edbc02..2a4f27973a 100644 --- a/src/gui/plugins/component_inspector_editor/Pose3d.hh +++ b/src/gui/plugins/component_inspector_editor/Pose3d.hh @@ -18,7 +18,7 @@ #define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_POSE3D_HH_ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/component_inspector_editor/Types.hh b/src/gui/plugins/component_inspector_editor/Types.hh index b8eb0ff422..78e8463d1b 100644 --- a/src/gui/plugins/component_inspector_editor/Types.hh +++ b/src/gui/plugins/component_inspector_editor/Types.hh @@ -23,7 +23,7 @@ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/copy_paste/CopyPaste.cc b/src/gui/plugins/copy_paste/CopyPaste.cc index 7b633c3176..52bb86b9ce 100644 --- a/src/gui/plugins/copy_paste/CopyPaste.cc +++ b/src/gui/plugins/copy_paste/CopyPaste.cc @@ -19,15 +19,15 @@ #include #include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" +#include +#include +#include +#include +#include +#include + +#include "gz/sim/components/Name.hh" +#include "gz/sim/gui/GuiEvents.hh" #include "CopyPaste.hh" diff --git a/src/gui/plugins/copy_paste/CopyPaste.hh b/src/gui/plugins/copy_paste/CopyPaste.hh index 9b54d85b94..0ac3dc3301 100644 --- a/src/gui/plugins/copy_paste/CopyPaste.hh +++ b/src/gui/plugins/copy_paste/CopyPaste.hh @@ -20,9 +20,9 @@ #include -#include +#include -#include "ignition/gazebo/gui/GuiSystem.hh" +#include "gz/sim/gui/GuiSystem.hh" namespace ignition { diff --git a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc index ebba5b6c54..ff916ff00b 100644 --- a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc +++ b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc @@ -22,18 +22,18 @@ #include -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include -#include +#include -#include -#include -#include +#include +#include +#include namespace ignition::gazebo { diff --git a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh index 4ed5858f3a..e7fd8b0966 100644 --- a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh +++ b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh @@ -20,11 +20,11 @@ #include -#include +#include -#include +#include -#include +#include namespace ignition { diff --git a/src/gui/plugins/lights/Lights.cc b/src/gui/plugins/lights/Lights.cc index 81ff6554ef..395c4607d9 100644 --- a/src/gui/plugins/lights/Lights.cc +++ b/src/gui/plugins/lights/Lights.cc @@ -17,23 +17,23 @@ #include "Lights.hh" -#include -#include +#include +#include #include #include #include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Primitives.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Primitives.hh" namespace ignition::gazebo { diff --git a/src/gui/plugins/lights/Lights.hh b/src/gui/plugins/lights/Lights.hh index 9caecfbbef..49fd8dd063 100644 --- a/src/gui/plugins/lights/Lights.hh +++ b/src/gui/plugins/lights/Lights.hh @@ -20,7 +20,7 @@ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/plotting/Plotting.cc b/src/gui/plugins/plotting/Plotting.cc index a6f5228ae5..902e0e5962 100644 --- a/src/gui/plugins/plotting/Plotting.cc +++ b/src/gui/plugins/plotting/Plotting.cc @@ -17,27 +17,27 @@ #include "Plotting.hh" -#include - -#include "ignition/gazebo/components/AngularAcceleration.hh" -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/CastShadows.hh" -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Gravity.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/LinearAcceleration.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/LinearVelocitySeed.hh" -#include "ignition/gazebo/components/MagneticField.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Physics.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/PoseCmd.hh" -#include "ignition/gazebo/components/SphericalCoordinates.hh" -#include "ignition/gazebo/components/Static.hh" -#include "ignition/gazebo/components/WindMode.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/EntityComponentManager.hh" +#include + +#include "gz/sim/components/AngularAcceleration.hh" +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/CastShadows.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Gravity.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/LinearAcceleration.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/LinearVelocitySeed.hh" +#include "gz/sim/components/MagneticField.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Physics.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/PoseCmd.hh" +#include "gz/sim/components/SphericalCoordinates.hh" +#include "gz/sim/components/Static.hh" +#include "gz/sim/components/WindMode.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/EntityComponentManager.hh" namespace ignition::gazebo { diff --git a/src/gui/plugins/plotting/Plotting.hh b/src/gui/plugins/plotting/Plotting.hh index 9e85c62264..578bb7ff6c 100644 --- a/src/gui/plugins/plotting/Plotting.hh +++ b/src/gui/plugins/plotting/Plotting.hh @@ -17,14 +17,14 @@ #ifndef IGNITION_GUI_PLUGINS_PLOTTING_HH_ #define IGNITION_GUI_PLUGINS_PLOTTING_HH_ -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include #include "sdf/Physics.hh" diff --git a/src/gui/plugins/resource_spawner/ResourceSpawner.cc b/src/gui/plugins/resource_spawner/ResourceSpawner.cc index 935f2c7201..205edac008 100644 --- a/src/gui/plugins/resource_spawner/ResourceSpawner.cc +++ b/src/gui/plugins/resource_spawner/ResourceSpawner.cc @@ -33,7 +33,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index c73fcbd927..20a4212356 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -49,7 +49,7 @@ #include #include -#include +#include #include #include #include diff --git a/src/gui/plugins/scene_manager/GzSceneManager.cc b/src/gui/plugins/scene_manager/GzSceneManager.cc index 9d0c6b1338..62bdf3c70d 100644 --- a/src/gui/plugins/scene_manager/GzSceneManager.cc +++ b/src/gui/plugins/scene_manager/GzSceneManager.cc @@ -26,21 +26,21 @@ #include -#include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/SystemPluginInfo.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" -#include "ignition/gazebo/rendering/RenderUtil.hh" +#include +#include +#include +#include +#include +#include +#include + +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/SystemPluginInfo.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/gui/GuiEvents.hh" +#include "gz/sim/rendering/RenderUtil.hh" namespace ignition { diff --git a/src/gui/plugins/scene_manager/GzSceneManager.hh b/src/gui/plugins/scene_manager/GzSceneManager.hh index 34208e0b33..c84f33322e 100644 --- a/src/gui/plugins/scene_manager/GzSceneManager.hh +++ b/src/gui/plugins/scene_manager/GzSceneManager.hh @@ -20,7 +20,7 @@ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/select_entities/SelectEntities.cc b/src/gui/plugins/select_entities/SelectEntities.cc index 921dd03242..fb5ab946f6 100644 --- a/src/gui/plugins/select_entities/SelectEntities.cc +++ b/src/gui/plugins/select_entities/SelectEntities.cc @@ -23,20 +23,20 @@ #include -#include -#include -#include -#include -#include -#include -#include -#include -#include "ignition/rendering/Camera.hh" - -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/rendering/RenderUtil.hh" +#include +#include +#include +#include +#include +#include +#include +#include +#include "gz/rendering/Camera.hh" + +#include "gz/sim/Entity.hh" +#include "gz/sim/gui/GuiEvents.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/rendering/RenderUtil.hh" #include "SelectEntities.hh" diff --git a/src/gui/plugins/select_entities/SelectEntities.hh b/src/gui/plugins/select_entities/SelectEntities.hh index cdbd3a172c..6643ab539e 100644 --- a/src/gui/plugins/select_entities/SelectEntities.hh +++ b/src/gui/plugins/select_entities/SelectEntities.hh @@ -20,7 +20,7 @@ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/spawn/Spawn.cc b/src/gui/plugins/spawn/Spawn.cc index be60287e52..cc33737aa4 100644 --- a/src/gui/plugins/spawn/Spawn.cc +++ b/src/gui/plugins/spawn/Spawn.cc @@ -17,8 +17,8 @@ #include "Spawn.hh" -#include -#include +#include +#include #include #include @@ -27,35 +27,35 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include -#include -#include -#include -#include +#include +#include +#include +#include -#include -#include +#include +#include -#include +#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include -#include -#include +#include +#include #include -#include "ignition/gazebo/rendering/RenderUtil.hh" -#include "ignition/gazebo/rendering/SceneManager.hh" +#include "gz/sim/rendering/RenderUtil.hh" +#include "gz/sim/rendering/SceneManager.hh" namespace ignition::gazebo { diff --git a/src/gui/plugins/spawn/Spawn.hh b/src/gui/plugins/spawn/Spawn.hh index f87ec4c160..43e5844919 100644 --- a/src/gui/plugins/spawn/Spawn.hh +++ b/src/gui/plugins/spawn/Spawn.hh @@ -20,8 +20,8 @@ #include -#include -#include +#include +#include namespace ignition { diff --git a/src/gui/plugins/transform_control/TransformControl.cc b/src/gui/plugins/transform_control/TransformControl.cc index bfe09786aa..5f51340eac 100644 --- a/src/gui/plugins/transform_control/TransformControl.cc +++ b/src/gui/plugins/transform_control/TransformControl.cc @@ -27,11 +27,11 @@ #include #include -#include -#include +#include +#include #include -#include -#include +#include +#include #include #include #include @@ -40,7 +40,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/gui/plugins/video_recorder/VideoRecorder.cc b/src/gui/plugins/video_recorder/VideoRecorder.cc index 64a6a66a27..061e008b84 100644 --- a/src/gui/plugins/video_recorder/VideoRecorder.cc +++ b/src/gui/plugins/video_recorder/VideoRecorder.cc @@ -25,15 +25,15 @@ #include #include -#include -#include +#include +#include #include -#include -#include +#include +#include #include -#include -#include -#include +#include +#include +#include #include #include diff --git a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc index e995949bab..34305ecc5a 100644 --- a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc +++ b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc @@ -17,8 +17,8 @@ #include "VisualizationCapabilities.hh" -#include -#include +#include +#include #include #include @@ -32,33 +32,33 @@ #include #include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -#include - -#include "ignition/rendering/AxisVisual.hh" -#include "ignition/rendering/Capsule.hh" -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include + +#include "gz/rendering/AxisVisual.hh" +#include "gz/rendering/Capsule.hh" +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include #include #include @@ -69,29 +69,29 @@ #include #include -#include "ignition/gazebo/components/CastShadows.hh" -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/Geometry.hh" -#include "ignition/gazebo/components/Inertial.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/JointType.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/ParentLinkName.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Scene.hh" -#include "ignition/gazebo/components/Transparency.hh" -#include "ignition/gazebo/components/Visibility.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/World.hh" - -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/rendering/RenderUtil.hh" -#include "ignition/gazebo/rendering/SceneManager.hh" +#include "gz/sim/components/CastShadows.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/Geometry.hh" +#include "gz/sim/components/Inertial.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/JointType.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/ParentLinkName.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Scene.hh" +#include "gz/sim/components/Transparency.hh" +#include "gz/sim/components/Visibility.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.hh" + +#include "gz/sim/Util.hh" +#include "gz/sim/rendering/RenderUtil.hh" +#include "gz/sim/rendering/SceneManager.hh" namespace ignition::gazebo { diff --git a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.hh b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.hh index 99a400f7eb..9d9d646448 100644 --- a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.hh +++ b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.hh @@ -20,7 +20,7 @@ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/visualize_contacts/VisualizeContacts.cc b/src/gui/plugins/visualize_contacts/VisualizeContacts.cc index 4420d90d05..58b4339c4a 100644 --- a/src/gui/plugins/visualize_contacts/VisualizeContacts.cc +++ b/src/gui/plugins/visualize_contacts/VisualizeContacts.cc @@ -15,8 +15,8 @@ * */ -#include -#include +#include +#include #include #include @@ -24,27 +24,27 @@ #include #include -#include +#include -#include +#include -#include -#include +#include +#include -#include +#include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/ContactSensor.hh" -#include "ignition/gazebo/components/ContactSensorData.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" -#include "ignition/gazebo/rendering/RenderUtil.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/ContactSensor.hh" +#include "gz/sim/components/ContactSensorData.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/gui/GuiEvents.hh" +#include "gz/sim/rendering/RenderUtil.hh" #include "VisualizeContacts.hh" diff --git a/src/gui/plugins/visualize_contacts/VisualizeContacts.hh b/src/gui/plugins/visualize_contacts/VisualizeContacts.hh index f1c6211084..333d8edf60 100644 --- a/src/gui/plugins/visualize_contacts/VisualizeContacts.hh +++ b/src/gui/plugins/visualize_contacts/VisualizeContacts.hh @@ -20,9 +20,9 @@ #include -#include +#include -#include "ignition/gui/qt.h" +#include "gz/gui/qt.h" namespace ignition { diff --git a/src/gui/plugins/visualize_lidar/VisualizeLidar.cc b/src/gui/plugins/visualize_lidar/VisualizeLidar.cc index 1a39fcffdf..1a1a0ea6a7 100644 --- a/src/gui/plugins/visualize_lidar/VisualizeLidar.cc +++ b/src/gui/plugins/visualize_lidar/VisualizeLidar.cc @@ -24,41 +24,41 @@ #include #include -#include -#include +#include +#include -#include +#include -#include -#include +#include +#include -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/rendering/RenderUtil.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/rendering/RenderUtil.hh" -#include "ignition/rendering/RenderTypes.hh" -#include "ignition/rendering/RenderingIface.hh" -#include "ignition/rendering/RenderEngine.hh" -#include "ignition/rendering/Scene.hh" -#include "ignition/rendering/LidarVisual.hh" +#include "gz/rendering/RenderTypes.hh" +#include "gz/rendering/RenderingIface.hh" +#include "gz/rendering/RenderEngine.hh" +#include "gz/rendering/Scene.hh" +#include "gz/rendering/LidarVisual.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Util.hh" -#include "ignition/msgs/laserscan.pb.h" +#include "gz/msgs/laserscan.pb.h" namespace ignition { diff --git a/src/gui/plugins/visualize_lidar/VisualizeLidar.hh b/src/gui/plugins/visualize_lidar/VisualizeLidar.hh index 7eebe69977..fe0bcdbad8 100644 --- a/src/gui/plugins/visualize_lidar/VisualizeLidar.hh +++ b/src/gui/plugins/visualize_lidar/VisualizeLidar.hh @@ -20,9 +20,9 @@ #include -#include "ignition/msgs/laserscan.pb.h" -#include "ignition/gazebo/gui/GuiSystem.hh" -#include "ignition/gui/qt.h" +#include "gz/msgs/laserscan.pb.h" +#include "gz/sim/gui/GuiSystem.hh" +#include "gz/gui/qt.h" namespace ignition { diff --git a/src/network/PeerTracker_TEST.cc b/src/network/PeerTracker_TEST.cc index da26ebb84a..fdc1d0d5d9 100644 --- a/src/network/PeerTracker_TEST.cc +++ b/src/network/PeerTracker_TEST.cc @@ -18,8 +18,8 @@ #include #include -#include -#include +#include +#include #include #include "PeerTracker.hh" diff --git a/src/rendering/MarkerManager.cc b/src/rendering/MarkerManager.cc index 9307cc492c..e66e356348 100644 --- a/src/rendering/MarkerManager.cc +++ b/src/rendering/MarkerManager.cc @@ -21,7 +21,7 @@ #include #include -#include +#include #include #include "gz/sim/Events.hh" diff --git a/src/systems/buoyancy/Buoyancy.cc b/src/systems/buoyancy/Buoyancy.cc index b3e9c0abe1..5347737ebb 100644 --- a/src/systems/buoyancy/Buoyancy.cc +++ b/src/systems/buoyancy/Buoyancy.cc @@ -42,7 +42,7 @@ #include "gz/sim/components/Gravity.hh" #include "gz/sim/components/Inertial.hh" #include "gz/sim/components/Link.hh" -#include "ignition/gazebo/components/ParentEntity.hh" +#include "gz/sim/components/ParentEntity.hh" #include "gz/sim/components/Pose.hh" #include "gz/sim/components/Volume.hh" #include "gz/sim/components/World.hh" diff --git a/src/systems/buoyancy_engine/BuoyancyEngine.cc b/src/systems/buoyancy_engine/BuoyancyEngine.cc index d128de4581..d200e22cdd 100644 --- a/src/systems/buoyancy_engine/BuoyancyEngine.cc +++ b/src/systems/buoyancy_engine/BuoyancyEngine.cc @@ -21,14 +21,14 @@ #include #include -#include -#include -#include -#include - -#include -#include -#include +#include +#include +#include +#include + +#include +#include +#include #include "BuoyancyEngine.hh" diff --git a/src/systems/buoyancy_engine/BuoyancyEngine.hh b/src/systems/buoyancy_engine/BuoyancyEngine.hh index 1e6f6747b5..faa0536c37 100644 --- a/src/systems/buoyancy_engine/BuoyancyEngine.hh +++ b/src/systems/buoyancy_engine/BuoyancyEngine.hh @@ -17,7 +17,7 @@ #ifndef IGNITION_GAZEBO_SYSTEMS_BUOYANCYENGINE_HH_ #define IGNITION_GAZEBO_SYSTEMS_BUOYANCYENGINE_HH_ -#include +#include #include diff --git a/src/systems/comms_endpoint/CommsEndpoint.cc b/src/systems/comms_endpoint/CommsEndpoint.cc index 98c4522bac..4202be96e2 100644 --- a/src/systems/comms_endpoint/CommsEndpoint.cc +++ b/src/systems/comms_endpoint/CommsEndpoint.cc @@ -15,19 +15,19 @@ * */ -#include -#include +#include +#include #include #include #include -#include -#include -#include +#include +#include +#include #include -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" #include "CommsEndpoint.hh" using namespace ignition; diff --git a/src/systems/comms_endpoint/CommsEndpoint.hh b/src/systems/comms_endpoint/CommsEndpoint.hh index a21e9b3089..d41841b45c 100644 --- a/src/systems/comms_endpoint/CommsEndpoint.hh +++ b/src/systems/comms_endpoint/CommsEndpoint.hh @@ -19,9 +19,9 @@ #include -#include +#include #include -#include "ignition/gazebo/System.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/detachable_joint/DetachableJoint.cc b/src/systems/detachable_joint/DetachableJoint.cc index c161247b28..15885a14f0 100644 --- a/src/systems/detachable_joint/DetachableJoint.cc +++ b/src/systems/detachable_joint/DetachableJoint.cc @@ -96,9 +96,14 @@ void DetachableJoint::Configure(const Entity &_entity, } // Setup detach topic - std::string defaultTopic{"/model/" + this->model.Name(_ecm) + - "/detachable_joint/detach"}; - this->topic = _sdf->Get("topic", defaultTopic).first; + std::vector topics; + if (_sdf->HasElement("topic")) + { + topics.push_back(_sdf->Get("topic")); + } + topics.push_back("/model/" + this->model.Name(_ecm) + + "/detachable_joint/detach"); + this->topic = validTopic(topics); this->suppressChildWarning = _sdf->Get("suppress_child_warning", this->suppressChildWarning) diff --git a/src/systems/follow_actor/FollowActor.cc b/src/systems/follow_actor/FollowActor.cc index f55c65c8ce..aad9a9e58e 100644 --- a/src/systems/follow_actor/FollowActor.cc +++ b/src/systems/follow_actor/FollowActor.cc @@ -17,15 +17,15 @@ #include -#include +#include -#include +#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include "FollowActor.hh" diff --git a/src/systems/follow_actor/FollowActor.hh b/src/systems/follow_actor/FollowActor.hh index 6c6023d836..019f22d57f 100644 --- a/src/systems/follow_actor/FollowActor.hh +++ b/src/systems/follow_actor/FollowActor.hh @@ -18,8 +18,8 @@ #define IGNITION_GAZEBO_SYSTEMS_FOLLOWACTOR_HH_ #include -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/force_torque/ForceTorque.cc b/src/systems/force_torque/ForceTorque.cc index 7ebd91c3d2..21b15f4243 100644 --- a/src/systems/force_torque/ForceTorque.cc +++ b/src/systems/force_torque/ForceTorque.cc @@ -21,30 +21,30 @@ #include #include -#include +#include #include -#include - -#include - -#include -#include - -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/ForceTorque.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointTransmittedWrench.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/ParentLinkName.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Util.hh" +#include + +#include + +#include +#include + +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/ForceTorque.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointTransmittedWrench.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/ParentLinkName.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/force_torque/ForceTorque.hh b/src/systems/force_torque/ForceTorque.hh index 5df5652fb0..ed4d40e387 100644 --- a/src/systems/force_torque/ForceTorque.hh +++ b/src/systems/force_torque/ForceTorque.hh @@ -18,8 +18,8 @@ #define IGNITION_GAZEBO_SYSTEMS_FORCE_TORQUE_HH_ #include -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/hydrodynamics/Hydrodynamics.cc b/src/systems/hydrodynamics/Hydrodynamics.cc index 4891165dda..a6e67c3b26 100644 --- a/src/systems/hydrodynamics/Hydrodynamics.cc +++ b/src/systems/hydrodynamics/Hydrodynamics.cc @@ -18,20 +18,20 @@ #include -#include +#include -#include "ignition/msgs/vector3d.pb.h" +#include "gz/msgs/vector3d.pb.h" -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/System.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/System.hh" +#include "gz/sim/Util.hh" -#include "ignition/transport/Node.hh" +#include "gz/transport/Node.hh" #include "Hydrodynamics.hh" diff --git a/src/systems/hydrodynamics/Hydrodynamics.hh b/src/systems/hydrodynamics/Hydrodynamics.hh index 0dd8cf3b9e..53187133ad 100644 --- a/src/systems/hydrodynamics/Hydrodynamics.hh +++ b/src/systems/hydrodynamics/Hydrodynamics.hh @@ -17,7 +17,7 @@ #ifndef IGNITION_GAZEBO_SYSTEMS_HYDRODYNAMICS_HH_ #define IGNITION_GAZEBO_SYSTEMS_HYDRODYNAMICS_HH_ -#include +#include #include namespace ignition diff --git a/src/systems/joint_traj_control/JointTrajectoryController.cc b/src/systems/joint_traj_control/JointTrajectoryController.cc index d7cb345e60..c72ef9e457 100644 --- a/src/systems/joint_traj_control/JointTrajectoryController.cc +++ b/src/systems/joint_traj_control/JointTrajectoryController.cc @@ -15,25 +15,25 @@ * */ -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -#include -#include -#include -#include -#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include #include #include diff --git a/src/systems/joint_traj_control/JointTrajectoryController.hh b/src/systems/joint_traj_control/JointTrajectoryController.hh index fb60279d1d..0caa15181a 100644 --- a/src/systems/joint_traj_control/JointTrajectoryController.hh +++ b/src/systems/joint_traj_control/JointTrajectoryController.hh @@ -18,7 +18,7 @@ #ifndef IGNITION_GAZEBO_SYSTEMS_JOINT_TRAJECTORY_CONTROLLER_HH_ #define IGNITION_GAZEBO_SYSTEMS_JOINT_TRAJECTORY_CONTROLLER_HH_ -#include +#include #include namespace ignition diff --git a/src/systems/label/Label.cc b/src/systems/label/Label.cc index 09986de104..1f76d0bd0a 100644 --- a/src/systems/label/Label.cc +++ b/src/systems/label/Label.cc @@ -19,14 +19,14 @@ #include #include -#include +#include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/SemanticLabel.hh" -#include "ignition/gazebo/components/Visual.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/SemanticLabel.hh" +#include "gz/sim/components/Visual.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/label/Label.hh b/src/systems/label/Label.hh index a0d6fffde6..4f09d886de 100644 --- a/src/systems/label/Label.hh +++ b/src/systems/label/Label.hh @@ -19,8 +19,8 @@ #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/System.hh" +#include "gz/sim/config.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/log/LogPlayback.cc b/src/systems/log/LogPlayback.cc index e1e99dec25..49719c6f9f 100644 --- a/src/systems/log/LogPlayback.cc +++ b/src/systems/log/LogPlayback.cc @@ -17,7 +17,6 @@ #include "LogPlayback.hh" -#include #include #include diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc index e0c7dd86ab..9b8325c629 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc @@ -31,7 +31,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/systems/mecanum_drive/MecanumDrive.cc b/src/systems/mecanum_drive/MecanumDrive.cc index 59dd701675..3b1ff40312 100644 --- a/src/systems/mecanum_drive/MecanumDrive.cc +++ b/src/systems/mecanum_drive/MecanumDrive.cc @@ -17,7 +17,7 @@ #include "MecanumDrive.hh" -#include +#include #include #include @@ -25,19 +25,19 @@ #include #include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/CanonicalLink.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/JointVelocityCmd.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include +#include +#include +#include +#include +#include + +#include "gz/sim/components/CanonicalLink.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/JointVelocityCmd.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/mecanum_drive/MecanumDrive.hh b/src/systems/mecanum_drive/MecanumDrive.hh index e9db61c2c9..38b7e342fe 100644 --- a/src/systems/mecanum_drive/MecanumDrive.hh +++ b/src/systems/mecanum_drive/MecanumDrive.hh @@ -19,7 +19,7 @@ #include -#include +#include namespace ignition { diff --git a/src/systems/model_photo_shoot/ModelPhotoShoot.cc b/src/systems/model_photo_shoot/ModelPhotoShoot.cc index 31f6373e1c..75d18c84cb 100644 --- a/src/systems/model_photo_shoot/ModelPhotoShoot.cc +++ b/src/systems/model_photo_shoot/ModelPhotoShoot.cc @@ -20,23 +20,23 @@ #include #include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/JointType.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/JointPositionReset.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/rendering/Events.hh" -#include "ignition/gazebo/Util.hh" +#include +#include +#include +#include +#include +#include + +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/JointType.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/JointPositionReset.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/rendering/Events.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/model_photo_shoot/ModelPhotoShoot.hh b/src/systems/model_photo_shoot/ModelPhotoShoot.hh index b059f2486e..9a14609c6a 100644 --- a/src/systems/model_photo_shoot/ModelPhotoShoot.hh +++ b/src/systems/model_photo_shoot/ModelPhotoShoot.hh @@ -21,7 +21,7 @@ #include -#include "ignition/gazebo/System.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/multicopter_motor_model/MulticopterMotorModel.cc b/src/systems/multicopter_motor_model/MulticopterMotorModel.cc index 914918770a..e438b715f5 100644 --- a/src/systems/multicopter_motor_model/MulticopterMotorModel.cc +++ b/src/systems/multicopter_motor_model/MulticopterMotorModel.cc @@ -35,7 +35,7 @@ #include #include #include -#include +#include #include diff --git a/src/systems/navsat/NavSat.cc b/src/systems/navsat/NavSat.cc index 2eea382d9e..2d56ef302a 100644 --- a/src/systems/navsat/NavSat.cc +++ b/src/systems/navsat/NavSat.cc @@ -17,7 +17,7 @@ #include "NavSat.hh" -#include +#include #include #include @@ -27,22 +27,22 @@ #include -#include -#include +#include +#include -#include -#include +#include +#include -#include -#include +#include +#include -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/NavSat.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/NavSat.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/navsat/NavSat.hh b/src/systems/navsat/NavSat.hh index e4ce4f34d6..71c10b75e1 100644 --- a/src/systems/navsat/NavSat.hh +++ b/src/systems/navsat/NavSat.hh @@ -17,10 +17,10 @@ #ifndef IGNITION_GAZEBO_SYSTEMS_NAVSAT_HH_ #define IGNITION_GAZEBO_SYSTEMS_NAVSAT_HH_ -#include +#include -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/odometry_publisher/OdometryPublisher.cc b/src/systems/odometry_publisher/OdometryPublisher.cc index 8b6270c0fd..1b8b2c8e58 100644 --- a/src/systems/odometry_publisher/OdometryPublisher.cc +++ b/src/systems/odometry_publisher/OdometryPublisher.cc @@ -17,8 +17,8 @@ #include "OdometryPublisher.hh" -#include -#include +#include +#include #include #include @@ -26,18 +26,18 @@ #include #include -#include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include +#include +#include +#include +#include +#include +#include + +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/odometry_publisher/OdometryPublisher.hh b/src/systems/odometry_publisher/OdometryPublisher.hh index c087ad51a0..0e8eb4b814 100644 --- a/src/systems/odometry_publisher/OdometryPublisher.hh +++ b/src/systems/odometry_publisher/OdometryPublisher.hh @@ -19,7 +19,7 @@ #include -#include +#include namespace ignition { diff --git a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc index 6007d95259..a6e2fec324 100644 --- a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc +++ b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc @@ -21,26 +21,26 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include -#include "ignition/gazebo/components/ContactSensor.hh" -#include "ignition/gazebo/components/ContactSensorData.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/DepthCamera.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Geometry.hh" +#include "gz/sim/components/ContactSensor.hh" +#include "gz/sim/components/ContactSensorData.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/DepthCamera.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Geometry.hh" #include "sdf/Box.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" #include "OpticalTactilePlugin.hh" diff --git a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh index 30853d164a..bb89595861 100644 --- a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh +++ b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh @@ -19,7 +19,7 @@ #define IGNITION_GAZEBO_SYSTEMS_OPTICAL_TACTILE_PLUGIN_HH_ #include -#include +#include #include "Visualization.hh" namespace ignition diff --git a/src/systems/optical_tactile_plugin/Visualization.cc b/src/systems/optical_tactile_plugin/Visualization.cc index d330e6a9d4..16c55a814f 100644 --- a/src/systems/optical_tactile_plugin/Visualization.cc +++ b/src/systems/optical_tactile_plugin/Visualization.cc @@ -15,9 +15,9 @@ * */ -#include -#include -#include +#include +#include +#include #include "Visualization.hh" diff --git a/src/systems/optical_tactile_plugin/Visualization.hh b/src/systems/optical_tactile_plugin/Visualization.hh index 96c8b46cc0..b2bee311e8 100644 --- a/src/systems/optical_tactile_plugin/Visualization.hh +++ b/src/systems/optical_tactile_plugin/Visualization.hh @@ -21,11 +21,11 @@ #include #include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/components/ContactSensorData.hh" +#include "gz/sim/components/ContactSensorData.hh" namespace ignition { diff --git a/src/systems/particle_emitter/ParticleEmitter.cc b/src/systems/particle_emitter/ParticleEmitter.cc index db1aa6b924..fae477f3f0 100644 --- a/src/systems/particle_emitter/ParticleEmitter.cc +++ b/src/systems/particle_emitter/ParticleEmitter.cc @@ -15,27 +15,27 @@ * */ -#include +#include #include #include #include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include #include #include "ParticleEmitter.hh" diff --git a/src/systems/particle_emitter/ParticleEmitter.hh b/src/systems/particle_emitter/ParticleEmitter.hh index 6a3da57d23..8fc1f91def 100644 --- a/src/systems/particle_emitter/ParticleEmitter.hh +++ b/src/systems/particle_emitter/ParticleEmitter.hh @@ -19,7 +19,7 @@ #include -#include +#include namespace ignition { diff --git a/src/systems/particle_emitter2/ParticleEmitter2.cc b/src/systems/particle_emitter2/ParticleEmitter2.cc index 6e0c290992..d79d45cb1c 100644 --- a/src/systems/particle_emitter2/ParticleEmitter2.cc +++ b/src/systems/particle_emitter2/ParticleEmitter2.cc @@ -15,24 +15,24 @@ * */ -#include -#include +#include +#include #include #include #include #include -#include -#include -#include -#include +#include +#include +#include +#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include "ParticleEmitter2.hh" using namespace std::chrono_literals; diff --git a/src/systems/particle_emitter2/ParticleEmitter2.hh b/src/systems/particle_emitter2/ParticleEmitter2.hh index a52d39f65f..e9e489a8ff 100644 --- a/src/systems/particle_emitter2/ParticleEmitter2.hh +++ b/src/systems/particle_emitter2/ParticleEmitter2.hh @@ -19,7 +19,7 @@ #include -#include +#include namespace ignition { diff --git a/src/systems/perfect_comms/PerfectComms.cc b/src/systems/perfect_comms/PerfectComms.cc index 08f24cc033..75b7eefe81 100644 --- a/src/systems/perfect_comms/PerfectComms.cc +++ b/src/systems/perfect_comms/PerfectComms.cc @@ -17,11 +17,11 @@ #include -#include -#include -#include "ignition/gazebo/comms/Broker.hh" -#include "ignition/gazebo/comms/MsgManager.hh" -#include "ignition/gazebo/Util.hh" +#include +#include +#include "gz/sim/comms/Broker.hh" +#include "gz/sim/comms/MsgManager.hh" +#include "gz/sim/Util.hh" #include "PerfectComms.hh" using namespace ignition; diff --git a/src/systems/perfect_comms/PerfectComms.hh b/src/systems/perfect_comms/PerfectComms.hh index 9ac93f07a7..14e200b518 100644 --- a/src/systems/perfect_comms/PerfectComms.hh +++ b/src/systems/perfect_comms/PerfectComms.hh @@ -19,10 +19,10 @@ #include -#include +#include #include -#include "ignition/gazebo/comms/ICommsModel.hh" -#include "ignition/gazebo/System.hh" +#include "gz/sim/comms/ICommsModel.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/physics/CanonicalLinkModelTracker.hh b/src/systems/physics/CanonicalLinkModelTracker.hh index 4f6f01443e..44e6f99e02 100644 --- a/src/systems/physics/CanonicalLinkModelTracker.hh +++ b/src/systems/physics/CanonicalLinkModelTracker.hh @@ -20,11 +20,11 @@ #include #include -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/components/CanonicalLink.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/config.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/components/CanonicalLink.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/config.hh" namespace ignition::gazebo { diff --git a/src/systems/rf_comms/RFComms.cc b/src/systems/rf_comms/RFComms.cc index 2ec1444cd0..978c36a74f 100644 --- a/src/systems/rf_comms/RFComms.cc +++ b/src/systems/rf_comms/RFComms.cc @@ -15,7 +15,7 @@ * */ -#include +#include #include #include @@ -26,15 +26,15 @@ #include #include -#include -#include -#include -#include -#include "ignition/gazebo/comms/MsgManager.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include +#include +#include +#include +#include "gz/sim/comms/MsgManager.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" #include "RFComms.hh" using namespace ignition; diff --git a/src/systems/rf_comms/RFComms.hh b/src/systems/rf_comms/RFComms.hh index c36696b62a..14e482b4aa 100644 --- a/src/systems/rf_comms/RFComms.hh +++ b/src/systems/rf_comms/RFComms.hh @@ -19,10 +19,10 @@ #include -#include +#include #include -#include "ignition/gazebo/comms/ICommsModel.hh" -#include "ignition/gazebo/System.hh" +#include "gz/sim/comms/ICommsModel.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/shader_param/ShaderParam.cc b/src/systems/shader_param/ShaderParam.cc index a97eeb4dbe..01cb24de8c 100644 --- a/src/systems/shader_param/ShaderParam.cc +++ b/src/systems/shader_param/ShaderParam.cc @@ -24,21 +24,21 @@ #include #include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include #include -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/SourceFilePath.hh" -#include "ignition/gazebo/rendering/Events.hh" -#include "ignition/gazebo/rendering/RenderUtil.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/SourceFilePath.hh" +#include "gz/sim/rendering/Events.hh" +#include "gz/sim/rendering/RenderUtil.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/shader_param/ShaderParam.hh b/src/systems/shader_param/ShaderParam.hh index 7b6135dd79..98c3fb2e6e 100644 --- a/src/systems/shader_param/ShaderParam.hh +++ b/src/systems/shader_param/ShaderParam.hh @@ -20,7 +20,7 @@ #include -#include "ignition/gazebo/System.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/thermal/ThermalSensor.cc b/src/systems/thermal/ThermalSensor.cc index 72e5f60a45..030b9c7bcf 100644 --- a/src/systems/thermal/ThermalSensor.cc +++ b/src/systems/thermal/ThermalSensor.cc @@ -20,14 +20,14 @@ #include #include -#include -#include +#include +#include -#include "ignition/gazebo/components/ThermalCamera.hh" -#include "ignition/gazebo/components/Temperature.hh" -#include "ignition/gazebo/components/TemperatureRange.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/ThermalCamera.hh" +#include "gz/sim/components/Temperature.hh" +#include "gz/sim/components/TemperatureRange.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/thermal/ThermalSensor.hh b/src/systems/thermal/ThermalSensor.hh index c0a27306d3..dae7094bb3 100644 --- a/src/systems/thermal/ThermalSensor.hh +++ b/src/systems/thermal/ThermalSensor.hh @@ -18,9 +18,9 @@ #define IGNITION_GAZEBO_SYSTEMS_THERMALSENSOR_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/src/systems/thruster/Thruster.cc b/src/systems/thruster/Thruster.cc index e3a58424c5..fc75ec0a21 100644 --- a/src/systems/thruster/Thruster.cc +++ b/src/systems/thruster/Thruster.cc @@ -19,27 +19,27 @@ #include #include -#include - -#include - -#include - -#include - -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/BatterySoC.hh" -#include "ignition/gazebo/components/BatteryPowerLoad.hh" -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/JointVelocityCmd.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include + +#include + +#include + +#include + +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/BatterySoC.hh" +#include "gz/sim/components/BatteryPowerLoad.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/JointVelocityCmd.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" #include "Thruster.hh" diff --git a/src/systems/thruster/Thruster.hh b/src/systems/thruster/Thruster.hh index e40627d465..f97de16a32 100644 --- a/src/systems/thruster/Thruster.hh +++ b/src/systems/thruster/Thruster.hh @@ -17,7 +17,7 @@ #ifndef IGNITION_GAZEBO_SYSTEMS_THRUSTER_HH_ #define IGNITION_GAZEBO_SYSTEMS_THRUSTER_HH_ -#include +#include #include diff --git a/src/systems/trajectory_follower/TrajectoryFollower.cc b/src/systems/trajectory_follower/TrajectoryFollower.cc index 8366c6065d..403d4d0345 100644 --- a/src/systems/trajectory_follower/TrajectoryFollower.cc +++ b/src/systems/trajectory_follower/TrajectoryFollower.cc @@ -15,28 +15,28 @@ * */ -#include +#include #include #include #include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/AngularVelocityCmd.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/AngularVelocityCmd.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" #include "TrajectoryFollower.hh" diff --git a/src/systems/trajectory_follower/TrajectoryFollower.hh b/src/systems/trajectory_follower/TrajectoryFollower.hh index 57fbfcaae9..9d8adf77a0 100644 --- a/src/systems/trajectory_follower/TrajectoryFollower.hh +++ b/src/systems/trajectory_follower/TrajectoryFollower.hh @@ -17,7 +17,7 @@ #ifndef IGNITION_GAZEBO_SYSTEMS_TRAJECTORYFOLLOWER_HH_ #define IGNITION_GAZEBO_SYSTEMS_TRAJECTORYFOLLOWER_HH_ -#include +#include #include namespace ignition diff --git a/test/integration/ModelPhotoShootTest.hh b/test/integration/ModelPhotoShootTest.hh index 9e3066951a..895c7edad6 100644 --- a/test/integration/ModelPhotoShootTest.hh +++ b/test/integration/ModelPhotoShootTest.hh @@ -27,24 +27,24 @@ #include #include -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/JointType.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" -#include "ignition/gazebo/TestFixture.hh" -#include "ignition/gazebo/rendering/Events.hh" -#include "ignition/gazebo/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/JointType.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" +#include "gz/sim/TestFixture.hh" +#include "gz/sim/rendering/Events.hh" +#include "gz/sim/Model.hh" -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include "helpers/UniqueTestDirectoryEnv.hh" diff --git a/test/integration/actor.cc b/test/integration/actor.cc index 7e874e57f8..6c0c23f324 100644 --- a/test/integration/actor.cc +++ b/test/integration/actor.cc @@ -17,16 +17,16 @@ #include -#include -#include -#include - -#include -#include -#include -#include -#include -#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/actor_trajectory.cc b/test/integration/actor_trajectory.cc index 66b25c6516..44de67fdbd 100644 --- a/test/integration/actor_trajectory.cc +++ b/test/integration/actor_trajectory.cc @@ -21,19 +21,19 @@ #include #include -#include +#include -#include -#include +#include +#include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/EventManager.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/Types.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/EventManager.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/Types.hh" +#include "gz/sim/test_config.hh" -#include "ignition/gazebo/rendering/Events.hh" +#include "gz/sim/rendering/Events.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/buoyancy_engine.cc b/test/integration/buoyancy_engine.cc index 334113eb78..7e8b94ada1 100644 --- a/test/integration/buoyancy_engine.cc +++ b/test/integration/buoyancy_engine.cc @@ -17,19 +17,19 @@ #include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Model.hh" - -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include + +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Model.hh" + +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/camera_sensor_background_from_scene.cc b/test/integration/camera_sensor_background_from_scene.cc index bc9e0259fa..cf7ffe59b1 100644 --- a/test/integration/camera_sensor_background_from_scene.cc +++ b/test/integration/camera_sensor_background_from_scene.cc @@ -19,13 +19,13 @@ #include -#include -#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/deprecated_TEST.cc b/test/integration/deprecated_TEST.cc index a47d16ea3a..06fbb6f904 100644 --- a/test/integration/deprecated_TEST.cc +++ b/test/integration/deprecated_TEST.cc @@ -16,7 +16,7 @@ */ #include -#include +#include ///////////////////////////////////////////////// // Make sure the ignition namespace still works diff --git a/test/integration/distortion_camera.cc b/test/integration/distortion_camera.cc index 279e6d28e7..c2d4ca8c29 100644 --- a/test/integration/distortion_camera.cc +++ b/test/integration/distortion_camera.cc @@ -20,18 +20,18 @@ #ifdef _MSC_VER #pragma warning(push, 0) #endif -#include +#include #ifdef _MSC_VER #pragma warning(pop) #endif -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" -#include -#include -#include -#include -#include +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" +#include +#include +#include +#include +#include #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/entity_system.cc b/test/integration/entity_system.cc index 338cf4e685..ed9f496ed0 100644 --- a/test/integration/entity_system.cc +++ b/test/integration/entity_system.cc @@ -16,18 +16,18 @@ */ #include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include + +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/follow_actor_system.cc b/test/integration/follow_actor_system.cc index a919b970d9..215d0d9388 100644 --- a/test/integration/follow_actor_system.cc +++ b/test/integration/follow_actor_system.cc @@ -16,17 +16,17 @@ */ #include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include + +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/force_torque_system.cc b/test/integration/force_torque_system.cc index 60c57a8b01..a251dfca5a 100644 --- a/test/integration/force_torque_system.cc +++ b/test/integration/force_torque_system.cc @@ -17,18 +17,18 @@ #include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/ForceTorque.hh" - -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include + +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/ForceTorque.hh" + +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "helpers/Relay.hh" #include "helpers/EnvTestFixture.hh" diff --git a/test/integration/fuel_cached_server.cc b/test/integration/fuel_cached_server.cc index 25f0e93377..a356a29ee2 100644 --- a/test/integration/fuel_cached_server.cc +++ b/test/integration/fuel_cached_server.cc @@ -16,10 +16,10 @@ */ #include -#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/ServerConfig.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/ServerConfig.hh" #include "../test/helpers/EnvTestFixture.hh" diff --git a/test/integration/halt_motion.cc b/test/integration/halt_motion.cc index fe8e0d8a92..e2238dd3da 100644 --- a/test/integration/halt_motion.cc +++ b/test/integration/halt_motion.cc @@ -16,19 +16,19 @@ */ #include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/HaltMotion.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include + +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/HaltMotion.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/hydrodynamics.cc b/test/integration/hydrodynamics.cc index 937cae1d95..ece8fe029f 100644 --- a/test/integration/hydrodynamics.cc +++ b/test/integration/hydrodynamics.cc @@ -17,22 +17,22 @@ #include -#include - -#include -#include -#include -#include - -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/TestFixture.hh" -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/World.hh" - -#include "ignition/gazebo/test_config.hh" +#include + +#include +#include +#include +#include + +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/TestFixture.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/World.hh" + +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/test/integration/hydrodynamics_flags.cc b/test/integration/hydrodynamics_flags.cc index a437d402ab..b64b7eb453 100644 --- a/test/integration/hydrodynamics_flags.cc +++ b/test/integration/hydrodynamics_flags.cc @@ -17,22 +17,22 @@ #include -#include - -#include -#include -#include -#include - -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/TestFixture.hh" -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/World.hh" - -#include "ignition/gazebo/test_config.hh" +#include + +#include +#include +#include +#include + +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/TestFixture.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/World.hh" + +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/test/integration/joint.cc b/test/integration/joint.cc index 7247079878..70b03ac134 100644 --- a/test/integration/joint.cc +++ b/test/integration/joint.cc @@ -17,33 +17,33 @@ #include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/joint_trajectory_controller_system.cc b/test/integration/joint_trajectory_controller_system.cc index 160af92aac..5d3e61e04c 100644 --- a/test/integration/joint_trajectory_controller_system.cc +++ b/test/integration/joint_trajectory_controller_system.cc @@ -17,24 +17,24 @@ #include -#include -#include +#include +#include #include -#include -#include -#include -#include +#include +#include +#include +#include -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/JointVelocity.hh" -#include "ignition/gazebo/components/Name.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/JointVelocity.hh" +#include "gz/sim/components/Name.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/light.cc b/test/integration/light.cc index abc20be990..6cd8c1ff37 100644 --- a/test/integration/light.cc +++ b/test/integration/light.cc @@ -17,27 +17,27 @@ #include -#include +#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/logical_audio_sensor_plugin.cc b/test/integration/logical_audio_sensor_plugin.cc index e4450358c8..4d6201a609 100644 --- a/test/integration/logical_audio_sensor_plugin.cc +++ b/test/integration/logical_audio_sensor_plugin.cc @@ -26,7 +26,7 @@ #include #include #include -#include +#include #include #include diff --git a/test/integration/model_photo_shoot_default_joints.cc b/test/integration/model_photo_shoot_default_joints.cc index 620bf42e8a..6c18c24797 100644 --- a/test/integration/model_photo_shoot_default_joints.cc +++ b/test/integration/model_photo_shoot_default_joints.cc @@ -17,7 +17,7 @@ #include "ModelPhotoShootTest.hh" -#include +#include // Test the Model Photo Shoot plugin on the example world. TEST_F(ModelPhotoShootTest, diff --git a/test/integration/model_photo_shoot_random_joints.cc b/test/integration/model_photo_shoot_random_joints.cc index 21cabd9681..782e84a9f9 100644 --- a/test/integration/model_photo_shoot_random_joints.cc +++ b/test/integration/model_photo_shoot_random_joints.cc @@ -17,7 +17,7 @@ #include "ModelPhotoShootTest.hh" -#include +#include // Test the Model Photo Shoot plugin on the example world. TEST_F(ModelPhotoShootTest, diff --git a/test/integration/multicopter.cc b/test/integration/multicopter.cc index ba8ab1b53e..0ae09e1bf3 100644 --- a/test/integration/multicopter.cc +++ b/test/integration/multicopter.cc @@ -20,7 +20,7 @@ #include -#include +#include #include #include diff --git a/test/integration/multiple_servers.cc b/test/integration/multiple_servers.cc index 519ee43313..b80cde5a36 100644 --- a/test/integration/multiple_servers.cc +++ b/test/integration/multiple_servers.cc @@ -17,10 +17,10 @@ #include -#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/ServerConfig.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/ServerConfig.hh" #include "../test/helpers/EnvTestFixture.hh" diff --git a/test/integration/navsat_system.cc b/test/integration/navsat_system.cc index 38ae04c867..921d81b182 100644 --- a/test/integration/navsat_system.cc +++ b/test/integration/navsat_system.cc @@ -17,24 +17,24 @@ #include -#include +#include #include -#include -#include -#include -#include - -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/NavSat.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/TestFixture.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include + +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/NavSat.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/TestFixture.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/nested_model_physics.cc b/test/integration/nested_model_physics.cc index f3eeb33e02..51380e03d4 100644 --- a/test/integration/nested_model_physics.cc +++ b/test/integration/nested_model_physics.cc @@ -16,19 +16,19 @@ */ #include -#include -#include -#include - -#include "ignition/math/Pose3.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Model.hh" - -#include "ignition/gazebo/test_config.hh" +#include +#include +#include + +#include "gz/math/Pose3.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Model.hh" + +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/odometry_publisher.cc b/test/integration/odometry_publisher.cc index 52e2eb0891..9006eec1a7 100644 --- a/test/integration/odometry_publisher.cc +++ b/test/integration/odometry_publisher.cc @@ -16,22 +16,22 @@ */ #include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/AngularVelocityCmd.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/LinearVelocityCmd.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include + +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/AngularVelocityCmd.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/LinearVelocityCmd.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/optical_tactile_plugin.cc b/test/integration/optical_tactile_plugin.cc index 76fb2e4571..d580ed3ce4 100644 --- a/test/integration/optical_tactile_plugin.cc +++ b/test/integration/optical_tactile_plugin.cc @@ -17,19 +17,19 @@ #include -#include +#include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/particle_emitter.cc b/test/integration/particle_emitter.cc index 40bb5308d1..329a64cebd 100644 --- a/test/integration/particle_emitter.cc +++ b/test/integration/particle_emitter.cc @@ -19,19 +19,19 @@ #include -#include - -#include -#include -#include - -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParticleEmitter.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/test_config.hh" +#include + +#include +#include +#include + +#include "gz/sim/Entity.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParticleEmitter.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/test_config.hh" #include "helpers/EnvTestFixture.hh" #include "helpers/Relay.hh" diff --git a/test/integration/particle_emitter2.cc b/test/integration/particle_emitter2.cc index 4d71f3349a..7d3bff2590 100644 --- a/test/integration/particle_emitter2.cc +++ b/test/integration/particle_emitter2.cc @@ -19,18 +19,18 @@ #include -#include -#include -#include -#include - -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParticleEmitter.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include + +#include "gz/sim/Entity.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParticleEmitter.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/test_config.hh" #include "helpers/EnvTestFixture.hh" #include "helpers/Relay.hh" diff --git a/test/integration/perfect_comms.cc b/test/integration/perfect_comms.cc index 56c77957c8..9d846e260d 100644 --- a/test/integration/perfect_comms.cc +++ b/test/integration/perfect_comms.cc @@ -21,11 +21,11 @@ #include #include -#include -#include -#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include +#include +#include +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/test/integration/play_pause.cc b/test/integration/play_pause.cc index 1ce1a37197..844bcfb9e1 100644 --- a/test/integration/play_pause.cc +++ b/test/integration/play_pause.cc @@ -19,7 +19,7 @@ #include #include -#include "ignition/msgs.hh" +#include "gz/msgs.hh" #include "gz/transport.hh" #include "gz/sim/Server.hh" #include "gz/sim/test_config.hh" // NOLINT(build/include) diff --git a/test/integration/recreate_entities.cc b/test/integration/recreate_entities.cc index 97ab6eb9f2..9c493b1723 100644 --- a/test/integration/recreate_entities.cc +++ b/test/integration/recreate_entities.cc @@ -20,24 +20,24 @@ #include #include -#include -#include -#include +#include +#include +#include #include -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/ParentLinkName.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Recreate.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/ParentLinkName.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Recreate.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/rf_comms.cc b/test/integration/rf_comms.cc index aa64733de1..9d70109395 100644 --- a/test/integration/rf_comms.cc +++ b/test/integration/rf_comms.cc @@ -21,12 +21,12 @@ #include #include -#include -#include -#include -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include +#include +#include +#include "gz/sim/Model.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/test/integration/sensor.cc b/test/integration/sensor.cc index 7536e00d27..e0bea88580 100644 --- a/test/integration/sensor.cc +++ b/test/integration/sensor.cc @@ -17,18 +17,18 @@ #include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/sensors_system_battery.cc b/test/integration/sensors_system_battery.cc index b7b65c0e11..19631fff7e 100644 --- a/test/integration/sensors_system_battery.cc +++ b/test/integration/sensors_system_battery.cc @@ -21,17 +21,17 @@ #include -#include -#include +#include +#include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/Types.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/Types.hh" +#include "gz/sim/test_config.hh" -#include "ignition/gazebo/components/BatterySoC.hh" -#include "ignition/gazebo/components/Name.hh" +#include "gz/sim/components/BatterySoC.hh" +#include "gz/sim/components/Name.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/shader_param_system.cc b/test/integration/shader_param_system.cc index 906133e937..8952203ac6 100644 --- a/test/integration/shader_param_system.cc +++ b/test/integration/shader_param_system.cc @@ -17,15 +17,15 @@ #include -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/spherical_coordinates.cc b/test/integration/spherical_coordinates.cc index 6f50f269bd..466019b889 100644 --- a/test/integration/spherical_coordinates.cc +++ b/test/integration/spherical_coordinates.cc @@ -16,21 +16,21 @@ */ #include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/TestFixture.hh" -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/World.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/SphericalCoordinates.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include + +#include "gz/sim/TestFixture.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/World.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/SphericalCoordinates.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/thermal_sensor_system.cc b/test/integration/thermal_sensor_system.cc index 8013bee829..1fb4d7ac0f 100644 --- a/test/integration/thermal_sensor_system.cc +++ b/test/integration/thermal_sensor_system.cc @@ -20,20 +20,20 @@ #include #include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Temperature.hh" -#include "ignition/gazebo/components/TemperatureRange.hh" -#include "ignition/gazebo/components/ThermalCamera.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include + +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Temperature.hh" +#include "gz/sim/components/TemperatureRange.hh" +#include "gz/sim/components/ThermalCamera.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/thruster.cc b/test/integration/thruster.cc index b6b0e589f1..023978f424 100644 --- a/test/integration/thruster.cc +++ b/test/integration/thruster.cc @@ -17,26 +17,26 @@ #include -#include - -#include -#include -#include -#include -#include - -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/TestFixture.hh" -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/World.hh" - -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/Pose.hh" - -#include "ignition/gazebo/test_config.hh" +#include + +#include +#include +#include +#include +#include + +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/TestFixture.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/World.hh" + +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/Pose.hh" + +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/test/integration/triggered_camera.cc b/test/integration/triggered_camera.cc index 6f36f37c6b..45b2fb0f74 100644 --- a/test/integration/triggered_camera.cc +++ b/test/integration/triggered_camera.cc @@ -20,20 +20,20 @@ #ifdef _MSC_VER #pragma warning(push, 0) #endif -#include +#include #ifdef _MSC_VER #pragma warning(pop) #endif -#include "ignition/gazebo/rendering/Events.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" -#include -#include -#include -#include -#include +#include "gz/sim/rendering/Events.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" +#include +#include +#include +#include +#include #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/world_control_state.cc b/test/integration/world_control_state.cc index 92bebfb68c..c3e7399f48 100644 --- a/test/integration/world_control_state.cc +++ b/test/integration/world_control_state.cc @@ -17,15 +17,15 @@ #include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/performance/sdf_runner.cc b/test/performance/sdf_runner.cc index 9cbbab1300..11725b95f1 100644 --- a/test/performance/sdf_runner.cc +++ b/test/performance/sdf_runner.cc @@ -17,7 +17,7 @@ #include -#include +#include #include #include diff --git a/test/plugins/TestVisualSystem.cc b/test/plugins/TestVisualSystem.cc index 9cc3741117..129c739e6f 100644 --- a/test/plugins/TestVisualSystem.cc +++ b/test/plugins/TestVisualSystem.cc @@ -16,7 +16,7 @@ */ #include "TestVisualSystem.hh" -#include +#include IGNITION_ADD_PLUGIN(ignition::gazebo::TestVisualSystem, ignition::gazebo::System, diff --git a/test/plugins/TestVisualSystem.hh b/test/plugins/TestVisualSystem.hh index e8cdf4a45f..dd751292d9 100644 --- a/test/plugins/TestVisualSystem.hh +++ b/test/plugins/TestVisualSystem.hh @@ -17,11 +17,11 @@ #ifndef IGNITION_GAZEBO_TEST_TESTVISUALSYSTEM_HH_ #define IGNITION_GAZEBO_TEST_TESTVISUALSYSTEM_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { From aee9f0d99abb9c0631bdea8f6e1b641da386fb99 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 24 May 2023 20:05:42 +0000 Subject: [PATCH 4/5] Fixed header redirects Signed-off-by: Nate Koenig --- include/ignition/gazebo/Actor.hh | 146 +-------- include/ignition/gazebo/Joint.hh | 269 +---------------- include/ignition/gazebo/Light.hh | 276 +----------------- include/ignition/gazebo/Primitives.hh | 68 +---- include/ignition/gazebo/Sensor.hh | 100 +------ include/ignition/gazebo/comms/Broker.hh | 141 +-------- include/ignition/gazebo/comms/ICommsModel.hh | 122 +------- include/ignition/gazebo/comms/MsgManager.hh | 146 +-------- .../gazebo/components/BatteryPowerLoad.hh | 39 +-- .../gazebo/components/BoundingBoxCamera.hh | 32 +- .../gazebo/components/CustomSensor.hh | 32 +- .../ignition/gazebo/components/ForceTorque.hh | 34 +-- .../ignition/gazebo/components/HaltMotion.hh | 25 +- .../components/JointTransmittedWrench.hh | 41 +-- .../ignition/gazebo/components/LightCmd.hh | 33 +-- .../ignition/gazebo/components/LightType.hh | 33 +-- include/ignition/gazebo/components/NavSat.hh | 33 +-- .../gazebo/components/ParticleEmitter.hh | 39 +-- .../ignition/gazebo/components/Recreate.hh | 35 +-- .../components/RenderEngineServerHeadless.hh | 32 +- .../gazebo/components/SegmentationCamera.hh | 32 +- .../gazebo/components/SemanticLabel.hh | 30 +- .../gazebo/components/SphericalCoordinates.hh | 40 +-- .../gazebo/components/SystemPluginInfo.hh | 34 +-- .../gazebo/components/TemperatureRange.hh | 86 +----- .../ignition/gazebo/components/Visibility.hh | 35 +-- .../ignition/gazebo/components/VisualCmd.hh | 33 +-- .../gazebo/components/WheelSlipCmd.hh | 31 +- 28 files changed, 74 insertions(+), 1923 deletions(-) diff --git a/include/ignition/gazebo/Actor.hh b/include/ignition/gazebo/Actor.hh index 50460891a0..a8bd091180 100644 --- a/include/ignition/gazebo/Actor.hh +++ b/include/ignition/gazebo/Actor.hh @@ -14,148 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_ACTOR_HH_ -#define IGNITION_GAZEBO_ACTOR_HH_ -#include -#include -#include - -#include - -#include - -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // - /// \class Actor Actor.hh ignition/gazebo/Actor.hh - /// \brief This class provides wrappers around entities and components - /// which are more convenient and straight-forward to use than dealing - /// with the `EntityComponentManager` directly. - /// All the functions provided here are meant to be used with a actor - /// entity. - /// - /// For example, given an actor's entity, find the value of its - /// name component, one could use the entity-component manager (`ecm`) - /// directly as follows: - /// - /// std::string name = ecm.Component(entity)->Data(); - /// - /// Using this class however, the same information can be obtained with - /// a simpler function call: - /// - /// Actor actor(entity); - /// std::string name = actor.Name(ecm); - /// - class IGNITION_GAZEBO_VISIBLE Actor - { - /// \brief Constructor - /// \param[in] _entity Actor entity - public: explicit Actor(gazebo::Entity _entity = kNullEntity); - - /// \brief Get the entity which this Actor is related to. - /// \return Actor entity. - public: gazebo::Entity Entity() const; - - /// \brief Reset Entity to a new one - /// \param[in] _newEntity New actor entity. - public: void ResetEntity(gazebo::Entity _newEntity); - - /// \brief Check whether this actor correctly refers to an entity that - /// has a components::Actor. - /// \param[in] _ecm Entity-component manager. - /// \return True if it's a valid actor in the manager. - public: bool Valid(const EntityComponentManager &_ecm) const; - - /// \brief Get the actor's unscoped name. - /// \param[in] _ecm Entity-component manager. - /// \return Actor's name or nullopt if the entity does not have a - /// components::Name component - public: std::optional Name( - const EntityComponentManager &_ecm) const; - - /// \brief Get the pose of the actor. - /// If the actor has a trajectory, this will only return the origin - /// pose of the trajectory and not the actual world pose of the actor. - /// \param[in] _ecm Entity-component manager. - /// \return Pose of the actor or nullopt if the entity does not - /// have a components::Pose component. - /// \sa WorldPose - public: std::optional Pose( - const EntityComponentManager &_ecm) const; - - /// \brief Get the trajectory pose of the actor. There are two - /// ways that the actor can follow a trajectory: 1) SDF script, - /// 2) manually setting trajectory pose. This function retrieves 2) the - /// manual trajectory pose set by the user. The Trajectory pose is - /// given relative to the trajectory pose origin returned by Pose(). - /// \param[in] _ecm Entity Component manager. - /// \return Trajectory pose of the actor w.r.t. to trajectory origin. - /// \sa Pose - public: std::optional TrajectoryPose( - const EntityComponentManager &_ecm) const; - - /// \brief Set the trajectory pose of the actor. There are two - /// ways that the actor can follow a trajectory: 1) SDF script, - /// 2) manually setting trajectory pose. This function enables option 2). - /// Manually setting the trajectory pose will override the scripted - /// trajectory specified in SDF. - /// \param[in] _ecm Entity Component manager. - /// \param[in] _name Trajectory pose w.r.t. to the trajectory origin - /// \sa Pose - public: void SetTrajectoryPose(EntityComponentManager &_ecm, - const math::Pose3d &_pose); - - /// \brief Get the world pose of the actor. - /// This returns the current world pose of the actor computed by gazebo. - /// The world pose is the combination of the actor's pose and its - /// trajectory pose. The currently trajectory pose is either manually set - /// via SetTrajectoryPose or interpolated from waypoints in the SDF script - /// based on the current time. - /// \param[in] _ecm Entity-component manager. - /// \return World pose of the actor or nullopt if the entity does not - /// have a components::WorldPose component. - /// \sa Pose - public: std::optional WorldPose( - const EntityComponentManager &_ecm) const; - - /// \brief Set the name of animation to use for this actor. - /// \param[in] _ecm Entity Component manager. - /// \param[in] _name Animation name - public: void SetAnimationName(EntityComponentManager &_ecm, - const std::string &_name); - - /// \brief Set the time of animation for this actor. - /// \param[in] _ecm Entity Component manager. - /// \param[in] _time Animation time - public: void SetAnimationTime(EntityComponentManager &_ecm, - const std::chrono::steady_clock::duration &_time); - - /// \brief Get the name of animation used by the actor - /// \param[in] _ecm Entity-component manager. - /// \return Animation name - public: std::optional AnimationName( - const EntityComponentManager &_ecm) const; - - /// \brief Get the time of animation for this actor - /// \param[in] _ecm Entity-component manager. - /// \return Animation time - public: std::optional AnimationTime( - const EntityComponentManager &_ecm) const; - - /// \brief Private data pointer. - IGN_UTILS_IMPL_PTR(dataPtr) - }; - } - } -} -#endif +#include +#include diff --git a/include/ignition/gazebo/Joint.hh b/include/ignition/gazebo/Joint.hh index e8b8ab31f3..8b4269d202 100644 --- a/include/ignition/gazebo/Joint.hh +++ b/include/ignition/gazebo/Joint.hh @@ -14,271 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_JOINT_HH_ -#define IGNITION_GAZEBO_JOINT_HH_ -#include -#include -#include -#include - -#include -#include - -#include -#include -#include - -#include -#include - -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Types.hh" - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // - /// \class Joint Joint.hh ignition/gazebo/Joint.hh - /// \brief This class provides wrappers around entities and components - /// which are more convenient and straight-forward to use than dealing - /// with the `EntityComponentManager` directly. - /// All the functions provided here are meant to be used with a joint - /// entity. - /// - /// For example, given a joint's entity, find the value of its - /// name component, one could use the entity-component manager (`ecm`) - /// directly as follows: - /// - /// std::string name = ecm.Component(entity)->Data(); - /// - /// Using this class however, the same information can be obtained with - /// a simpler function call: - /// - /// Joint joint(entity); - /// std::string name = joint.Name(ecm); - /// - class IGNITION_GAZEBO_VISIBLE Joint - { - /// \brief Constructor - /// \param[in] _entity Joint entity - public: explicit Joint(gazebo::Entity _entity = kNullEntity); - - /// \brief Get the entity which this Joint is related to. - /// \return Joint entity. - public: gazebo::Entity Entity() const; - - /// \brief Reset Entity to a new one - /// \param[in] _newEntity New joint entity. - public: void ResetEntity(gazebo::Entity _newEntity); - - /// \brief Check whether this joint correctly refers to an entity that - /// has a components::Joint. - /// \param[in] _ecm Entity-component manager. - /// \return True if it's a valid joint in the manager. - public: bool Valid(const EntityComponentManager &_ecm) const; - - /// \brief Get the joint's unscoped name. - /// \param[in] _ecm Entity-component manager. - /// \return Joint's name or nullopt if the entity does not have a - /// components::Name component - public: std::optional Name( - const EntityComponentManager &_ecm) const; - - /// \brief Get the parent link name - /// \param[in] _ecm Entity-component manager. - /// \return Parent link name or nullopt if the entity does not have a - /// components::ParentLinkName component. - public: std::optional ParentLinkName( - const EntityComponentManager &_ecm) const; - - /// \brief Get the child link name - /// \param[in] _ecm Entity-component manager. - /// \return Child link name or nullopt if the entity does not have a - /// components::ChildLinkName component. - public: std::optional ChildLinkName( - const EntityComponentManager &_ecm) const; - - /// \brief Get the pose of the joint - /// \param[in] _ecm Entity-component manager. - /// \return Pose of the joint or nullopt if the entity does not - /// have a components::Pose component. - public: std::optional Pose( - const EntityComponentManager &_ecm) const; - - /// \brief Get the thread pitch of the joint - /// \param[in] _ecm Entity-component manager. - /// \return Thread pitch of the joint or nullopt if the entity does not - /// have a components::ThreadPitch component. - public: std::optional ThreadPitch( - const EntityComponentManager &_ecm) const; - - /// \brief Get the joint axis - /// \param[in] _ecm Entity-component manager. - /// \return Axis of the joint or nullopt if the entity does not - /// have a components::JointAxis or components::JointAxis2 component. - public: std::optional> Axis( - const EntityComponentManager &_ecm) const; - - /// \brief Get the joint type - /// \param[in] _ecm Entity-component manager. - /// \return Type of the joint or nullopt if the entity does not - /// have a components::JointType component. - public: std::optional Type( - const EntityComponentManager &_ecm) const; - - /// \brief Get the ID of a sensor entity which is an immediate child of - /// this joint. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _name Sensor name. - /// \return Sensor entity. - public: gazebo::Entity SensorByName(const EntityComponentManager &_ecm, - const std::string &_name) const; - - /// \brief Get all sensors which are immediate children of this joint. - /// \param[in] _ecm Entity-component manager. - /// \return All sensors in this joint. - public: std::vector Sensors( - const EntityComponentManager &_ecm) const; - - /// \brief Get the number of sensors which are immediate children of this - /// joint. - /// \param[in] _ecm Entity-component manager. - /// \return Number of sensors in this joint. - public: uint64_t SensorCount(const EntityComponentManager &_ecm) const; - - /// \brief Set velocity on this joint. Only applied if no forces are set - /// \param[in] _ecm Entity Component manager. - /// \param[in] _velocities Joint velocities commands (target velocities). - /// This is different from ResetVelocity in that this does not modify the - /// internal state of the joint. Instead, the physics engine is expected - /// to compute the necessary joint torque for the commanded velocity and - /// apply it in the next simulation step. The vector of velocities should - /// have the same size as the degrees of freedom of the joint. - public: void SetVelocity(EntityComponentManager &_ecm, - const std::vector &_velocities); - - /// \brief Set force on this joint. If both forces and velocities are set, - /// only forces are applied - /// \param[in] _ecm Entity Component manager. - /// \param[in] _forces Joint force or torque commands (target forces - /// or toruqes). The vector of forces should have the same size as the - /// degrees of freedom of the joint. - public: void SetForce(EntityComponentManager &_ecm, - const std::vector &_forces); - - /// \brief Set the velocity limits on a joint axis. - /// \param[in] _ecm Entity Component manager. - /// \param[in] _limits Joint limits to set to. The X() component of the - /// Vector2 specifies the minimum velocity limit, the Y() component stands - /// for maximum limit. The vector of limits should have the same size as - /// the degrees of freedom of the joint. - public: void SetVelocityLimits(EntityComponentManager &_ecm, - const std::vector &_limits); - - /// \brief Set the effort limits on a joint axis. - /// \param[in] _ecm Entity Component manager. - /// \param[in] _limits Joint limits to set to. The X() component of the - /// Vector2 specifies the minimum effort limit, the Y() component stands - /// for maximum limit. The vector of limits should have the same size as - /// the degrees of freedom of the joint. - public: void SetEffortLimits(EntityComponentManager &_ecm, - const std::vector &_limits); - - /// \brief Set the position limits on a joint axis. - /// \param[in] _ecm Entity Component manager. - /// \param[in] _limits Joint limits to set to. The X() component of the - /// Vector2 specifies the minimum position limit, the Y() component stands - /// for maximum limit. The vector of limits should have the same size as - /// the degrees of freedom of the joint. - public: void SetPositionLimits(EntityComponentManager &_ecm, - const std::vector &_limits); - - /// \brief Reset the joint positions - /// \param[in] _ecm Entity Component manager. - /// \param[in] _positions Joint positions to reset to. - /// The vector of positions should have the same size as the degrees of - /// freedom of the joint. - public: void ResetPosition(EntityComponentManager &_ecm, - const std::vector &_positions); - - /// \brief Reset the joint velocities - /// \param[in] _ecm Entity Component manager. - /// \param[in] _velocities Joint velocities to reset to. This is different - /// from SetVelocity as this modifies the internal state of the joint. - /// The vector of velocities should have the same size as the degrees of - /// freedom of the joint. - public: void ResetVelocity(EntityComponentManager &_ecm, - const std::vector &_velocities); - - /// \brief By default, Gazebo will not report velocities for a joint, so - /// functions like `Velocity` will return nullopt. This - /// function can be used to enable joint velocity check. - /// \param[in] _ecm Mutable reference to the ECM. - /// \param[in] _enable True to enable checks, false to disable. Defaults - /// to true. - public: void EnableVelocityCheck(EntityComponentManager &_ecm, - bool _enable = true) const; - - /// \brief By default, Gazebo will not report positions for a joint, so - /// functions like `Position` will return nullopt. This - /// function can be used to enable joint position check. - /// \param[in] _ecm Mutable reference to the ECM. - /// \param[in] _enable True to enable checks, false to disable. Defaults - /// to true. - public: void EnablePositionCheck(EntityComponentManager &_ecm, - bool _enable = true) const; - - /// \brief By default, Gazebo will not report transmitted wrench for a - /// joint, so functions like `TransmittedWrench` will return nullopt. This - /// function can be used to enable joint transmitted wrench check. - /// \param[in] _ecm Mutable reference to the ECM. - /// \param[in] _enable True to enable checks, false to disable. Defaults - /// to true. - public: void EnableTransmittedWrenchCheck(EntityComponentManager &_ecm, - bool _enable = true) const; - - /// \brief Get the velocity of the joint - /// \param[in] _ecm Entity-component manager. - /// \return Velocity of the joint or nullopt if velocity check - /// is not enabled. - /// \sa EnableVelocityCheck - public: std::optional> Velocity( - const EntityComponentManager &_ecm) const; - - /// \brief Get the position of the joint - /// \param[in] _ecm Entity-component manager. - /// \return Position of the joint or nullopt if position check - /// is not enabled. - /// \sa EnablePositionCheck - public: std::optional> Position( - const EntityComponentManager &_ecm) const; - - /// \brief Get the transmitted wrench of the joint - /// \param[in] _ecm Entity-component manager. - /// \return Transmitted wrench of the joint or nullopt if transmitted - /// wrench check is not enabled. - /// \sa EnableTransmittedWrenchCheck - public: std::optional> TransmittedWrench( - const EntityComponentManager &_ecm) const; - - /// \brief Get the parent model - /// \param[in] _ecm Entity-component manager. - /// \return Parent Model or nullopt if the entity does not have a - /// components::ParentEntity component. - public: std::optional ParentModel( - const EntityComponentManager &_ecm) const; - - /// \brief Private data pointer. - IGN_UTILS_IMPL_PTR(dataPtr) - }; - } - } -} -#endif +#include +#include diff --git a/include/ignition/gazebo/Light.hh b/include/ignition/gazebo/Light.hh index f3680991dd..087d73bc21 100644 --- a/include/ignition/gazebo/Light.hh +++ b/include/ignition/gazebo/Light.hh @@ -14,278 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_LIGHT_HH_ -#define IGNITION_GAZEBO_LIGHT_HH_ -#include -#include -#include -#include - -#include - -#include -#include -#include -#include - -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // - /// \class Light Light.hh ignition/gazebo/Light.hh - /// \brief This class provides wrappers around entities and components - /// which are more convenient and straight-forward to use than dealing - /// with the `EntityComponentManager` directly. - /// All the functions provided here are meant to be used with a light - /// entity. - /// - /// For example, given a light's entity, find the value of its - /// name component, one could use the entity-component manager (`ecm`) - /// directly as follows: - /// - /// std::string name = ecm.Component(entity)->Data(); - /// - /// Using this class however, the same information can be obtained with - /// a simpler function call: - /// - /// Light light(entity); - /// std::string name = light.Name(ecm); - /// - class IGNITION_GAZEBO_VISIBLE Light - { - /// \brief Constructor - /// \param[in] _entity Light entity - public: explicit Light(gazebo::Entity _entity = kNullEntity); - - /// \brief Get the entity which this Light is related to. - /// \return Light entity. - public: gazebo::Entity Entity() const; - - /// \brief Reset Entity to a new one - /// \param[in] _newEntity New light entity. - public: void ResetEntity(gazebo::Entity _newEntity); - - /// \brief Check whether this light correctly refers to an entity that - /// has a components::Light. - /// \param[in] _ecm Entity-component manager. - /// \return True if it's a valid light in the manager. - public: bool Valid(const EntityComponentManager &_ecm) const; - - /// \brief Get the light's unscoped name. - /// \param[in] _ecm Entity-component manager. - /// \return Light's name or nullopt if the entity does not have a - /// components::Name component - public: std::optional Name( - const EntityComponentManager &_ecm) const; - - /// \brief Get the pose of the light. - /// The pose is given w.r.t the light's parent. which can be a world or - /// a link. - /// \param[in] _ecm Entity-component manager. - /// \return Pose of the light or nullopt if the entity does not - /// have a components::Pose component. - public: std::optional Pose( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light type - /// \param[in] _ecm Entity-component manager. - /// \return Type of the light or nullopt if the entity does not - /// have a components::LightType component. - public: std::optional Type( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light diffuse color - /// \param[in] _ecm Entity-component manager. - /// \return Diffuse color of the light or nullopt if the entity does not - /// have a components::Light component. - public: std::optional DiffuseColor( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light specular color - /// \param[in] _ecm Entity-component manager. - /// \return Specular color of the light or nullopt if the entity does not - /// have a components::Light component. - public: std::optional SpecularColor( - const EntityComponentManager &_ecm) const; - - /// \brief Get whether the light casts shadows - /// \param[in] _ecm Entity-component manager. - /// \return Cast shadow bool value of light or nullopt if the entity does - /// not have a components::CastShadows component. - public: std::optional CastShadows( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light intensity. - /// \param[in] _ecm Entity-component manager. - /// \return Intensity of light or nullopt if the entity does not - /// have a components::Light component. - public: std::optional Intensity( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light direction. - /// \param[in] _ecm Entity-component manager. - /// \return Direction of light or nullopt if the entity does not - /// have a components::Light component. - public: std::optional Direction( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light attenuation range. - /// Light attenuation is not applicable to directional lights. - /// \param[in] _ecm Entity-component manager. - /// \return Attenuation range of light or nullopt if the entity does not - /// have a components::Light component. - public: std::optional AttenuationRange( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light attenuation constant value. - /// Light attenuation is not applicable to directional lights. - /// \param[in] _ecm Entity-component manager. - /// \return Attenuation constant value of light or nullopt if the entity - /// does not have a components::Light component. - public: std::optional AttenuationConstant( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light attenuation linear value. - /// Light attenuation is not applicable to directional lights. - /// \param[in] _ecm Entity-component manager. - /// \return Attenuation linear value of light or nullopt if the entity - /// does not have a components::Light component. - public: std::optional AttenuationLinear( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light attenuation quadratic value. - /// Light attenuation is not applicable to directional lights. - /// \param[in] _ecm Entity-component manager. - /// \return Attenuation quadratic value of light or nullopt if the entity - /// does not have a components::Light component. - public: std::optional AttenuationQuadratic( - const EntityComponentManager &_ecm) const; - - /// \brief Get the inner angle of light. Applies to spot lights only. - /// \param[in] _ecm Entity-component manager. - /// \return Inner angle of spot light or nullopt if the entity - /// does not have a components::Light component. - public: std::optional SpotInnerAngle( - const EntityComponentManager &_ecm) const; - - /// \brief Get the outer angle of light. Applies to spot lights only. - /// \param[in] _ecm Entity-component manager. - /// \return Outer angle of spot light or nullopt if the entity - /// does not have a components::Light component. - public: std::optional SpotOuterAngle( - const EntityComponentManager &_ecm) const; - - /// \brief Get the fall off value of light. Applies to spot lights only. - /// \param[in] _ecm Entity-component manager. - /// \return Fall off value of spot light or nullopt if the entity - /// does not have a components::Light component. - public: std::optional SpotFalloff( - const EntityComponentManager &_ecm) const; - - /// \brief Set the pose of this light. - /// \param[in] _ecm Entity-component manager. - /// Pose is set w.r.t. the light's parent which can be a world or a link. - /// \param[in] _pose Pose to set the light to. - public: void SetPose(EntityComponentManager &_ecm, - const math::Pose3d &_pose); - - /// \brief Set the diffuse color of this light. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _color Diffuse color to set the light to - public: void SetDiffuseColor(EntityComponentManager &_ecm, - const math::Color &_color); - - /// \brief Set the specular color of this light. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _color Specular color to set the light to - public: void SetSpecularColor(EntityComponentManager &_ecm, - const math::Color &_color); - - /// \brief Set whether the light casts shadows. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _bool True to cast shadows, false to not cast shadows. - public: void SetCastShadows(EntityComponentManager &_ecm, - bool _castShadows); - - /// \brief Set light intensity. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _value Intensity value - public: void SetIntensity(EntityComponentManager &_ecm, - double _value); - - /// \brief Set light direction. Applies to directional lights - /// \param[in] _ecm Entity-component manager. - /// and spot lights only. - /// \param[in] _dir Direction to set - public: void SetDirection(EntityComponentManager &_ecm, - const math::Vector3d &_dir); - - /// \brief Set attenuation range of this light. - /// \param[in] _ecm Entity-component manager. - /// Light attenuation is not applicable to directional lights. - /// \param[in] _bool True to cast shadows, false to not cast shadows. - public: void SetAttenuationRange(EntityComponentManager &_ecm, - double _range); - - /// \brief Set attenuation constant value of this light. - /// \param[in] _ecm Entity-component manager. - /// Light attenuation is not applicable to directional lights. - /// \param[in] _value Attenuation constant value to set - public: void SetAttenuationConstant(EntityComponentManager &_ecm, - double _value); - - /// \brief Set attenuation linear value of this light. - /// \param[in] _ecm Entity-component manager. - /// Light attenuation is not applicable to directional lights. - /// \param[in] _value Attenuation linear value to set - public: void SetAttenuationLinear(EntityComponentManager &_ecm, - double _value); - - /// \brief Set attenuation quadratic value of this light. - /// \param[in] _ecm Entity-component manager. - /// Light attenuation is not applicable to directional lights. - /// \param[in] _value Attenuation quadratic value to set - public: void SetAttenuationQuadratic(EntityComponentManager &_ecm, - double _value); - - /// \brief Set inner angle for this light. Applies to spot lights only. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _angle Angle to set. - public: void SetSpotInnerAngle(EntityComponentManager &_ecm, - const math::Angle &_angle); - - /// \brief Set outer angle for this light. Applies to spot lights only. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _angle Angle to set. - public: void SetSpotOuterAngle(EntityComponentManager &_ecm, - const math::Angle &_angle); - - /// \brief Set fall off value for this light. Applies to spot lights only. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _fallOff Fall off value - public: void SetSpotFalloff(EntityComponentManager &_ecm, - double _falloff); - - /// \brief Get the parent entity. This can be a world or a link. - /// \param[in] _ecm Entity-component manager. - /// \return Parent entity or nullopt if the entity does not have a - /// components::ParentEntity component. - public: std::optional Parent( - const EntityComponentManager &_ecm) const; - - /// \brief Private data pointer. - IGN_UTILS_IMPL_PTR(dataPtr) - }; - } - } -} -#endif +#include +#include diff --git a/include/ignition/gazebo/Primitives.hh b/include/ignition/gazebo/Primitives.hh index eff9a97b83..41c74f8880 100644 --- a/include/ignition/gazebo/Primitives.hh +++ b/include/ignition/gazebo/Primitives.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -15,69 +15,5 @@ * */ -#ifndef IGNITION_GAZEBO_PRIMITIVES_HH_ -#define IGNITION_GAZEBO_PRIMITIVES_HH_ - +#include #include -#include - -#include - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - - /// \brief Enumeration of available primitive shape types - enum class IGNITION_GAZEBO_VISIBLE PrimitiveShape - { - kBox, - kCapsule, - kCylinder, - kEllipsoid, - kSphere, - }; - - /// \brief Enumeration of available primitive light types - enum class IGNITION_GAZEBO_VISIBLE PrimitiveLight - { - kDirectional, - kPoint, - kSpot, - }; - - /// \brief Return an SDF string of one of the available primitive - /// shape types - /// \param[in] _type Type of shape to retrieve - /// \return String containing SDF description of primitive shape - /// Empty string if the _type is not supported. - std::string IGNITION_GAZEBO_VISIBLE - getPrimitiveShape(const PrimitiveShape &_type); - - /// \brief Return an SDF string of one of the available primitive - /// light types - /// \param[in] _type Type of light to retrieve - /// \return String containing SDF description of primitive light - /// Empty string if the _type is not supported. - std::string IGNITION_GAZEBO_VISIBLE - getPrimitiveLight(const PrimitiveLight &_type); - - /// \brief Return an SDF string of one of the available primitive shape or - /// light types. - /// \param[in] _typeName Type name of the of shape or light to retrieve. - /// Must be one of: box, sphere, cylinder, capsule, ellipsoid, directional, - /// point, or spot. - /// \return String containing SDF description of primitive shape or light. - /// Empty string if the _typeName is invalid. - std::string IGNITION_GAZEBO_VISIBLE - getPrimitive(const std::string &_typeName); - } - } // namespace gazebo -} // namespace ignition - - -#endif // IGNITION_GAZEBO_PRIMITIVES_HH_ - - diff --git a/include/ignition/gazebo/Sensor.hh b/include/ignition/gazebo/Sensor.hh index af677f252b..e6325f0464 100644 --- a/include/ignition/gazebo/Sensor.hh +++ b/include/ignition/gazebo/Sensor.hh @@ -14,102 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SENSOR_HH_ -#define IGNITION_GAZEBO_SENSOR_HH_ -#include -#include -#include - -#include - -#include - -#include - -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // - /// \class Sensor Sensor.hh ignition/gazebo/Sensor.hh - /// \brief This class provides wrappers around entities and components - /// which are more convenient and straight-forward to use than dealing - /// with the `EntityComponentManager` directly. - /// All the functions provided here are meant to be used with a sensor - /// entity. - /// - /// For example, given a sensor's entity, find the value of its - /// name component, one could use the entity-component manager (`ecm`) - /// directly as follows: - /// - /// std::string name = ecm.Component(entity)->Data(); - /// - /// Using this class however, the same information can be obtained with - /// a simpler function call: - /// - /// Sensor sensor(entity); - /// std::string name = sensor.Name(ecm); - /// - class IGNITION_GAZEBO_VISIBLE Sensor - { - /// \brief Constructor - /// \param[in] _entity Sensor entity - public: explicit Sensor(gazebo::Entity _entity = kNullEntity); - - /// \brief Get the entity which this Sensor is related to. - /// \return Sensor entity. - public: gazebo::Entity Entity() const; - - /// \brief Reset Entity to a new one - /// \param[in] _newEntity New sensor entity. - public: void ResetEntity(gazebo::Entity _newEntity); - - /// \brief Check whether this sensor correctly refers to an entity that - /// has a components::Sensor. - /// \param[in] _ecm Entity-component manager. - /// \return True if it's a valid sensor in the manager. - public: bool Valid(const EntityComponentManager &_ecm) const; - - /// \brief Get the sensor's unscoped name. - /// \param[in] _ecm Entity-component manager. - /// \return Sensor's name or nullopt if the entity does not have a - /// components::Name component - public: std::optional Name( - const EntityComponentManager &_ecm) const; - - /// \brief Get the pose of the sensor - /// \param[in] _ecm Entity-component manager. - /// \return Pose of the sensor or nullopt if the entity does not - /// have a components::Pose component. - public: std::optional Pose( - const EntityComponentManager &_ecm) const; - - /// \brief Get the topic of the sensor - /// \param[in] _ecm Entity-component manager. - /// \return Topic of the sensor or nullopt if the entity does not - /// have a components::SensorTopic component. - public: std::optional Topic( - const EntityComponentManager &_ecm) const; - - /// \brief Get the parent entity. This can be a link or a joint. - /// \param[in] _ecm Entity-component manager. - /// \return Parent entity or nullopt if the entity does not have a - /// components::ParentEntity component. - public: std::optional Parent( - const EntityComponentManager &_ecm) const; - - /// \brief Private data pointer. - IGN_UTILS_IMPL_PTR(dataPtr) - }; - } - } -} -#endif +#include +#include diff --git a/include/ignition/gazebo/comms/Broker.hh b/include/ignition/gazebo/comms/Broker.hh index bf06cdf383..91437357fe 100644 --- a/include/ignition/gazebo/comms/Broker.hh +++ b/include/ignition/gazebo/comms/Broker.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2022 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -15,140 +15,5 @@ * */ -#ifndef IGNITION_GAZEBO_BROKER_HH_ -#define IGNITION_GAZEBO_BROKER_HH_ - -#include - -#include -#include -#include "ignition/gazebo/comms/MsgManager.hh" -#include "ignition/gazebo/config.hh" - -namespace ignition -{ -namespace msgs -{ - // Forward declarations. - class Boolean; - class Dataframe; - class StringMsg_V; -} -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace comms -{ - // Forward declarations. - class MsgManager; - - /// \brief A class to store messages to be delivered using a comms model. - /// This class should be used in combination with a specific comms model that - /// implements the ICommsModel interface. - /// \sa ICommsModel.hh - /// The broker maintains two queues: inbound and outbound. When a client - /// sends a communication request, we'll store it in the outbound queue of - /// the sender's address. When the comms model decides that a message needs - /// to be delivered to one of the destination, it'll be stored in the inbound - /// queue of the destination's address. - /// - /// The main goal of this class is to receive the comms requests, stamp the - /// time, and place them in the appropriate outbound queue, as well as deliver - /// the messages that are in the inbound queues. - /// - /// The instance of the comms model is responsible for moving around the - /// messages from the outbound queues to the inbound queues. - /// - /// The broker can be configured with the following SDF parameters: - /// - /// * Optional parameters: - /// Element used to capture the broker parameters. This block can - /// contain any of the next parameters: - /// : Topic name where the broker receives all the incoming - /// messages. The default value is "/broker/msgs" - /// : Service name used to bind an address. - /// The default value is "/broker/bind" - /// : Service name used to unbind from an address. - /// The default value is "/broker/unbind" - /// - /// Here's an example: - /// - /// - /// /broker/inbound - /// /broker/bind_address - /// /broker/unbind_address - /// - /// - class IGNITION_GAZEBO_VISIBLE Broker - { - /// \brief Constructor. - public: Broker(); - - /// \brief Configure the broker via SDF. - /// \param[in] _sdf The SDF Element associated with the broker parameters. - public: void Load(std::shared_ptr _sdf); - - /// \brief Start handling comms services. - /// - /// This function allows us to wait to advertise capabilities to - /// clients until the broker has been entirely initialized. - public: void Start(); - - /// \brief Get the current time. - /// \return Current time. - public: std::chrono::steady_clock::duration Time() const; - - /// \brief Set the current time. - /// \param[in] _time Current time. - public: void SetTime(const std::chrono::steady_clock::duration &_time); - - /// \brief This method associates an address with a client topic used as - /// callback for receiving messages. This is a client requirement to - /// start receiving messages. - /// \param[in] _req Bind request containing the following content: - /// _req[0] Client address. - /// _req[1] Model name associated to the address. - /// _req[2] Client subscription topic. - /// \param[out] _rep Unused - /// \return True when the bind service succeeded or false otherwise. - public: bool OnBind(const ignition::msgs::StringMsg_V &_req, - ignition::msgs::Boolean &_rep); - - /// \brief Unbind a given client address. The client associated to this - /// address will not receive any more messages. - /// \param[in] _req Bind request containing the following content: - /// _req[0] Client address. - /// _req[1] Client subscription topic. - public: void OnUnbind(const ignition::msgs::StringMsg_V &_req); - - /// \brief Callback executed to process a communication request from one of - /// the clients. - /// \param[in] _msg The message from the client. - public: void OnMsg(const ignition::msgs::Dataframe &_msg); - - /// \brief Process all the messages in the inbound queue and deliver them - /// to the destination clients. - public: void DeliverMsgs(); - - /// \brief Get a mutable reference to the message manager. - /// \return The mutable reference. - public: MsgManager &DataManager(); - - /// \brief Lock the mutex to access the message manager. - public: void Lock(); - - /// \brief Unlock the mutex to access the message manager. - public: void Unlock(); - - /// \brief Private data pointer. - IGN_UTILS_UNIQUE_IMPL_PTR(dataPtr) - }; -} -} -} -} - -#endif +#include +#include diff --git a/include/ignition/gazebo/comms/ICommsModel.hh b/include/ignition/gazebo/comms/ICommsModel.hh index 367cbe975b..de2214ddfb 100644 --- a/include/ignition/gazebo/comms/ICommsModel.hh +++ b/include/ignition/gazebo/comms/ICommsModel.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2022 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -15,121 +15,5 @@ * */ -#ifndef IGNITION_GAZEBO_ICOMMSMODEL_HH_ -#define IGNITION_GAZEBO_ICOMMSMODEL_HH_ - -#include - -#include -#include -#include "ignition/gazebo/comms/MsgManager.hh" -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/System.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - - // Forward declarations - class EntityComponentManager; - class EventManager; - -namespace comms -{ - /// \brief Abstract interface to define how the environment should handle - /// communication simulation. As an example, this class could be responsible - /// for handling dropouts, decay and packet collisions. - /// - /// The derived comms models can be configured with the following SDF - /// parameters: - /// - /// * Optional parameters: - /// If defined this will allow the comms model to run at a - /// higher frequency than the physics engine. This is useful when dealing - /// with ranging. If the is set larger than the physics engine dt - /// then the comms model step size will default to dt. - /// Note: for consistency it is adviced that the dt is a multiple of timestep. - /// Units are in seconds. - /// - /// Here's an example: - /// - /// 2 - /// 1.0 - /// - /// - /// 1 - /// - class IGNITION_GAZEBO_VISIBLE ICommsModel: -#ifdef _MSC_VER - #pragma warning(push) - #pragma warning(disable:4275) -#endif - public System, -#ifdef _MSC_VER - #pragma warning(pop) -#endif - public ISystemConfigure, - public ISystemPreUpdate - { - /// \brief Constructor. - public: explicit ICommsModel(); - - // Documentation inherited. - public: void Configure(const Entity &_entity, - const std::shared_ptr &_sdf, - EntityComponentManager &_ecm, - EventManager &_eventMgr) override; - - // Documentation inherited. - public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; - - /// \brief This method is called when there is a timestep in the simulator. - /// \param[in] _info Simulator information about the current timestep. - /// will become the new registry. - /// \param[in] _ecm - Ignition's ECM. - public: virtual void StepImpl(const UpdateInfo &_info, - EntityComponentManager &_ecm); - - /// \brief This method is called when the system is being configured - /// override this to load any additional params for the comms model - /// \param[in] _entity The entity this plugin is attached to. - /// \param[in] _sdf The SDF Element associated with this system plugin. - /// \param[in] _ecm The EntityComponentManager of the given simulation - /// instance. - /// \param[in] _eventMgr The EventManager of the given simulation instance. - public: virtual void Load(const Entity &_entity, - std::shared_ptr _sdf, - EntityComponentManager &_ecm, - EventManager &_eventMgr) = 0; - - /// \brief This method is called when there is a timestep in the simulator - /// override this to update your data structures as needed. - /// - /// Note: this is an experimental interface and might change in the future. - /// - /// \param[in] _info Simulator information about the current timestep. - /// \param[in] _currentRegistry The current registry. - /// \param[out] _newRegistry The new registry. When Step() is finished this - /// will become the new registry. - /// \param[in] _ecm - Ignition's ECM. - public: virtual void Step(const UpdateInfo &_info, - const Registry &_currentRegistry, - Registry &_newRegistry, - EntityComponentManager &_ecm) = 0; - - /// \brief Private data pointer. - IGN_UTILS_UNIQUE_IMPL_PTR(dataPtr) - }; -} -} -} -} - -#endif +#include +#include diff --git a/include/ignition/gazebo/comms/MsgManager.hh b/include/ignition/gazebo/comms/MsgManager.hh index aa5bde7f4d..25f1ff139b 100644 --- a/include/ignition/gazebo/comms/MsgManager.hh +++ b/include/ignition/gazebo/comms/MsgManager.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2022 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -15,145 +15,5 @@ * */ -#ifndef IGNITION_GAZEBO_MSGMANAGER_HH_ -#define IGNITION_GAZEBO_MSGMANAGER_HH_ - -#include -#include -#include -#include - -#include -#include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/System.hh" - -namespace ignition -{ -namespace msgs -{ - // Forward declarations. - class Dataframe; -} -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace comms -{ - -/// \brief A queue of message pointers. -using DataQueue = std::deque; - -/// \brief A map where the key is the topic subscribed to an address and -/// the value is a publisher to reach that topic. -using SubscriptionHandler = - std::unordered_map; - -/// \brief All the information associated to an address. -struct AddressContent -{ - /// \brief Queue of inbound messages. - public: DataQueue inboundMsgs; - - /// \brief Queue of outbound messages. - public: DataQueue outboundMsgs; - - /// \brief Subscribers. - public: SubscriptionHandler subscriptions; - - /// \brief Model name associated to this address. - public: std::string modelName; - - /// \brief Entity of the model associated to this address. - public: gazebo::Entity entity; -}; - -/// \brief A map where the key is an address and the value is all the -/// information associated to each address (subscribers, queues, ...). -using Registry = std::unordered_map; - -/// \brief Class to handle messages and subscriptions. -class IGNITION_GAZEBO_VISIBLE MsgManager -{ - /// \brief Default constructor. - public: MsgManager(); - - /// \brief Add a new subscriber. It's possible to associate multiple topics - /// to the same address/model pair. However, the same address cannot be - /// attached to multiple models. When all the subscribers are removed, it's - /// posible to bind to this address using a different model. - /// \param[in] _address The subscriber address. - /// \param[in] _modelName The model name. - /// \param[in] _topic The subscriber topic. - /// \return True if the subscriber was successfully added or false otherwise. - public: bool AddSubscriber(const std::string &_address, - const std::string &_modelName, - const std::string &_topic); - - /// \brief Add a new message to the inbound queue. - /// \param[in] _address The destination address. - /// \param[in] _msg The message. - public: void AddInbound(const std::string &_address, - const msgs::DataframeSharedPtr &_msg); - - /// \brief Add a new message to the outbound queue. - /// \param[in] _address The sender address. - /// \param[in] _msg The message. - public: void AddOutbound(const std::string &_address, - const msgs::DataframeSharedPtr &_msg); - - /// \brief Remove an existing subscriber. - /// \param[in] _address The subscriber address. - /// \param[in] _topic The Subscriber topic. - /// \return True if the subscriber was removed or false otherwise. - public: bool RemoveSubscriber(const std::string &_address, - const std::string &_topic); - - /// \brief Remove a message from the inbound queue. - /// \param[in] _address The destination address. - /// \param[in] _Msg Message pointer to remove. - /// \return True if the message was removed or false otherwise. - public: bool RemoveInbound(const std::string &_address, - const msgs::DataframeSharedPtr &_msg); - - /// \brief Remove a message from the outbound queue. - /// \param[in] _address The sender address. - /// \param[in] _msg Message pointer to remove. - /// \return True if the message was removed or false otherwise. - public: bool RemoveOutbound(const std::string &_address, - const msgs::DataframeSharedPtr &_msg); - - /// \brief This function delivers all the messages in the inbound queue to - /// the appropriate subscribers. This function also clears the inbound queue. - public: void DeliverMsgs(); - - /// \brief Get an inmutable reference to the data containing subscriptions and - /// data queues. - /// \return A const reference to the data. - public: const Registry &DataConst() const; - - /// \brief Get a mutable reference to the data containing subscriptions and - /// data queues. - /// \return A mutable reference to the data. - public: Registry &Data(); - - /// \brief Get a copy of the data structure containing subscriptions and data - /// queues. - /// \return A copy of the data. - public: Registry Copy() const; - - /// \brief Set the data structure containing subscriptions and data queues. - /// \param[in] _newContent New content to be set. - public: void Set(const Registry &_newContent); - - /// \brief Private data pointer. - IGN_UTILS_UNIQUE_IMPL_PTR(dataPtr) -}; -} -} -} -} - -#endif +#include +#include diff --git a/include/ignition/gazebo/components/BatteryPowerLoad.hh b/include/ignition/gazebo/components/BatteryPowerLoad.hh index 6cfb191678..1073d23e85 100644 --- a/include/ignition/gazebo/components/BatteryPowerLoad.hh +++ b/include/ignition/gazebo/components/BatteryPowerLoad.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2022 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,40 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_BATTERYPOWERLOAD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_BATTERYPOWERLOAD_HH_ + */ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Data structure to hold the consumer power load - /// and the name of the battery it uses. - struct BatteryPowerLoadInfo - { - /// \brief Entity of the battery to use. - Entity batteryId; - /// \brief Battery power load (W) to add to the battery. - double batteryPowerLoad; - }; - - /// \brief A component that indicates the total consumption of a battery. - using BatteryPowerLoad = - Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.BatteryPowerLoad", - BatteryPowerLoad) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/BoundingBoxCamera.hh b/include/ignition/gazebo/components/BoundingBoxCamera.hh index 2451fd8f24..14a78a1325 100644 --- a/include/ignition/gazebo/components/BoundingBoxCamera.hh +++ b/include/ignition/gazebo/components/BoundingBoxCamera.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2022 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,33 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_BOUNDINGBOXCAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_BOUNDINGBOXCAMERA_HH_ + */ -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains a BoundingBox camera sensor, - /// sdf::Camera, information. - using BoundingBoxCamera = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.BoundingBoxCamera", - BoundingBoxCamera) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/CustomSensor.hh b/include/ignition/gazebo/components/CustomSensor.hh index 9871249241..aa9e0acc33 100644 --- a/include/ignition/gazebo/components/CustomSensor.hh +++ b/include/ignition/gazebo/components/CustomSensor.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,33 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_CUSTOMSENSOR_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CUSTOMSENSOR_HH_ + */ -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains a custom sensor's information. - /// A custom sensor is any sensor that's not officially supported through - /// the SDF spec. - using CustomSensor = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.CustomSensor", - CustomSensor) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/ForceTorque.hh b/include/ignition/gazebo/components/ForceTorque.hh index 12da278077..059287fa34 100644 --- a/include/ignition/gazebo/components/ForceTorque.hh +++ b/include/ignition/gazebo/components/ForceTorque.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,35 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_FORCETORQUE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_FORCETORQUE_HH_ - -#include + */ +#include #include -#include - -#include -#include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains an FT sensor, - /// sdf::ForceTorque, information. - using ForceTorque = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ForceTorque", - ForceTorque) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/HaltMotion.hh b/include/ignition/gazebo/components/HaltMotion.hh index 2b44fa5bb8..c2064af00b 100644 --- a/include/ignition/gazebo/components/HaltMotion.hh +++ b/include/ignition/gazebo/components/HaltMotion.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,27 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_HALT_MOTION_HH_ -#define IGNITION_GAZEBO_COMPONENTS_HALT_MOTION_HH_ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component used to turn off a model's joint's movement. - using HaltMotion = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.HaltMotion", - HaltMotion) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/JointTransmittedWrench.hh b/include/ignition/gazebo/components/JointTransmittedWrench.hh index a723fdc285..3b605deca8 100644 --- a/include/ignition/gazebo/components/JointTransmittedWrench.hh +++ b/include/ignition/gazebo/components/JointTransmittedWrench.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,43 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - -namespace components -{ -/// \brief Joint Transmitted wrench in SI units (Nm for torque, N for force). -/// The wrench is expressed in the Joint frame and the force component is -/// applied at the joint origin. -/// \note The term Wrench is used here to mean a pair of 3D vectors representing -/// torque and force quantities expressed in a given frame and where the force -/// is applied at the origin of the frame. This is different from the Wrench -/// used in screw theory. -/// \note The value of force_offset in msgs::Wrench is ignored for this -/// component. The force is assumed to be applied at the origin of the joint -/// frame. -using JointTransmittedWrench = - Component; -IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.JointTransmittedWrench", - JointTransmittedWrench) -} // namespace components -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/LightCmd.hh b/include/ignition/gazebo/components/LightCmd.hh index fdba5858fc..d9a4c56bc3 100644 --- a/include/ignition/gazebo/components/LightCmd.hh +++ b/include/ignition/gazebo/components/LightCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,35 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LIGHTCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LIGHTCMD_HH_ - -#include +#include #include -#include -#include -#include -#include - -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains commanded light of an - /// entity in the world frame represented by msgs::Light. - using LightCmd = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LightCmd", - LightCmd) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/LightType.hh b/include/ignition/gazebo/components/LightType.hh index 249eb8602f..bb83332ce6 100644 --- a/include/ignition/gazebo/components/LightType.hh +++ b/include/ignition/gazebo/components/LightType.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,34 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_LIGHTTYPE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LIGHTTYPE_HH_ + */ -#include -#include -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that contains the light type. This is a simple wrapper - /// around std::string - using LightType = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LightType", LightType) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/NavSat.hh b/include/ignition/gazebo/components/NavSat.hh index ae3358b9b4..9dec2250cc 100644 --- a/include/ignition/gazebo/components/NavSat.hh +++ b/include/ignition/gazebo/components/NavSat.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,34 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_NAVSAT_HH_ -#define IGNITION_GAZEBO_COMPONENTS_NAVSAT_HH_ - -#include + */ +#include #include -#include - -#include -#include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains an NavSat sensor, - /// sdf::NavSat, information. - using NavSat = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.NavSat", NavSat) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/ParticleEmitter.hh b/include/ignition/gazebo/components/ParticleEmitter.hh index 86fc36bd88..7c86a7a187 100644 --- a/include/ignition/gazebo/components/ParticleEmitter.hh +++ b/include/ignition/gazebo/components/ParticleEmitter.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,40 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ + */ -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that contains a particle emitter. - using ParticleEmitter = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ParticleEmitter", - ParticleEmitter) - - /// \brief A component that contains a particle emitter command. - using ParticleEmitterCmd = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ParticleEmitterCmd", - ParticleEmitterCmd) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Recreate.hh b/include/ignition/gazebo/components/Recreate.hh index bb053fe5f9..f11585232a 100644 --- a/include/ignition/gazebo/components/Recreate.hh +++ b/include/ignition/gazebo/components/Recreate.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,36 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_RECREATE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_RECREATE_HH_ + */ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that identifies an entity needs to be recreated. - /// Currently, only Models will be processed for recreation by the - /// SimulationRunner in the ProcessRecreateEntitiesRemove and - /// ProcessRecreateEntitiesCreate functions. - /// - /// The GUI ModelEditor contains example code on how to use this - /// component. For example, the ModelEditor allows a user to add a link to an - /// existing model. The existing model is tagged with this component so - /// that it can be recreated by the server. - using Recreate = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Recreate", Recreate) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/RenderEngineServerHeadless.hh b/include/ignition/gazebo/components/RenderEngineServerHeadless.hh index 9746e4b0aa..dc0a7cfa38 100644 --- a/include/ignition/gazebo/components/RenderEngineServerHeadless.hh +++ b/include/ignition/gazebo/components/RenderEngineServerHeadless.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,33 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ -#define IGNITION_GAZEBO_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ + */ -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Holds the headless mode. - using RenderEngineServerHeadless = Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.RenderEngineServerHeadless", - RenderEngineServerHeadless) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/SegmentationCamera.hh b/include/ignition/gazebo/components/SegmentationCamera.hh index c476fc8ba8..0bcedbce99 100644 --- a/include/ignition/gazebo/components/SegmentationCamera.hh +++ b/include/ignition/gazebo/components/SegmentationCamera.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,33 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_SEGMENTATIONCAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SEGMENTATIONCAMERA_HH_ + */ -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains a Segmentation camera sensor, - /// sdf::Camera, information. - using SegmentationCamera = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SegmentationCamera", - SegmentationCamera) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/SemanticLabel.hh b/include/ignition/gazebo/components/SemanticLabel.hh index 3139b75310..985cd6b8d3 100644 --- a/include/ignition/gazebo/components/SemanticLabel.hh +++ b/include/ignition/gazebo/components/SemanticLabel.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,30 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LABEL_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LABEL_HH_ -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/components/Component.hh" -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/config.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that holds the label of an entity. One example use - /// case of the Label component is with Segmentation & Bounding box - /// sensors to generate dataset annotations. - using SemanticLabel = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SemanticLabel", - SemanticLabel) -} -} -} -} -#endif +#include +#include diff --git a/include/ignition/gazebo/components/SphericalCoordinates.hh b/include/ignition/gazebo/components/SphericalCoordinates.hh index 93ebd43fa8..ef6996f098 100644 --- a/include/ignition/gazebo/components/SphericalCoordinates.hh +++ b/include/ignition/gazebo/components/SphericalCoordinates.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,41 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ + */ -#include -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace serializers -{ - using SphericalCoordinatesSerializer = - serializers::ComponentToMsgSerializer; -} - -namespace components -{ - /// \brief This component holds the spherical coordinates of the world origin. - using SphericalCoordinates = - Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.SphericalCoordinates", SphericalCoordinates) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/SystemPluginInfo.hh b/include/ignition/gazebo/components/SystemPluginInfo.hh index 365886c1e4..96e9d65758 100644 --- a/include/ignition/gazebo/components/SystemPluginInfo.hh +++ b/include/ignition/gazebo/components/SystemPluginInfo.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2022 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,35 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_SYSTEMINFO_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SYSTEMINFO_HH_ + */ -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief This component holds information about all the system plugins that - /// are attached to an entity. The content of each system is populated the - /// moment the plugin is instantiated and isn't modified throughout - /// simulation. - using SystemPluginInfo = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SystemPluginInfo", - SystemPluginInfo) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/TemperatureRange.hh b/include/ignition/gazebo/components/TemperatureRange.hh index 99e4a26151..0ca9e81f40 100644 --- a/include/ignition/gazebo/components/TemperatureRange.hh +++ b/include/ignition/gazebo/components/TemperatureRange.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,87 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_TEMPERATURERANGE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_TEMPERATURERANGE_HH_ + */ -#include -#include - -#include - -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Data structure to hold a temperature range, in kelvin - struct TemperatureRangeInfo - { - /// \brief The minimum temperature (kelvin) - math::Temperature min; - /// \brief The maximum temperature (kelvin) - math::Temperature max; - - public: bool operator==(const TemperatureRangeInfo &_info) const - { - return (this->min == _info.min) && - (this->max == _info.max); - } - - public: bool operator!=(const TemperatureRangeInfo &_info) const - { - return !(*this == _info); - } - }; -} - -namespace serializers -{ - /// \brief Serializer for components::TemperatureRangeInfo object - class TemperatureRangeInfoSerializer - { - /// \brief Serialization for components::TemperatureRangeInfo - /// \param[out] _out Output stream - /// \param[in] _info Object for the stream - /// \return The stream - public: static std::ostream &Serialize(std::ostream &_out, - const components::TemperatureRangeInfo &_info) - { - _out << _info.min << " " << _info.max; - return _out; - } - - /// \brief Deserialization for components::TemperatureRangeInfo - /// \param[in] _in Input stream - /// \param[out] _info The object to populate - /// \return The stream - public: static std::istream &Deserialize(std::istream &_in, - components::TemperatureRangeInfo &_info) - { - _in >> _info.min >> _info.max; - return _in; - } - }; -} - -namespace components -{ - /// \brief A component that stores a temperature range in kelvin - using TemperatureRange = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.TemperatureRange", - TemperatureRange) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Visibility.hh b/include/ignition/gazebo/components/Visibility.hh index 7a53ddbb3e..a3f52c491e 100644 --- a/include/ignition/gazebo/components/Visibility.hh +++ b/include/ignition/gazebo/components/Visibility.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,36 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_VISIBILITY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_VISIBILITY_HH_ + */ -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief This component holds an entity's visibility flags (visual entities) - using VisibilityFlags = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.VisibilityFlags", - VisibilityFlags) - - /// \brief This component holds an entity's visibility mask - /// (camera sensor entities) - using VisibilityMask = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.VisibilityMask", - VisibilityMask) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/VisualCmd.hh b/include/ignition/gazebo/components/VisualCmd.hh index 794057aabb..bd6a95e618 100644 --- a/include/ignition/gazebo/components/VisualCmd.hh +++ b/include/ignition/gazebo/components/VisualCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,35 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_VISUALCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_VISUALCMD_HH_ +#include #include -#include -#include -#include -#include - -#include - -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains commanded visual of an - /// entity in the world frame represented by msgs::Visual. - using VisualCmd = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.VisualCmd", - VisualCmd) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/WheelSlipCmd.hh b/include/ignition/gazebo/components/WheelSlipCmd.hh index 4daf7ee249..8c90b88a7b 100644 --- a/include/ignition/gazebo/components/WheelSlipCmd.hh +++ b/include/ignition/gazebo/components/WheelSlipCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2022 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,33 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ +#include #include -#include -#include -#include -#include - -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains commanded wheel slip parameters of - /// an entity in the world frame represented by msgs::WheelSlipParameters. - using WheelSlipCmd = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WheelSlipCmd", - WheelSlipCmd) -} -} -} -} -#endif From 5f1458ac6c8c9014b1aa44b9aa44110002ac47d5 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Thu, 25 May 2023 21:00:56 -0700 Subject: [PATCH 5/5] fixed comments Signed-off-by: Nate Koenig --- include/gz/sim/Actor.hh | 4 +- include/gz/sim/Joint.hh | 4 +- include/gz/sim/Light.hh | 4 +- include/gz/sim/Primitives.hh | 4 +- include/gz/sim/Sensor.hh | 4 +- include/gz/sim/comms/Broker.hh | 4 +- include/gz/sim/comms/ICommsModel.hh | 4 +- include/gz/sim/comms/MsgManager.hh | 4 +- include/gz/sim/components/BatteryPowerLoad.hh | 4 +- .../gz/sim/components/BoundingBoxCamera.hh | 4 +- include/gz/sim/components/CustomSensor.hh | 4 +- include/gz/sim/components/Factory.hh | 7 +-- include/gz/sim/components/ForceTorque.hh | 4 +- include/gz/sim/components/HaltMotion.hh | 4 +- .../sim/components/JointTransmittedWrench.hh | 4 +- include/gz/sim/components/LightCmd.hh | 4 +- include/gz/sim/components/LightType.hh | 4 +- include/gz/sim/components/NavSat.hh | 4 +- include/gz/sim/components/ParticleEmitter.hh | 4 +- include/gz/sim/components/Recreate.hh | 4 +- .../components/RenderEngineServerHeadless.hh | 4 +- .../gz/sim/components/SegmentationCamera.hh | 4 +- include/gz/sim/components/SemanticLabel.hh | 4 +- .../gz/sim/components/SphericalCoordinates.hh | 4 +- include/gz/sim/components/SystemPluginInfo.hh | 4 +- include/gz/sim/components/TemperatureRange.hh | 4 +- include/gz/sim/components/Visibility.hh | 4 +- include/gz/sim/components/VisualCmd.hh | 4 +- include/gz/sim/components/WheelSlipCmd.hh | 4 +- include/gz/sim/detail/BaseView.hh | 4 +- include/gz/sim/rendering/MarkerManager.hh | 1 + src/Server_TEST.cc | 12 ++--- src/gui/GuiRunner.cc | 14 +++--- src/gui/plugins/align_tool/AlignTool.cc | 2 +- .../banana_for_scale/BananaForScale.cc | 10 ++-- .../banana_for_scale/BananaForScale.hh | 2 +- .../ComponentInspectorEditor.cc | 18 +++---- .../component_inspector_editor/ModelEditor.cc | 8 ++-- src/gui/plugins/copy_paste/CopyPaste.cc | 16 +++---- .../EntityContextMenuPlugin.cc | 14 +++--- .../EntityContextMenuPlugin.hh | 2 +- src/gui/plugins/entity_tree/EntityTree.cc | 12 ++--- src/gui/plugins/lights/Lights.cc | 10 ++-- src/gui/plugins/lights/Lights.hh | 2 +- src/gui/plugins/plotting/Plotting.cc | 6 +-- src/gui/plugins/plotting/Plotting.hh | 2 +- src/gui/plugins/scene3d/Scene3D.cc | 16 +++---- .../plugins/scene_manager/GzSceneManager.cc | 22 ++++----- .../plugins/scene_manager/GzSceneManager.hh | 2 +- .../plugins/select_entities/SelectEntities.cc | 40 ++++++++-------- .../plugins/select_entities/SelectEntities.hh | 2 +- src/gui/plugins/shapes/Shapes.cc | 6 +-- src/gui/plugins/spawn/Spawn.cc | 48 +++++++++---------- src/gui/plugins/spawn/Spawn.hh | 4 +- .../transform_control/TransformControl.cc | 40 ++++++++-------- .../plugins/video_recorder/VideoRecorder.cc | 4 +- src/gui/plugins/view_angle/ViewAngle.cc | 6 +-- .../VisualizationCapabilities.cc | 8 ++-- .../visualize_contacts/VisualizeContacts.cc | 2 +- .../plugins/visualize_lidar/VisualizeLidar.cc | 12 ++--- 60 files changed, 234 insertions(+), 232 deletions(-) diff --git a/include/gz/sim/Actor.hh b/include/gz/sim/Actor.hh index e19f154a0a..b95db5e897 100644 --- a/include/gz/sim/Actor.hh +++ b/include/gz/sim/Actor.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_ACTOR_HH_ -#define IGNITION_GAZEBO_ACTOR_HH_ +#ifndef GZ_GAZEBO_ACTOR_HH_ +#define GZ_GAZEBO_ACTOR_HH_ #include #include diff --git a/include/gz/sim/Joint.hh b/include/gz/sim/Joint.hh index e58ed60264..ea79b96a3e 100644 --- a/include/gz/sim/Joint.hh +++ b/include/gz/sim/Joint.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_JOINT_HH_ -#define IGNITION_GAZEBO_JOINT_HH_ +#ifndef GZ_GAZEBO_JOINT_HH_ +#define GZ_GAZEBO_JOINT_HH_ #include #include diff --git a/include/gz/sim/Light.hh b/include/gz/sim/Light.hh index 130809bac3..72c408beb1 100644 --- a/include/gz/sim/Light.hh +++ b/include/gz/sim/Light.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_LIGHT_HH_ -#define IGNITION_GAZEBO_LIGHT_HH_ +#ifndef GZ_GAZEBO_LIGHT_HH_ +#define GZ_GAZEBO_LIGHT_HH_ #include #include diff --git a/include/gz/sim/Primitives.hh b/include/gz/sim/Primitives.hh index cb68727af3..1a519b1e05 100644 --- a/include/gz/sim/Primitives.hh +++ b/include/gz/sim/Primitives.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_PRIMITIVES_HH_ -#define IGNITION_GAZEBO_PRIMITIVES_HH_ +#ifndef GZ_GAZEBO_PRIMITIVES_HH_ +#define GZ_GAZEBO_PRIMITIVES_HH_ #include #include diff --git a/include/gz/sim/Sensor.hh b/include/gz/sim/Sensor.hh index ee08c8a814..7f727b2247 100644 --- a/include/gz/sim/Sensor.hh +++ b/include/gz/sim/Sensor.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SENSOR_HH_ -#define IGNITION_GAZEBO_SENSOR_HH_ +#ifndef GZ_GAZEBO_SENSOR_HH_ +#define GZ_GAZEBO_SENSOR_HH_ #include #include diff --git a/include/gz/sim/comms/Broker.hh b/include/gz/sim/comms/Broker.hh index f25646d575..f8825a29a6 100644 --- a/include/gz/sim/comms/Broker.hh +++ b/include/gz/sim/comms/Broker.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_BROKER_HH_ -#define IGNITION_GAZEBO_BROKER_HH_ +#ifndef GZ_GAZEBO_BROKER_HH_ +#define GZ_GAZEBO_BROKER_HH_ #include diff --git a/include/gz/sim/comms/ICommsModel.hh b/include/gz/sim/comms/ICommsModel.hh index e91ee63335..add9811a3f 100644 --- a/include/gz/sim/comms/ICommsModel.hh +++ b/include/gz/sim/comms/ICommsModel.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_ICOMMSMODEL_HH_ -#define IGNITION_GAZEBO_ICOMMSMODEL_HH_ +#ifndef GZ_GAZEBO_ICOMMSMODEL_HH_ +#define GZ_GAZEBO_ICOMMSMODEL_HH_ #include diff --git a/include/gz/sim/comms/MsgManager.hh b/include/gz/sim/comms/MsgManager.hh index 68ebfbd54b..8b50a33f06 100644 --- a/include/gz/sim/comms/MsgManager.hh +++ b/include/gz/sim/comms/MsgManager.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_MSGMANAGER_HH_ -#define IGNITION_GAZEBO_MSGMANAGER_HH_ +#ifndef GZ_GAZEBO_MSGMANAGER_HH_ +#define GZ_GAZEBO_MSGMANAGER_HH_ #include #include diff --git a/include/gz/sim/components/BatteryPowerLoad.hh b/include/gz/sim/components/BatteryPowerLoad.hh index 47764ca4b2..2a25996a4c 100644 --- a/include/gz/sim/components/BatteryPowerLoad.hh +++ b/include/gz/sim/components/BatteryPowerLoad.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_BATTERYPOWERLOAD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_BATTERYPOWERLOAD_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_BATTERYPOWERLOAD_HH_ +#define GZ_GAZEBO_COMPONENTS_BATTERYPOWERLOAD_HH_ #include #include diff --git a/include/gz/sim/components/BoundingBoxCamera.hh b/include/gz/sim/components/BoundingBoxCamera.hh index 39d56f1d84..cc9fd8f29f 100644 --- a/include/gz/sim/components/BoundingBoxCamera.hh +++ b/include/gz/sim/components/BoundingBoxCamera.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_BOUNDINGBOXCAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_BOUNDINGBOXCAMERA_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_BOUNDINGBOXCAMERA_HH_ +#define GZ_GAZEBO_COMPONENTS_BOUNDINGBOXCAMERA_HH_ #include diff --git a/include/gz/sim/components/CustomSensor.hh b/include/gz/sim/components/CustomSensor.hh index 63b79d63d1..54965bf58e 100644 --- a/include/gz/sim/components/CustomSensor.hh +++ b/include/gz/sim/components/CustomSensor.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_CUSTOMSENSOR_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CUSTOMSENSOR_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_CUSTOMSENSOR_HH_ +#define GZ_GAZEBO_COMPONENTS_CUSTOMSENSOR_HH_ #include #include diff --git a/include/gz/sim/components/Factory.hh b/include/gz/sim/components/Factory.hh index 7883333888..456cf3fc20 100644 --- a/include/gz/sim/components/Factory.hh +++ b/include/gz/sim/components/Factory.hh @@ -512,9 +512,10 @@ namespace components public: IgnGazeboComponents##_classname() \ { \ using namespace ignition; \ - using Desc = gazebo::components::ComponentDescriptor<_classname>; \ - gazebo::components::Factory::Instance()->Register<_classname>(\ - _compType, new Desc(), gazebo::components::RegistrationObjectId(this));\ + using Desc = gz::sim::components::ComponentDescriptor<_classname>; \ + gz::sim::components::Factory::Instance()->Register<_classname>(\ + _compType, new Desc(), \ + gz::sim::components::RegistrationObjectId(this));\ } \ public: IgnGazeboComponents##_classname( \ const IgnGazeboComponents##_classname&) = delete; \ diff --git a/include/gz/sim/components/ForceTorque.hh b/include/gz/sim/components/ForceTorque.hh index 98c42c1f67..1801ed85de 100644 --- a/include/gz/sim/components/ForceTorque.hh +++ b/include/gz/sim/components/ForceTorque.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_FORCETORQUE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_FORCETORQUE_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_FORCETORQUE_HH_ +#define GZ_GAZEBO_COMPONENTS_FORCETORQUE_HH_ #include diff --git a/include/gz/sim/components/HaltMotion.hh b/include/gz/sim/components/HaltMotion.hh index ece6c659df..3d231b54dd 100644 --- a/include/gz/sim/components/HaltMotion.hh +++ b/include/gz/sim/components/HaltMotion.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_HALT_MOTION_HH_ -#define IGNITION_GAZEBO_COMPONENTS_HALT_MOTION_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_HALT_MOTION_HH_ +#define GZ_GAZEBO_COMPONENTS_HALT_MOTION_HH_ #include #include diff --git a/include/gz/sim/components/JointTransmittedWrench.hh b/include/gz/sim/components/JointTransmittedWrench.hh index e082f1ab1a..2affd4f6a5 100644 --- a/include/gz/sim/components/JointTransmittedWrench.hh +++ b/include/gz/sim/components/JointTransmittedWrench.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ +#define GZ_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ #include diff --git a/include/gz/sim/components/LightCmd.hh b/include/gz/sim/components/LightCmd.hh index b4e36b8ddd..3dbc6803cd 100644 --- a/include/gz/sim/components/LightCmd.hh +++ b/include/gz/sim/components/LightCmd.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LIGHTCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LIGHTCMD_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_LIGHTCMD_HH_ +#define GZ_GAZEBO_COMPONENTS_LIGHTCMD_HH_ #include diff --git a/include/gz/sim/components/LightType.hh b/include/gz/sim/components/LightType.hh index ffc3ed62c7..e40f114b3c 100644 --- a/include/gz/sim/components/LightType.hh +++ b/include/gz/sim/components/LightType.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LIGHTTYPE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LIGHTTYPE_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_LIGHTTYPE_HH_ +#define GZ_GAZEBO_COMPONENTS_LIGHTTYPE_HH_ #include #include diff --git a/include/gz/sim/components/NavSat.hh b/include/gz/sim/components/NavSat.hh index 35c864563a..29e9af8ddc 100644 --- a/include/gz/sim/components/NavSat.hh +++ b/include/gz/sim/components/NavSat.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_NAVSAT_HH_ -#define IGNITION_GAZEBO_COMPONENTS_NAVSAT_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_NAVSAT_HH_ +#define GZ_GAZEBO_COMPONENTS_NAVSAT_HH_ #include diff --git a/include/gz/sim/components/ParticleEmitter.hh b/include/gz/sim/components/ParticleEmitter.hh index 7d70532c22..4771bb89fc 100644 --- a/include/gz/sim/components/ParticleEmitter.hh +++ b/include/gz/sim/components/ParticleEmitter.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ +#define GZ_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ #include #include diff --git a/include/gz/sim/components/Recreate.hh b/include/gz/sim/components/Recreate.hh index d15ea5fdf4..6f9eb082a0 100644 --- a/include/gz/sim/components/Recreate.hh +++ b/include/gz/sim/components/Recreate.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_RECREATE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_RECREATE_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_RECREATE_HH_ +#define GZ_GAZEBO_COMPONENTS_RECREATE_HH_ #include #include diff --git a/include/gz/sim/components/RenderEngineServerHeadless.hh b/include/gz/sim/components/RenderEngineServerHeadless.hh index 0f9ea36ebc..05ab542dc4 100644 --- a/include/gz/sim/components/RenderEngineServerHeadless.hh +++ b/include/gz/sim/components/RenderEngineServerHeadless.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ -#define IGNITION_GAZEBO_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ +#define GZ_GAZEBO_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ #include #include diff --git a/include/gz/sim/components/SegmentationCamera.hh b/include/gz/sim/components/SegmentationCamera.hh index b84658a6ef..35cf4399d5 100644 --- a/include/gz/sim/components/SegmentationCamera.hh +++ b/include/gz/sim/components/SegmentationCamera.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_SEGMENTATIONCAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SEGMENTATIONCAMERA_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_SEGMENTATIONCAMERA_HH_ +#define GZ_GAZEBO_COMPONENTS_SEGMENTATIONCAMERA_HH_ #include diff --git a/include/gz/sim/components/SemanticLabel.hh b/include/gz/sim/components/SemanticLabel.hh index 9282751be8..0416d1b310 100644 --- a/include/gz/sim/components/SemanticLabel.hh +++ b/include/gz/sim/components/SemanticLabel.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LABEL_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LABEL_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_LABEL_HH_ +#define GZ_GAZEBO_COMPONENTS_LABEL_HH_ #include "gz/sim/Export.hh" #include "gz/sim/components/Component.hh" diff --git a/include/gz/sim/components/SphericalCoordinates.hh b/include/gz/sim/components/SphericalCoordinates.hh index 1f98bf7331..ea19224625 100644 --- a/include/gz/sim/components/SphericalCoordinates.hh +++ b/include/gz/sim/components/SphericalCoordinates.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ +#define GZ_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ #include #include diff --git a/include/gz/sim/components/SystemPluginInfo.hh b/include/gz/sim/components/SystemPluginInfo.hh index 4990b2a2ee..6e0389d0e4 100644 --- a/include/gz/sim/components/SystemPluginInfo.hh +++ b/include/gz/sim/components/SystemPluginInfo.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_SYSTEMINFO_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SYSTEMINFO_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_SYSTEMINFO_HH_ +#define GZ_GAZEBO_COMPONENTS_SYSTEMINFO_HH_ #include #include diff --git a/include/gz/sim/components/TemperatureRange.hh b/include/gz/sim/components/TemperatureRange.hh index 668fa2a7ef..24a5e5f4ff 100644 --- a/include/gz/sim/components/TemperatureRange.hh +++ b/include/gz/sim/components/TemperatureRange.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_TEMPERATURERANGE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_TEMPERATURERANGE_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_TEMPERATURERANGE_HH_ +#define GZ_GAZEBO_COMPONENTS_TEMPERATURERANGE_HH_ #include #include diff --git a/include/gz/sim/components/Visibility.hh b/include/gz/sim/components/Visibility.hh index 3465db7eaa..d39f263794 100644 --- a/include/gz/sim/components/Visibility.hh +++ b/include/gz/sim/components/Visibility.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_VISIBILITY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_VISIBILITY_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_VISIBILITY_HH_ +#define GZ_GAZEBO_COMPONENTS_VISIBILITY_HH_ #include #include diff --git a/include/gz/sim/components/VisualCmd.hh b/include/gz/sim/components/VisualCmd.hh index 71a424ec9b..7bfcfcbd05 100644 --- a/include/gz/sim/components/VisualCmd.hh +++ b/include/gz/sim/components/VisualCmd.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_VISUALCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_VISUALCMD_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_VISUALCMD_HH_ +#define GZ_GAZEBO_COMPONENTS_VISUALCMD_HH_ #include #include diff --git a/include/gz/sim/components/WheelSlipCmd.hh b/include/gz/sim/components/WheelSlipCmd.hh index ec6ae1b3bb..b87e756f50 100644 --- a/include/gz/sim/components/WheelSlipCmd.hh +++ b/include/gz/sim/components/WheelSlipCmd.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ +#define GZ_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ #include #include diff --git a/include/gz/sim/detail/BaseView.hh b/include/gz/sim/detail/BaseView.hh index 6452524bd8..3fc53d4453 100644 --- a/include/gz/sim/detail/BaseView.hh +++ b/include/gz/sim/detail/BaseView.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_DETAIL_BASEVIEW_HH_ -#define IGNITION_GAZEBO_DETAIL_BASEVIEW_HH_ +#ifndef GZ_GAZEBO_DETAIL_BASEVIEW_HH_ +#define GZ_GAZEBO_DETAIL_BASEVIEW_HH_ #include #include diff --git a/include/gz/sim/rendering/MarkerManager.hh b/include/gz/sim/rendering/MarkerManager.hh index 5139505772..26c4b0d716 100644 --- a/include/gz/sim/rendering/MarkerManager.hh +++ b/include/gz/sim/rendering/MarkerManager.hh @@ -20,6 +20,7 @@ #include #include +#include #include #include "gz/rendering/RenderTypes.hh" diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc index 509c730c95..5e1a89b5da 100644 --- a/src/Server_TEST.cc +++ b/src/Server_TEST.cc @@ -170,7 +170,7 @@ TEST_P(ServerFixture, ServerConfigSdfPluginInfo) plugin.SetName("interface"); pluginInfo.SetPlugin(plugin); - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.AddPlugin(pluginInfo); const std::list &plugins = serverConfig.Plugins(); @@ -364,7 +364,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(SdfServerConfig)) ///////////////////////////////////////////////// TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(SdfRootServerConfig)) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetSdfString(TestWorldSansPhysics::World()); EXPECT_TRUE(serverConfig.SdfFile().empty()); @@ -386,7 +386,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(SdfRootServerConfig)) EXPECT_TRUE(serverConfig.SdfFile().empty()); EXPECT_TRUE(serverConfig.SdfString().empty()); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_TRUE(*server.Paused()); @@ -693,7 +693,7 @@ TEST_P(ServerFixture, RunNonBlockingMultiple) { ServerConfig serverConfig; serverConfig.SetSdfString(TestWorldSansPhysics::World()); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); @@ -1113,7 +1113,7 @@ TEST_P(ServerFixture, ResolveResourcePaths) common::setenv("IGN_FILE_PATH", ""); ServerConfig serverConfig; - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(*server.Running(0)); @@ -1186,7 +1186,7 @@ TEST_P(ServerFixture, Stop) serverConfig.SetSdfFile(common::joinPaths((PROJECT_SOURCE_PATH), "test", "worlds", "shapes.sdf")); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); // The simulation runner should not be running. EXPECT_FALSE(*server.Running(0)); diff --git a/src/gui/GuiRunner.cc b/src/gui/GuiRunner.cc index 27f82039dc..5d2580eb5c 100644 --- a/src/gui/GuiRunner.cc +++ b/src/gui/GuiRunner.cc @@ -154,8 +154,8 @@ GuiRunner::GuiRunner(const std::string &_worldName) this->dataPtr->controlService = "/world/" + _worldName + "/control/state"; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); } ///////////////////////////////////////////////// @@ -164,10 +164,10 @@ GuiRunner::~GuiRunner() = default; ///////////////////////////////////////////////// bool GuiRunner::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::WorldControl::kType) + if (_event->type() == gz::gui::events::WorldControl::kType) { auto worldControlEvent = - reinterpret_cast(_event); + reinterpret_cast(_event); if (worldControlEvent) { msgs::WorldControlState req; @@ -232,7 +232,7 @@ bool GuiRunner::eventFilter(QObject *_obj, QEvent *_event) void GuiRunner::RequestState() { // set up service for async state response callback - std::string id = std::to_string(ignition::gui::App()->applicationPid()); + std::string id = std::to_string(gz::gui::App()->applicationPid()); std::string reqSrv = this->dataPtr->node.Options().NameSpace() + "/" + id + "/state_async"; auto reqSrvValid = transport::TopicUtils::AsValidTopic(reqSrv); @@ -286,7 +286,7 @@ void GuiRunner::OnStateAsyncService(const msgs::SerializedStepMap &_res) // todo(anyone) store reqSrv string in a member variable and use it here // and in RequestState() - std::string id = std::to_string(ignition::gui::App()->applicationPid()); + std::string id = std::to_string(gz::gui::App()->applicationPid()); std::string reqSrv = this->dataPtr->node.Options().NameSpace() + "/" + id + "/state_async"; this->dataPtr->node.UnadvertiseSrv(reqSrv); @@ -326,7 +326,7 @@ void GuiRunner::OnStateQt(const msgs::SerializedStepMap &_msg) void GuiRunner::UpdatePlugins() { // gui plugins - auto plugins = ignition::gui::App()->findChildren(); + auto plugins = gz::gui::App()->findChildren(); for (auto plugin : plugins) { plugin->Update(this->dataPtr->updateInfo, this->dataPtr->ecm); diff --git a/src/gui/plugins/align_tool/AlignTool.cc b/src/gui/plugins/align_tool/AlignTool.cc index 5fdbcf4f62..3a864e9016 100644 --- a/src/gui/plugins/align_tool/AlignTool.cc +++ b/src/gui/plugins/align_tool/AlignTool.cc @@ -551,7 +551,7 @@ rendering::NodePtr AlignTool::TopLevelNode(rendering::ScenePtr &_scene, ///////////////////////////////////////////////// bool AlignTool::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { // This event is called in Scene3d's RenderThread, so it's safe to make // rendering calls here diff --git a/src/gui/plugins/banana_for_scale/BananaForScale.cc b/src/gui/plugins/banana_for_scale/BananaForScale.cc index a134466d00..f0627d57fc 100644 --- a/src/gui/plugins/banana_for_scale/BananaForScale.cc +++ b/src/gui/plugins/banana_for_scale/BananaForScale.cc @@ -54,7 +54,7 @@ using namespace gazebo; ///////////////////////////////////////////////// BananaForScale::BananaForScale() - : ignition::gui::Plugin(), + : gz::gui::Plugin(), dataPtr(std::make_unique()) { this->dataPtr->fuelClient = @@ -101,12 +101,12 @@ void BananaForScale::OnMode(const QString &_mode) sdfPath = ignition::common::joinPaths(localPath, "model.sdf"); } - ignition::gui::events::SpawnFromPath event(sdfPath); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::SpawnFromPath event(sdfPath); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); } // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::BananaForScale, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/banana_for_scale/BananaForScale.hh b/src/gui/plugins/banana_for_scale/BananaForScale.hh index 36e71d28f5..668f8a570c 100644 --- a/src/gui/plugins/banana_for_scale/BananaForScale.hh +++ b/src/gui/plugins/banana_for_scale/BananaForScale.hh @@ -29,7 +29,7 @@ namespace gazebo class BananaPrivate; /// \brief Provides buttons for adding a banana for scale - class BananaForScale: public ignition::gui::Plugin + class BananaForScale: public gz::gui::Plugin { Q_OBJECT diff --git a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc index 6aacd3b4dc..6c3655abe9 100644 --- a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc +++ b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc @@ -479,8 +479,8 @@ void ComponentInspectorEditor::LoadConfig(const tinyxml2::XMLElement *) if (this->title.empty()) this->title = "Component inspector editor"; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); // Connect model this->Context()->setContextProperty( @@ -1348,8 +1348,8 @@ void ComponentInspectorEditor::OnAddEntity(const QString &_entity, ignition::gazebo::gui::events::ModelEditorAddEntity addEntityEvent( _entity, _type, this->dataPtr->entity); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &addEntityEvent); } @@ -1364,8 +1364,8 @@ void ComponentInspectorEditor::OnAddJoint(const QString &_jointType, addEntityEvent.Data().insert("parent_link", _parentLink); addEntityEvent.Data().insert("child_link", _childLink); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &addEntityEvent); } @@ -1391,12 +1391,12 @@ void ComponentInspectorEditor::OnLoadMesh(const QString &_entity, addEntityEvent.Data().insert("uri", QString(meshStr.c_str())); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &addEntityEvent); } } // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::ComponentInspectorEditor, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/component_inspector_editor/ModelEditor.cc b/src/gui/plugins/component_inspector_editor/ModelEditor.cc index 2f88fcd717..b6d108d324 100644 --- a/src/gui/plugins/component_inspector_editor/ModelEditor.cc +++ b/src/gui/plugins/component_inspector_editor/ModelEditor.cc @@ -145,8 +145,8 @@ ModelEditor::~ModelEditor() = default; ///////////////////////////////////////////////// void ModelEditor::Load() { - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); } ////////////////////////////////////////////////// @@ -240,8 +240,8 @@ void ModelEditor::Update(const UpdateInfo &, std::set removedEntities; ignition::gazebo::gui::events::GuiNewRemovedEntities event( newEntities, removedEntities); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); this->dataPtr->entitiesToAdd.clear(); diff --git a/src/gui/plugins/copy_paste/CopyPaste.cc b/src/gui/plugins/copy_paste/CopyPaste.cc index 52bb86b9ce..3ec045b913 100644 --- a/src/gui/plugins/copy_paste/CopyPaste.cc +++ b/src/gui/plugins/copy_paste/CopyPaste.cc @@ -90,10 +90,10 @@ void CopyPaste::LoadConfig(const tinyxml2::XMLElement *) if (this->title.empty()) this->title = "Copy/Paste"; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->QuickWindow()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->QuickWindow()->installEventFilter(this); } ///////////////////////////////////////////////// @@ -123,9 +123,9 @@ void CopyPaste::OnPaste() // we should only paste if something has been copied if (!this->dataPtr->copiedData.empty()) { - ignition::gui::events::SpawnCloneFromName event(this->dataPtr->copiedData); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::SpawnCloneFromName event(this->dataPtr->copiedData); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); } } @@ -182,4 +182,4 @@ bool CopyPaste::PasteServiceCB(const ignition::msgs::Empty &/*_req*/, // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::CopyPaste, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc index ff916ff00b..d1dc2c17c2 100644 --- a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc +++ b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc @@ -112,21 +112,21 @@ void EntityContextMenu::LoadConfig(const tinyxml2::XMLElement *) if (this->title.empty()) this->title = "Entity Context Menu"; - ignition::gui::App()->findChild - ()->installEventFilter(this); + gz::gui::App()->findChild + ()->installEventFilter(this); } //////////////////////////////////////////////// bool EntityContextMenu::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { this->dataPtr->OnRender(); } - else if (_event->type() == ignition::gui::events::RightClickOnScene::kType) + else if (_event->type() == gz::gui::events::RightClickOnScene::kType) { - ignition::gui::events::RightClickOnScene *_e = - static_cast(_event); + gz::gui::events::RightClickOnScene *_e = + static_cast(_event); if (_e) { this->dataPtr->entityContextMenuHandler.HandleMouseContextMenu( @@ -205,4 +205,4 @@ void EntityContextMenuHandler::HandleMouseContextMenu( // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::EntityContextMenu, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh index e7fd8b0966..a0c0cd79d7 100644 --- a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh +++ b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh @@ -34,7 +34,7 @@ namespace gazebo /// \brief This plugin is in charge of showing the entity context menu when /// the right button is clicked on a visual. - class EntityContextMenu : public ignition::gui::Plugin + class EntityContextMenu : public gz::gui::Plugin { Q_OBJECT diff --git a/src/gui/plugins/entity_tree/EntityTree.cc b/src/gui/plugins/entity_tree/EntityTree.cc index b00ebf169f..828c872d9f 100644 --- a/src/gui/plugins/entity_tree/EntityTree.cc +++ b/src/gui/plugins/entity_tree/EntityTree.cc @@ -468,9 +468,9 @@ void EntityTree::DeselectAllEntities() void EntityTree::OnInsertEntity(const QString &_type) { std::string modelSdfString = getPrimitive(_type.toStdString()); - ignition::gui::events::SpawnFromDescription event(modelSdfString); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::SpawnFromDescription event(modelSdfString); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); } @@ -515,9 +515,9 @@ void EntityTree::OnLoadMesh(const QString &_mesh) "" ""; - ignition::gui::events::SpawnFromDescription event(sdf); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::SpawnFromDescription event(sdf); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); } diff --git a/src/gui/plugins/lights/Lights.cc b/src/gui/plugins/lights/Lights.cc index 395c4607d9..996eeed87a 100644 --- a/src/gui/plugins/lights/Lights.cc +++ b/src/gui/plugins/lights/Lights.cc @@ -47,7 +47,7 @@ using namespace gazebo; ///////////////////////////////////////////////// Lights::Lights() - : ignition::gui::Plugin(), + : gz::gui::Plugin(), dataPtr(std::make_unique()) { } @@ -70,13 +70,13 @@ void Lights::OnNewLightClicked(const QString &_sdfString) if (!modelSdfString.empty()) { - ignition::gui::events::SpawnFromDescription event(modelSdfString); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::SpawnFromDescription event(modelSdfString); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); } } // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::Lights, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/lights/Lights.hh b/src/gui/plugins/lights/Lights.hh index 49fd8dd063..dee445ff87 100644 --- a/src/gui/plugins/lights/Lights.hh +++ b/src/gui/plugins/lights/Lights.hh @@ -30,7 +30,7 @@ namespace gazebo /// \brief Provides buttons for adding a point, directional, or spot light /// to the scene - class Lights : public ignition::gui::Plugin + class Lights : public gz::gui::Plugin { Q_OBJECT diff --git a/src/gui/plugins/plotting/Plotting.cc b/src/gui/plugins/plotting/Plotting.cc index 902e0e5962..23b3486381 100644 --- a/src/gui/plugins/plotting/Plotting.cc +++ b/src/gui/plugins/plotting/Plotting.cc @@ -69,13 +69,13 @@ namespace ignition::gazebo /// \brief attributes of the components, /// ex: x,y,z attributes in Vector3d type component public: std::map> data; + std::shared_ptr> data; }; } using namespace ignition; using namespace ignition::gazebo; -using namespace ignition::gui; +using namespace gz::gui; ////////////////////////////////////////////////// PlotComponent::PlotComponent(const std::string &_type, @@ -552,4 +552,4 @@ void Plotting::Update(const ignition::gazebo::UpdateInfo &_info, // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::Plotting, ignition::gazebo::GuiSystem, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/plotting/Plotting.hh b/src/gui/plugins/plotting/Plotting.hh index 578bb7ff6c..29b003fb34 100644 --- a/src/gui/plugins/plotting/Plotting.hh +++ b/src/gui/plugins/plotting/Plotting.hh @@ -76,7 +76,7 @@ class PlotComponent /// \brief Get all attributes of the component /// \return component attributes - public: std::map> + public: std::map> Data() const; /// \brief Get the Component entity ID diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 20a4212356..80cf24845a 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -2112,7 +2112,7 @@ std::string IgnRenderer::Initialize() } this->dataPtr->renderUtil.SetWinID(std::to_string( - ignition::gui::App()->findChild()-> + gz::gui::App()->findChild()-> QuickWindow()->winId())); this->dataPtr->renderUtil.SetUseCurrentGLContext(true); this->dataPtr->renderUtil.Init(); @@ -3713,7 +3713,7 @@ bool Scene3D::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - gui::events::DeselectAllEntities::kType) + gz::sim::gui::events::DeselectAllEntities::kType) { auto deselectEvent = reinterpret_cast( @@ -3727,9 +3727,9 @@ bool Scene3D::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gui::events::SnapIntervals::kType) + gz::gui::events::SnapIntervals::kType) { - auto snapEvent = reinterpret_cast( + auto snapEvent = reinterpret_cast( _event); if (snapEvent) { @@ -3740,20 +3740,20 @@ bool Scene3D::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gui::events::SpawnFromDescription::kType) + gz::gui::events::SpawnFromDescription::kType) { auto spawnPreviewEvent = reinterpret_cast< - ignition::gui::events::SpawnFromDescription *>(_event); + gz::gui::events::SpawnFromDescription *>(_event); if (spawnPreviewEvent) { auto renderWindow = this->PluginItem()->findChild(); renderWindow->SetModel(spawnPreviewEvent->Description()); } } - else if (_event->type() == ignition::gui::events::SpawnFromPath::kType) + else if (_event->type() == gz::gui::events::SpawnFromPath::kType) { auto spawnPreviewPathEvent = - reinterpret_cast(_event); + reinterpret_cast(_event); if (spawnPreviewPathEvent) { auto renderWindow = this->PluginItem()->findChild(); diff --git a/src/gui/plugins/scene_manager/GzSceneManager.cc b/src/gui/plugins/scene_manager/GzSceneManager.cc index 62bdf3c70d..3cfd836fb4 100644 --- a/src/gui/plugins/scene_manager/GzSceneManager.cc +++ b/src/gui/plugins/scene_manager/GzSceneManager.cc @@ -111,8 +111,8 @@ void GzSceneManager::LoadConfig(const tinyxml2::XMLElement *) } done = true; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); this->dataPtr->initialized = true; } @@ -177,8 +177,8 @@ void GzSceneManager::Update(const UpdateInfo &_info, // Send the new VisualPlugins event ignition::gazebo::gui::events::VisualPlugins visualPluginsEvent( it.first, it.second); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &visualPluginsEvent); // Send the old VisualPlugin event @@ -186,8 +186,8 @@ void GzSceneManager::Update(const UpdateInfo &_info, { ignition::gazebo::gui::events::VisualPlugin visualPluginEvent( it.first, plugin.ToElement()); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &visualPluginEvent); } } @@ -211,15 +211,15 @@ void GzSceneManager::Update(const UpdateInfo &_info, ignition::gazebo::gui::events::NewRemovedEntities removedEvent( created, removed); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &removedEvent); } ///////////////////////////////////////////////// bool GzSceneManager::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { this->dataPtr->OnRender(); } @@ -254,7 +254,7 @@ void GzSceneManagerPrivate::OnRender() this->renderUtil.SetScene(this->scene); - auto runners = ignition::gui::App()->findChildren(); + auto runners = gz::gui::App()->findChildren(); if (runners.empty() || runners[0] == nullptr) { ignerr << "Internal error: no GuiRunner found." << std::endl; @@ -270,4 +270,4 @@ void GzSceneManagerPrivate::OnRender() // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::GzSceneManager, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/scene_manager/GzSceneManager.hh b/src/gui/plugins/scene_manager/GzSceneManager.hh index c84f33322e..54f0cdb3ef 100644 --- a/src/gui/plugins/scene_manager/GzSceneManager.hh +++ b/src/gui/plugins/scene_manager/GzSceneManager.hh @@ -33,7 +33,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Updates a 3D scene based on information coming from the ECM. /// This plugin doesn't instantiate a new 3D scene. Instead, it relies on /// another plugin being loaded alongside it that will create and paint the - /// scene to the window, such as `ignition::gui::plugins::Scene3D`. + /// scene to the window, such as `gz::gui::plugins::Scene3D`. /// /// Only one GzSceneManager can be used at a time. class GzSceneManager : public GuiSystem diff --git a/src/gui/plugins/select_entities/SelectEntities.cc b/src/gui/plugins/select_entities/SelectEntities.cc index fb5ab946f6..8ae535f598 100644 --- a/src/gui/plugins/select_entities/SelectEntities.cc +++ b/src/gui/plugins/select_entities/SelectEntities.cc @@ -186,8 +186,8 @@ void SelectEntitiesPrivate::HandleEntitySelection() ignition::gazebo::gui::events::EntitiesSelected selectEvent( this->selectedEntities); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &selectEvent); } this->receivedSelectedEntities = false; @@ -375,8 +375,8 @@ void SelectEntitiesPrivate::SetSelectedEntity( this->HighlightNode(topLevelVisual); ignition::gazebo::gui::events::EntitiesSelected entitiesSelected( this->selectedEntities); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &entitiesSelected); } @@ -396,8 +396,8 @@ void SelectEntitiesPrivate::DeselectAllEntities() this->selectedEntitiesID.clear(); ignition::gazebo::gui::events::DeselectAllEntities deselectEvent(true); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &deselectEvent); } @@ -425,8 +425,8 @@ void SelectEntitiesPrivate::UpdateSelectedEntity( { ignition::gazebo::gui::events::EntitiesSelected selectEvent( this->selectedEntities); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &selectEvent); } } @@ -488,17 +488,17 @@ void SelectEntities::LoadConfig(const tinyxml2::XMLElement *) } done = true; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); } ///////////////////////////////////////////////// bool SelectEntities::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::LeftClickOnScene::kType) + if (_event->type() == gz::gui::events::LeftClickOnScene::kType) { - ignition::gui::events::LeftClickOnScene *_e = - static_cast(_event); + gz::gui::events::LeftClickOnScene *_e = + static_cast(_event); this->dataPtr->mouseEvent = _e->Mouse(); if (this->dataPtr->mouseEvent.Button() == common::MouseEvent::LEFT && @@ -514,7 +514,7 @@ bool SelectEntities::eventFilter(QObject *_obj, QEvent *_event) } } } - else if (_event->type() == ignition::gui::events::Render::kType) + else if (_event->type() == gz::gui::events::Render::kType) { this->dataPtr->Initialize(); this->dataPtr->HandleEntitySelection(); @@ -569,16 +569,16 @@ bool SelectEntities::eventFilter(QObject *_obj, QEvent *_event) this->dataPtr->selectedEntities.clear(); } else if (_event->type() == - ignition::gui::events::SpawnFromDescription::kType || - _event->type() == ignition::gui::events::SpawnFromPath::kType) + gz::gui::events::SpawnFromDescription::kType || + _event->type() == gz::gui::events::SpawnFromPath::kType) { this->dataPtr->isSpawning = true; this->dataPtr->mouseDirty = true; } - else if (_event->type() == ignition::gui::events::KeyReleaseOnScene::kType) + else if (_event->type() == gz::gui::events::KeyReleaseOnScene::kType) { - ignition::gui::events::KeyReleaseOnScene *_e = - static_cast(_event); + gz::gui::events::KeyReleaseOnScene *_e = + static_cast(_event); if (_e->Key().Key() == Qt::Key_Escape) { this->dataPtr->mouseDirty = true; @@ -612,4 +612,4 @@ bool SelectEntities::eventFilter(QObject *_obj, QEvent *_event) // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::gui::SelectEntities, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/select_entities/SelectEntities.hh b/src/gui/plugins/select_entities/SelectEntities.hh index 6643ab539e..ff50a3e21a 100644 --- a/src/gui/plugins/select_entities/SelectEntities.hh +++ b/src/gui/plugins/select_entities/SelectEntities.hh @@ -32,7 +32,7 @@ namespace gui /// \brief This plugin is in charge of selecting and deselecting the entities /// from the Scene3D and emit the corresponding events. - class SelectEntities : public ignition::gui::Plugin + class SelectEntities : public gz::gui::Plugin { Q_OBJECT diff --git a/src/gui/plugins/shapes/Shapes.cc b/src/gui/plugins/shapes/Shapes.cc index 37c006a613..057bbd17cb 100644 --- a/src/gui/plugins/shapes/Shapes.cc +++ b/src/gui/plugins/shapes/Shapes.cc @@ -73,9 +73,9 @@ void Shapes::OnMode(const QString &_mode) if (!modelSdfString.empty()) { - ignition::gui::events::SpawnFromDescription event(modelSdfString); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::SpawnFromDescription event(modelSdfString); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); } } diff --git a/src/gui/plugins/spawn/Spawn.cc b/src/gui/plugins/spawn/Spawn.cc index cc33737aa4..ebf435d5b8 100644 --- a/src/gui/plugins/spawn/Spawn.cc +++ b/src/gui/plugins/spawn/Spawn.cc @@ -154,7 +154,7 @@ using namespace gazebo; ///////////////////////////////////////////////// Spawn::Spawn() - : ignition::gui::Plugin(), + : gz::gui::Plugin(), dataPtr(std::make_unique()) { } @@ -184,8 +184,8 @@ void Spawn::LoadConfig(const tinyxml2::XMLElement *) if (!worldNames.empty()) this->dataPtr->worldName = worldNames[0].toStdString(); - ignition::gui::App()->findChild - ()->installEventFilter(this); + gz::gui::App()->findChild + ()->installEventFilter(this); } ///////////////////////////////////////////////// @@ -477,63 +477,63 @@ bool SpawnPrivate::GeneratePreview(const std::string &_name) //////////////////////////////////////////////// bool Spawn::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { this->dataPtr->OnRender(); } - else if (_event->type() == ignition::gui::events::LeftClickOnScene::kType) + else if (_event->type() == gz::gui::events::LeftClickOnScene::kType) { - ignition::gui::events::LeftClickOnScene *_e = - static_cast(_event); + gz::gui::events::LeftClickOnScene *_e = + static_cast(_event); this->dataPtr->mouseEvent = _e->Mouse(); if (this->dataPtr->generatePreview || this->dataPtr->isPlacing) this->dataPtr->mouseDirty = true; } - else if (_event->type() == ignition::gui::events::HoverOnScene::kType) + else if (_event->type() == gz::gui::events::HoverOnScene::kType) { - ignition::gui::events::HoverOnScene *_e = - static_cast(_event); + gz::gui::events::HoverOnScene *_e = + static_cast(_event); this->dataPtr->mouseHoverPos = _e->Mouse().Pos(); this->dataPtr->hoverDirty = true; } else if (_event->type() == - ignition::gui::events::SpawnFromDescription::kType) + gz::gui::events::SpawnFromDescription::kType) { - ignition::gui::events::SpawnFromDescription *_e = - static_cast(_event); + gz::gui::events::SpawnFromDescription *_e = + static_cast(_event); this->dataPtr->spawnSdfString = _e->Description(); this->dataPtr->generatePreview = true; } - else if (_event->type() == ignition::gui::events::SpawnFromPath::kType) + else if (_event->type() == gz::gui::events::SpawnFromPath::kType) { auto spawnPreviewPathEvent = - reinterpret_cast(_event); + reinterpret_cast(_event); this->dataPtr->spawnSdfPath = spawnPreviewPathEvent->FilePath(); this->dataPtr->generatePreview = true; } - else if (_event->type() == ignition::gui::events::SpawnCloneFromName::kType) + else if (_event->type() == gz::gui::events::SpawnCloneFromName::kType) { auto spawnCloneEvent = - reinterpret_cast(_event); + reinterpret_cast(_event); if (spawnCloneEvent) { this->dataPtr->spawnCloneName = spawnCloneEvent->Name(); this->dataPtr->generatePreview = true; } } - else if (_event->type() == ignition::gui::events::KeyReleaseOnScene::kType) + else if (_event->type() == gz::gui::events::KeyReleaseOnScene::kType) { - ignition::gui::events::KeyReleaseOnScene *_e = - static_cast(_event); + gz::gui::events::KeyReleaseOnScene *_e = + static_cast(_event); if (_e->Key().Key() == Qt::Key_Escape) { this->dataPtr->escapeReleased = true; } } - else if (_event->type() == ignition::gui::events::DropOnScene::kType) + else if (_event->type() == gz::gui::events::DropOnScene::kType) { auto dropOnSceneEvent = - reinterpret_cast(_event); + reinterpret_cast(_event); if (dropOnSceneEvent) { this->OnDropped(dropOnSceneEvent); @@ -544,7 +544,7 @@ bool Spawn::eventFilter(QObject *_obj, QEvent *_event) } ///////////////////////////////////////////////// -void Spawn::OnDropped(const ignition::gui::events::DropOnScene *_event) +void Spawn::OnDropped(const gz::gui::events::DropOnScene *_event) { if (nullptr == _event || nullptr == this->dataPtr->camera || nullptr == this->dataPtr->rayQuery) @@ -647,4 +647,4 @@ void Spawn::SetErrorPopupText(const QString &_errorTxt) // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::Spawn, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/spawn/Spawn.hh b/src/gui/plugins/spawn/Spawn.hh index 43e5844919..fc7bb5d621 100644 --- a/src/gui/plugins/spawn/Spawn.hh +++ b/src/gui/plugins/spawn/Spawn.hh @@ -31,7 +31,7 @@ namespace gazebo /// \brief Allows to spawn models and lights using the spawn gui events or /// drag and drop. - class Spawn : public ignition::gui::Plugin + class Spawn : public gz::gui::Plugin { Q_OBJECT @@ -54,7 +54,7 @@ namespace gazebo /// \brief Handle drop events. /// \param[in] _event Event with drop information. - public: void OnDropped(const ignition::gui::events::DropOnScene *_event); + public: void OnDropped(const gz::gui::events::DropOnScene *_event); /// \brief Get the text for the popup error message /// \return The error text diff --git a/src/gui/plugins/transform_control/TransformControl.cc b/src/gui/plugins/transform_control/TransformControl.cc index 5f51340eac..bb7e77bf58 100644 --- a/src/gui/plugins/transform_control/TransformControl.cc +++ b/src/gui/plugins/transform_control/TransformControl.cc @@ -289,8 +289,8 @@ void TransformControl::OnMode(const QString &_mode) gazebo::gui::events::TransformControlModeActive transformControlModeActive(this->dataPtr->transformMode); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &transformControlModeActive); this->dataPtr->mouseDirty = true; } @@ -350,7 +350,7 @@ void TransformControl::LoadGrid() ///////////////////////////////////////////////// bool TransformControl::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { // This event is called in Scene3d's RenderThread, so it's safe to make // rendering calls here @@ -381,31 +381,31 @@ bool TransformControl::eventFilter(QObject *_obj, QEvent *_event) this->dataPtr->selectedEntities.clear(); } } - else if (_event->type() == ignition::gui::events::LeftClickOnScene::kType) + else if (_event->type() == gz::gui::events::LeftClickOnScene::kType) { - ignition::gui::events::LeftClickOnScene *_e = - static_cast(_event); + gz::gui::events::LeftClickOnScene *_e = + static_cast(_event); this->dataPtr->mouseEvent = _e->Mouse(); this->dataPtr->mouseDirty = true; } - else if (_event->type() == ignition::gui::events::MousePressOnScene::kType) + else if (_event->type() == gz::gui::events::MousePressOnScene::kType) { auto event = - static_cast(_event); + static_cast(_event); this->dataPtr->mouseEvent = event->Mouse(); this->dataPtr->mouseDirty = true; } - else if (_event->type() == ignition::gui::events::DragOnScene::kType) + else if (_event->type() == gz::gui::events::DragOnScene::kType) { auto event = - static_cast(_event); + static_cast(_event); this->dataPtr->mouseEvent = event->Mouse(); this->dataPtr->mouseDirty = true; } - else if (_event->type() == ignition::gui::events::KeyPressOnScene::kType) + else if (_event->type() == gz::gui::events::KeyPressOnScene::kType) { - ignition::gui::events::KeyPressOnScene *_e = - static_cast(_event); + gz::gui::events::KeyPressOnScene *_e = + static_cast(_event); this->dataPtr->keyEvent = _e->Key(); if (this->dataPtr->keyEvent.Key() == Qt::Key_T) @@ -417,10 +417,10 @@ bool TransformControl::eventFilter(QObject *_obj, QEvent *_event) this->activateRotate(); } } - else if (_event->type() == ignition::gui::events::KeyReleaseOnScene::kType) + else if (_event->type() == gz::gui::events::KeyReleaseOnScene::kType) { - ignition::gui::events::KeyReleaseOnScene *_e = - static_cast(_event); + gz::gui::events::KeyReleaseOnScene *_e = + static_cast(_event); this->dataPtr->keyEvent = _e->Key(); if (this->dataPtr->keyEvent.Key() == Qt::Key_Escape) { @@ -580,9 +580,9 @@ void TransformControlPrivate::HandleTransform() this->HandleMouseEvents(); - ignition::gui::events::BlockOrbit blockOrbitEvent(this->blockOrbit); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::BlockOrbit blockOrbitEvent(this->blockOrbit); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &blockOrbitEvent); } @@ -677,7 +677,7 @@ void TransformControlPrivate::HandleMouseEvents() if (this->poseCmdService.empty()) { std::string worldName; - auto worldNames = ignition::gui::worldNames(); + auto worldNames = gz::gui::worldNames(); if (!worldNames.empty()) worldName = worldNames[0].toStdString(); diff --git a/src/gui/plugins/video_recorder/VideoRecorder.cc b/src/gui/plugins/video_recorder/VideoRecorder.cc index 061e008b84..ab38e977ae 100644 --- a/src/gui/plugins/video_recorder/VideoRecorder.cc +++ b/src/gui/plugins/video_recorder/VideoRecorder.cc @@ -360,8 +360,8 @@ void VideoRecorder::LoadConfig(const tinyxml2::XMLElement * _pluginElem) << "MinimalScene." << std::endl; } - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); } ///////////////////////////////////////////////// diff --git a/src/gui/plugins/view_angle/ViewAngle.cc b/src/gui/plugins/view_angle/ViewAngle.cc index f3471ea3de..5c68056e93 100644 --- a/src/gui/plugins/view_angle/ViewAngle.cc +++ b/src/gui/plugins/view_angle/ViewAngle.cc @@ -199,14 +199,14 @@ void ViewAngle::LoadConfig(const tinyxml2::XMLElement *_pluginElem) ignmsg << "Move to model service on [" << this->dataPtr->moveToModelService << "]" << std::endl; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); } ///////////////////////////////////////////////// bool ViewAngle::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { this->dataPtr->OnRender(); diff --git a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc index 34305ecc5a..22938db16d 100644 --- a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc +++ b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc @@ -2854,14 +2854,14 @@ void VisualizationCapabilities::LoadConfig(const tinyxml2::XMLElement *) ignmsg << "View frames service on [" << this->dataPtr->viewFramesService << "]" << std::endl; - ignition::gui::App()->findChild - ()->installEventFilter(this); + gz::gui::App()->findChild + ()->installEventFilter(this); } //////////////////////////////////////////////// bool VisualizationCapabilities::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { this->dataPtr->OnRender(); } @@ -2871,4 +2871,4 @@ bool VisualizationCapabilities::eventFilter(QObject *_obj, QEvent *_event) // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::VisualizationCapabilities, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/visualize_contacts/VisualizeContacts.cc b/src/gui/plugins/visualize_contacts/VisualizeContacts.cc index 58b4339c4a..e7ddbc2833 100644 --- a/src/gui/plugins/visualize_contacts/VisualizeContacts.cc +++ b/src/gui/plugins/visualize_contacts/VisualizeContacts.cc @@ -311,4 +311,4 @@ void VisualizeContacts::UpdatePeriod(double _period) // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::VisualizeContacts, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/visualize_lidar/VisualizeLidar.cc b/src/gui/plugins/visualize_lidar/VisualizeLidar.cc index 1a1a0ea6a7..f76ad7d3cc 100644 --- a/src/gui/plugins/visualize_lidar/VisualizeLidar.cc +++ b/src/gui/plugins/visualize_lidar/VisualizeLidar.cc @@ -197,8 +197,8 @@ void VisualizeLidar::LoadLidar() scene->DestroyVisual(this->dataPtr->lidar); - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->removeEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->removeEventFilter(this); } else { @@ -214,14 +214,14 @@ void VisualizeLidar::LoadConfig(const tinyxml2::XMLElement *) if (this->title.empty()) this->title = "Visualize lidar"; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); } ///////////////////////////////////////////////// bool VisualizeLidar::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { // This event is called in Scene3d's RenderThread, so it's safe to make // rendering calls here @@ -526,4 +526,4 @@ QString VisualizeLidar::MinRange() const // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::VisualizeLidar, - ignition::gui::Plugin) + gz::gui::Plugin)