From 35199f4fb2718373bef0e1ef3456708d0dfc43a5 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 9 May 2022 14:57:32 -0700 Subject: [PATCH] Migrate sources in src, test, examples, and include Signed-off-by: methylDragon --- examples/plugin/command_actor/CommandActor.cc | 4 +- examples/plugin/command_actor/CommandActor.hh | 2 +- .../custom_component/CustomComponentPlugin.cc | 2 +- .../custom_component/CustomComponentPlugin.hh | 8 +- .../custom_sensor_system/OdometerSystem.cc | 24 ++-- .../custom_sensor_system/OdometerSystem.hh | 6 +- .../gui_system_plugin/GuiSystemPlugin.cc | 10 +- .../gui_system_plugin/GuiSystemPlugin.hh | 6 +- examples/plugin/hello_world/HelloWorld.cc | 4 +- examples/plugin/hello_world/HelloWorld.hh | 2 +- .../rendering_plugins/RenderingGuiPlugin.cc | 16 +-- .../rendering_plugins/RenderingGuiPlugin.hh | 6 +- .../RenderingServerPlugin.cc | 12 +- .../RenderingServerPlugin.hh | 4 +- examples/plugin/system_plugin/SampleSystem.cc | 2 +- examples/plugin/system_plugin/SampleSystem.hh | 2 +- .../plugin/system_plugin/SampleSystem2.cc | 2 +- examples/standalone/comms/publisher.cc | 4 +- .../standalone/custom_server/custom_server.cc | 4 +- examples/standalone/each_performance/each.cc | 10 +- .../entity_creation/entity_creation.cc | 4 +- .../standalone/external_ecm/external_ecm.cc | 10 +- .../standalone/gtest_setup/command_TEST.cc | 20 +-- .../standalone/gtest_setup/gravity_TEST.cc | 12 +- .../standalone/joy_to_twist/joy_to_twist.cc | 2 +- examples/standalone/joystick/joystick.cc | 4 +- examples/standalone/keyboard/keyboard.cc | 6 +- .../standalone/light_control/light_control.cc | 8 +- .../multi_lrauv_race/multi_lrauv_race.cc | 4 +- .../scene_requester/scene_requester.cc | 4 +- include/gz/sim/Conversions.hh | 48 +++---- include/gz/sim/Entity.hh | 8 +- include/gz/sim/EntityComponentManager.hh | 26 ++-- include/gz/sim/EventManager.hh | 16 +-- include/gz/sim/Events.hh | 12 +- include/gz/sim/Link.hh | 22 ++-- include/gz/sim/Model.hh | 16 +-- include/gz/sim/Primitives.hh | 10 +- include/gz/sim/SdfEntityCreator.hh | 14 +- include/gz/sim/Server.hh | 16 +-- include/gz/sim/ServerConfig.hh | 16 +-- include/gz/sim/System.hh | 24 ++-- include/gz/sim/SystemLoader.hh | 14 +- include/gz/sim/SystemPluginPtr.hh | 8 +- include/gz/sim/TestFixture.hh | 12 +- include/gz/sim/Types.hh | 6 +- include/gz/sim/Util.hh | 16 +-- include/gz/sim/World.hh | 18 +-- include/gz/sim/comms/Broker.hh | 10 +- include/gz/sim/comms/ICommsModel.hh | 12 +- include/gz/sim/comms/MsgManager.hh | 14 +- include/gz/sim/components/Actor.hh | 22 ++-- include/gz/sim/components/Actuators.hh | 16 +-- .../gz/sim/components/AirPressureSensor.hh | 14 +- include/gz/sim/components/Altimeter.hh | 14 +- .../gz/sim/components/AngularAcceleration.hh | 18 +-- include/gz/sim/components/AngularVelocity.hh | 18 +-- .../gz/sim/components/AngularVelocityCmd.hh | 16 +-- include/gz/sim/components/Atmosphere.hh | 16 +-- include/gz/sim/components/AxisAlignedBox.hh | 20 +-- include/gz/sim/components/BatterySoC.hh | 12 +- include/gz/sim/components/Camera.hh | 14 +- include/gz/sim/components/CanonicalLink.hh | 16 +-- include/gz/sim/components/CastShadows.hh | 12 +- include/gz/sim/components/CenterOfVolume.hh | 14 +- include/gz/sim/components/ChildLinkName.hh | 14 +- include/gz/sim/components/Collision.hh | 18 +-- include/gz/sim/components/Component.hh | 12 +- include/gz/sim/components/ContactSensor.hh | 12 +- .../gz/sim/components/ContactSensorData.hh | 18 +-- include/gz/sim/components/CustomSensor.hh | 14 +- include/gz/sim/components/DepthCamera.hh | 14 +- include/gz/sim/components/DetachableJoint.hh | 14 +- .../sim/components/ExternalWorldWrenchCmd.hh | 16 +-- include/gz/sim/components/Factory.hh | 24 ++-- include/gz/sim/components/ForceTorque.hh | 16 +-- include/gz/sim/components/Geometry.hh | 18 +-- include/gz/sim/components/GpuLidar.hh | 14 +- include/gz/sim/components/Gravity.hh | 16 +-- include/gz/sim/components/HaltMotion.hh | 12 +- include/gz/sim/components/Imu.hh | 16 +-- include/gz/sim/components/Inertial.hh | 20 +-- include/gz/sim/components/Joint.hh | 12 +- include/gz/sim/components/JointAxis.hh | 18 +-- .../gz/sim/components/JointEffortLimitsCmd.hh | 18 +-- include/gz/sim/components/JointForce.hh | 14 +- include/gz/sim/components/JointForceCmd.hh | 12 +- include/gz/sim/components/JointPosition.hh | 14 +- .../sim/components/JointPositionLimitsCmd.hh | 18 +-- .../gz/sim/components/JointPositionReset.hh | 14 +- .../sim/components/JointTransmittedWrench.hh | 16 +-- include/gz/sim/components/JointType.hh | 12 +- include/gz/sim/components/JointVelocity.hh | 16 +-- include/gz/sim/components/JointVelocityCmd.hh | 16 +-- .../sim/components/JointVelocityLimitsCmd.hh | 18 +-- .../gz/sim/components/JointVelocityReset.hh | 14 +- include/gz/sim/components/LaserRetro.hh | 12 +- include/gz/sim/components/Level.hh | 16 +-- include/gz/sim/components/LevelBuffer.hh | 14 +- include/gz/sim/components/LevelEntityNames.hh | 14 +- include/gz/sim/components/Lidar.hh | 14 +- include/gz/sim/components/Light.hh | 18 +-- include/gz/sim/components/LightCmd.hh | 18 +-- include/gz/sim/components/LightType.hh | 14 +- .../gz/sim/components/LinearAcceleration.hh | 18 +-- include/gz/sim/components/LinearVelocity.hh | 16 +-- .../gz/sim/components/LinearVelocityCmd.hh | 16 +-- .../gz/sim/components/LinearVelocitySeed.hh | 16 +-- include/gz/sim/components/Link.hh | 12 +- .../sim/components/LogPlaybackStatistics.hh | 18 +-- include/gz/sim/components/LogicalAudio.hh | 16 +-- include/gz/sim/components/LogicalCamera.hh | 12 +- include/gz/sim/components/MagneticField.hh | 16 +-- include/gz/sim/components/Magnetometer.hh | 16 +-- include/gz/sim/components/Material.hh | 16 +-- include/gz/sim/components/Model.hh | 14 +- include/gz/sim/components/Name.hh | 14 +- include/gz/sim/components/NavSat.hh | 16 +-- include/gz/sim/components/ParentEntity.hh | 14 +- include/gz/sim/components/ParentLinkName.hh | 14 +- include/gz/sim/components/ParticleEmitter.hh | 18 +-- include/gz/sim/components/Performer.hh | 14 +- .../gz/sim/components/PerformerAffinity.hh | 16 +-- include/gz/sim/components/PerformerLevels.hh | 16 +-- include/gz/sim/components/Physics.hh | 24 ++-- include/gz/sim/components/PhysicsCmd.hh | 16 +-- .../gz/sim/components/PhysicsEnginePlugin.hh | 14 +- include/gz/sim/components/Pose.hh | 18 +-- include/gz/sim/components/PoseCmd.hh | 16 +-- include/gz/sim/components/Recreate.hh | 12 +- .../sim/components/RenderEngineGuiPlugin.hh | 14 +- .../components/RenderEngineServerHeadless.hh | 14 +- .../components/RenderEngineServerPlugin.hh | 14 +- include/gz/sim/components/RgbdCamera.hh | 14 +- include/gz/sim/components/Scene.hh | 18 +-- .../gz/sim/components/SegmentationCamera.hh | 14 +- include/gz/sim/components/SelfCollide.hh | 12 +- include/gz/sim/components/SemanticLabel.hh | 14 +- include/gz/sim/components/Sensor.hh | 16 +-- include/gz/sim/components/Serialization.hh | 10 +- .../gz/sim/components/SlipComplianceCmd.hh | 14 +- include/gz/sim/components/SourceFilePath.hh | 14 +- .../gz/sim/components/SphericalCoordinates.hh | 18 +-- include/gz/sim/components/Static.hh | 12 +- include/gz/sim/components/Temperature.hh | 16 +-- include/gz/sim/components/TemperatureRange.hh | 14 +- include/gz/sim/components/ThermalCamera.hh | 14 +- include/gz/sim/components/ThreadPitch.hh | 12 +- include/gz/sim/components/Transparency.hh | 12 +- include/gz/sim/components/Visibility.hh | 14 +- include/gz/sim/components/Visual.hh | 14 +- include/gz/sim/components/VisualCmd.hh | 18 +-- include/gz/sim/components/Volume.hh | 12 +- include/gz/sim/components/WheelSlipCmd.hh | 18 +-- include/gz/sim/components/WideAngleCamera.hh | 14 +- include/gz/sim/components/Wind.hh | 12 +- include/gz/sim/components/WindMode.hh | 12 +- include/gz/sim/components/World.hh | 14 +- include/gz/sim/detail/BaseView.hh | 10 +- include/gz/sim/detail/ComponentStorageBase.hh | 6 +- .../gz/sim/detail/EntityComponentManager.hh | 8 +- include/gz/sim/detail/View.hh | 14 +- include/gz/sim/gui/Gui.hh | 16 +-- include/gz/sim/gui/GuiEvents.hh | 16 +-- include/gz/sim/gui/GuiSystem.hh | 12 +- include/gz/sim/physics/Events.hh | 14 +- include/gz/sim/rendering/Events.hh | 10 +- include/gz/sim/rendering/MarkerManager.hh | 8 +- include/gz/sim/rendering/RenderUtil.hh | 16 +-- include/gz/sim/rendering/SceneManager.hh | 20 +-- include/gz/sim/sim.hh.in | 2 +- src/Barrier.hh | 4 +- src/BaseView.cc | 6 +- src/BaseView_TEST.cc | 14 +- src/ComponentFactory_TEST.cc | 10 +- src/Component_TEST.cc | 8 +- src/Conversions.cc | 6 +- src/Conversions_TEST.cc | 2 +- src/EntityComponentManager.cc | 24 ++-- src/EntityComponentManagerDiff.cc | 2 +- src/EntityComponentManagerDiff.hh | 6 +- src/EntityComponentManager_TEST.cc | 22 ++-- src/EventManager_TEST.cc | 4 +- src/LevelManager.cc | 58 ++++----- src/LevelManager.hh | 8 +- src/Link.cc | 42 +++--- src/Link_TEST.cc | 2 +- src/Model.cc | 22 ++-- src/ModelCommandAPI_TEST.cc | 4 +- src/Model_TEST.cc | 12 +- src/Primitives.cc | 2 +- src/Primitives_TEST.cc | 2 +- src/SdfEntityCreator.cc | 120 +++++++++--------- src/SdfEntityCreator_TEST.cc | 50 ++++---- src/SdfGenerator.cc | 66 +++++----- src/SdfGenerator.hh | 2 +- src/SdfGenerator_TEST.cc | 26 ++-- src/Server.cc | 6 +- src/ServerConfig.cc | 4 +- src/ServerConfig_TEST.cc | 6 +- src/ServerPrivate.cc | 2 +- src/ServerPrivate.hh | 8 +- src/Server_TEST.cc | 22 ++-- src/SimulationRunner.cc | 24 ++-- src/SimulationRunner.hh | 16 +-- src/SimulationRunner_TEST.cc | 48 +++---- src/SystemInternal.hh | 6 +- src/SystemLoader.cc | 6 +- src/SystemLoader_TEST.cc | 6 +- src/SystemManager.hh | 10 +- src/SystemManager_TEST.cc | 10 +- src/System_TEST.cc | 2 +- src/TestFixture.cc | 6 +- src/TestFixture_TEST.cc | 8 +- src/Util.cc | 32 ++--- src/Util_TEST.cc | 28 ++-- src/View.cc | 2 +- src/World.cc | 22 ++-- src/WorldControl.hh | 2 +- src/World_TEST.cc | 2 +- src/cmd/ModelCommandAPI.cc | 42 +++--- src/cmd/cmdgazebo.rb.in | 2 +- src/cmd/ign.cc | 10 +- src/comms/Broker.cc | 8 +- src/comms/Broker_TEST.cc | 4 +- src/comms/ICommsModel.cc | 10 +- src/comms/MsgManager.cc | 4 +- src/comms/MsgManager_TEST.cc | 2 +- src/gui/AboutDialogHandler.hh | 4 +- src/gui/Gui.cc | 8 +- src/gui/GuiEvents.cc | 2 +- src/gui/GuiEvents_TEST.cc | 4 +- src/gui/GuiFileHandler.hh | 4 +- src/gui/GuiRunner.cc | 12 +- src/gui/GuiRunner.hh | 6 +- src/gui/Gui_TEST.cc | 4 +- src/gui/Gui_clean_exit_TEST.cc | 6 +- src/gui/PathManager.cc | 2 +- src/gui/PathManager.hh | 4 +- src/gui/plugins/align_tool/AlignTool.cc | 10 +- src/gui/plugins/align_tool/AlignTool.hh | 2 +- .../banana_for_scale/BananaForScale.cc | 2 +- .../component_inspector/ComponentInspector.cc | 90 ++++++------- .../component_inspector/ComponentInspector.hh | 6 +- .../ComponentInspector.qml | 4 +- src/gui/plugins/component_inspector/Pose3d.hh | 6 +- src/gui/plugins/component_inspector/Types.hh | 2 +- .../component_inspector_editor/AirPressure.cc | 4 +- .../component_inspector_editor/Altimeter.cc | 2 +- .../ComponentInspectorEditor.cc | 96 +++++++------- .../ComponentInspectorEditor.hh | 6 +- .../ComponentInspectorEditor.qml | 4 +- .../plugins/component_inspector_editor/Imu.cc | 4 +- .../component_inspector_editor/JointType.cc | 8 +- .../component_inspector_editor/Lidar.cc | 4 +- .../Magnetometer.cc | 2 +- .../component_inspector_editor/ModelEditor.cc | 18 +-- .../component_inspector_editor/ModelEditor.hh | 2 +- .../component_inspector_editor/Pose3d.cc | 8 +- .../component_inspector_editor/Types.hh | 2 +- src/gui/plugins/copy_paste/CopyPaste.cc | 4 +- src/gui/plugins/copy_paste/CopyPaste.hh | 2 +- .../EntityContextMenuPlugin.qml | 4 +- src/gui/plugins/entity_tree/EntityTree.cc | 34 ++--- src/gui/plugins/entity_tree/EntityTree.hh | 4 +- src/gui/plugins/entity_tree/EntityTree.qml | 6 +- .../JointPositionController.cc | 18 +-- .../JointPositionController.hh | 4 +- .../JointPositionController_TEST.cc | 18 +-- src/gui/plugins/lights/Lights.cc | 4 +- src/gui/plugins/modules/EntityContextMenu.cc | 4 +- src/gui/plugins/modules/EntityContextMenu.hh | 6 +- src/gui/plugins/modules/EntityContextMenu.qml | 4 +- src/gui/plugins/modules/EntityContextMenu.qrc | 2 +- src/gui/plugins/modules/qmldir | 6 +- .../playback_scrubber/PlaybackScrubber.cc | 4 +- .../playback_scrubber/PlaybackScrubber.hh | 2 +- src/gui/plugins/plot_3d/Plot3D.cc | 10 +- src/gui/plugins/plot_3d/Plot3D.hh | 2 +- src/gui/plugins/plot_3d/Plot3D_TEST.cc | 18 +-- src/gui/plugins/plotting/Plotting.cc | 38 +++--- src/gui/plugins/plotting/Plotting.hh | 2 +- .../resource_spawner/ResourceSpawner.cc | 2 +- src/gui/plugins/scene3d/GzScene3D.qml | 4 +- src/gui/plugins/scene3d/Scene3D.cc | 12 +- src/gui/plugins/scene3d/Scene3D.hh | 2 +- .../plugins/scene_manager/GzSceneManager.cc | 12 +- .../plugins/scene_manager/GzSceneManager.hh | 2 +- .../plugins/select_entities/SelectEntities.cc | 8 +- src/gui/plugins/shapes/Shapes.cc | 2 +- src/gui/plugins/spawn/Spawn.cc | 4 +- .../transform_control/TransformControl.cc | 2 +- .../plugins/video_recorder/VideoRecorder.hh | 2 +- src/gui/plugins/view_angle/ViewAngle.cc | 4 +- .../VisualizationCapabilities.cc | 46 +++---- .../VisualizationCapabilities.hh | 2 +- .../visualize_contacts/VisualizeContacts.cc | 16 +-- .../visualize_contacts/VisualizeContacts.hh | 2 +- .../plugins/visualize_lidar/VisualizeLidar.cc | 22 ++-- .../plugins/visualize_lidar/VisualizeLidar.hh | 2 +- src/ign.cc | 8 +- src/ign.hh | 2 +- src/ign_TEST.cc | 2 +- src/network/NetworkConfig.hh | 6 +- src/network/NetworkManager.cc | 2 +- src/network/NetworkManager.hh | 8 +- src/network/NetworkManagerPrimary.cc | 12 +- src/network/NetworkManagerPrimary.hh | 8 +- src/network/NetworkManagerPrivate.hh | 6 +- src/network/NetworkManagerSecondary.cc | 10 +- src/network/NetworkManagerSecondary.hh | 6 +- src/network/NetworkManager_TEST.cc | 2 +- src/network/NetworkRole.hh | 4 +- src/network/PeerInfo.hh | 4 +- src/network/PeerTracker.hh | 6 +- src/network/PeerTracker_TEST.cc | 2 +- src/rendering/MarkerManager.cc | 6 +- src/rendering/RenderUtil.cc | 90 ++++++------- src/rendering/SceneManager.cc | 6 +- .../ackermann_steering/AckermannSteering.cc | 12 +- .../ackermann_steering/AckermannSteering.hh | 2 +- .../ackermann_steering/SpeedLimiter.hh | 2 +- src/systems/air_pressure/AirPressure.cc | 14 +- src/systems/air_pressure/AirPressure.hh | 6 +- src/systems/altimeter/Altimeter.cc | 18 +-- src/systems/altimeter/Altimeter.hh | 6 +- .../apply_joint_force/ApplyJointForce.cc | 6 +- .../apply_joint_force/ApplyJointForce.hh | 2 +- .../battery_plugin/LinearBatteryPlugin.cc | 16 +-- .../battery_plugin/LinearBatteryPlugin.hh | 2 +- src/systems/breadcrumbs/Breadcrumbs.cc | 22 ++-- src/systems/breadcrumbs/Breadcrumbs.hh | 6 +- src/systems/buoyancy/Buoyancy.cc | 24 ++-- src/systems/buoyancy/Buoyancy.hh | 2 +- src/systems/buoyancy_engine/BuoyancyEngine.cc | 8 +- src/systems/buoyancy_engine/BuoyancyEngine.hh | 2 +- .../CameraVideoRecorder.cc | 26 ++-- .../CameraVideoRecorder.hh | 6 +- .../ColladaWorldExporter.cc | 26 ++-- .../ColladaWorldExporter.hh | 2 +- src/systems/comms_endpoint/CommsEndpoint.cc | 4 +- src/systems/comms_endpoint/CommsEndpoint.hh | 2 +- src/systems/contact/Contact.cc | 18 +-- src/systems/contact/Contact.hh | 4 +- .../detachable_joint/DetachableJoint.cc | 16 +-- .../detachable_joint/DetachableJoint.hh | 4 +- src/systems/diff_drive/DiffDrive.cc | 12 +- src/systems/diff_drive/DiffDrive.hh | 2 +- src/systems/elevator/Elevator.cc | 16 +-- src/systems/elevator/Elevator.hh | 2 +- src/systems/elevator/ElevatorStateMachine.hh | 2 +- src/systems/elevator/utils/DoorTimer.hh | 2 +- src/systems/elevator/utils/JointMonitor.cc | 4 +- src/systems/elevator/utils/JointMonitor.hh | 2 +- src/systems/follow_actor/FollowActor.cc | 10 +- src/systems/follow_actor/FollowActor.hh | 6 +- src/systems/force_torque/ForceTorque.cc | 26 ++-- src/systems/force_torque/ForceTorque.hh | 6 +- src/systems/hydrodynamics/Hydrodynamics.cc | 16 +-- src/systems/hydrodynamics/Hydrodynamics.hh | 2 +- src/systems/imu/Imu.cc | 24 ++-- src/systems/imu/Imu.hh | 6 +- .../joint_controller/JointController.cc | 8 +- .../joint_controller/JointController.hh | 2 +- .../JointPositionController.cc | 8 +- .../JointPositionController.hh | 2 +- .../JointStatePublisher.cc | 22 ++-- .../JointStatePublisher.hh | 4 +- .../JointTrajectoryController.cc | 16 +-- .../JointTrajectoryController.hh | 2 +- .../KineticEnergyMonitor.cc | 22 ++-- .../KineticEnergyMonitor.hh | 6 +- src/systems/label/Label.cc | 12 +- src/systems/label/Label.hh | 4 +- src/systems/lift_drag/LiftDrag.cc | 26 ++-- src/systems/lift_drag/LiftDrag.hh | 2 +- src/systems/log/LogPlayback.cc | 18 +-- src/systems/log/LogPlayback.hh | 6 +- src/systems/log/LogRecord.cc | 22 ++-- src/systems/log/LogRecord.hh | 6 +- .../log_video_recorder/LogVideoRecorder.cc | 16 +-- .../log_video_recorder/LogVideoRecorder.hh | 6 +- .../LogicalAudio.hh | 6 +- .../LogicalAudioSensorPlugin.cc | 16 +-- .../LogicalAudioSensorPlugin.hh | 2 +- src/systems/logical_camera/LogicalCamera.cc | 18 +-- src/systems/logical_camera/LogicalCamera.hh | 6 +- src/systems/magnetometer/Magnetometer.cc | 18 +-- src/systems/magnetometer/Magnetometer.hh | 4 +- src/systems/mecanum_drive/MecanumDrive.cc | 12 +- src/systems/mecanum_drive/MecanumDrive.hh | 2 +- .../model_photo_shoot/ModelPhotoShoot.cc | 20 +-- .../model_photo_shoot/ModelPhotoShoot.hh | 2 +- src/systems/multicopter_control/Common.cc | 18 +-- src/systems/multicopter_control/Common.hh | 6 +- .../LeeVelocityController.hh | 2 +- .../MulticopterVelocityControl.cc | 16 +-- .../MulticopterVelocityControl.hh | 6 +- src/systems/multicopter_control/Parameters.hh | 2 +- .../MulticopterMotorModel.cc | 22 ++-- .../MulticopterMotorModel.hh | 2 +- src/systems/navsat/NavSat.cc | 14 +- src/systems/navsat/NavSat.hh | 6 +- .../odometry_publisher/OdometryPublisher.cc | 8 +- .../odometry_publisher/OdometryPublisher.hh | 2 +- .../OpticalTactilePlugin.cc | 22 ++-- .../OpticalTactilePlugin.hh | 2 +- .../optical_tactile_plugin/Visualization.hh | 6 +- .../particle_emitter/ParticleEmitter.cc | 10 +- .../particle_emitter/ParticleEmitter.hh | 2 +- .../particle_emitter2/ParticleEmitter2.cc | 10 +- .../particle_emitter2/ParticleEmitter2.hh | 2 +- src/systems/perfect_comms/PerfectComms.cc | 6 +- src/systems/perfect_comms/PerfectComms.hh | 4 +- .../performer_detector/PerformerDetector.cc | 16 +-- .../performer_detector/PerformerDetector.hh | 4 +- .../physics/CanonicalLinkModelTracker.hh | 10 +- src/systems/physics/EntityFeatureMap.hh | 2 +- src/systems/physics/EntityFeatureMap_TEST.cc | 2 +- src/systems/physics/Physics.cc | 100 +++++++-------- src/systems/physics/Physics.hh | 6 +- src/systems/pose_publisher/PosePublisher.cc | 32 ++--- src/systems/pose_publisher/PosePublisher.hh | 4 +- src/systems/rf_comms/RFComms.cc | 10 +- src/systems/rf_comms/RFComms.hh | 4 +- .../scene_broadcaster/SceneBroadcaster.cc | 54 ++++---- .../scene_broadcaster/SceneBroadcaster.hh | 6 +- src/systems/sensors/Sensors.cc | 36 +++--- src/systems/sensors/Sensors.hh | 6 +- src/systems/shader_param/ShaderParam.cc | 10 +- src/systems/shader_param/ShaderParam.hh | 2 +- src/systems/thermal/Thermal.cc | 14 +- src/systems/thermal/Thermal.hh | 4 +- src/systems/thermal/ThermalSensor.cc | 10 +- src/systems/thermal/ThermalSensor.hh | 6 +- src/systems/thruster/Thruster.cc | 20 +-- src/systems/thruster/Thruster.hh | 2 +- src/systems/touch_plugin/TouchPlugin.cc | 18 +-- src/systems/touch_plugin/TouchPlugin.hh | 2 +- .../track_controller/TrackController.cc | 12 +- .../track_controller/TrackController.hh | 4 +- src/systems/tracked_vehicle/TrackedVehicle.cc | 10 +- src/systems/tracked_vehicle/TrackedVehicle.hh | 2 +- .../trajectory_follower/TrajectoryFollower.cc | 10 +- .../trajectory_follower/TrajectoryFollower.hh | 2 +- .../triggered_publisher/TriggeredPublisher.hh | 2 +- src/systems/user_commands/UserCommands.cc | 50 ++++---- src/systems/user_commands/UserCommands.hh | 4 +- .../velocity_control/VelocityControl.cc | 8 +- .../velocity_control/VelocityControl.hh | 2 +- src/systems/wheel_slip/WheelSlip.cc | 18 +-- src/systems/wheel_slip/WheelSlip.hh | 2 +- src/systems/wind_effects/WindEffects.cc | 30 ++--- src/systems/wind_effects/WindEffects.hh | 4 +- test/helpers/EnvTestFixture.hh | 2 +- test/helpers/Relay.hh | 2 +- test/helpers/UniqueTestDirectoryEnv.hh | 2 +- test/integration/ModelPhotoShootTest.hh | 2 +- test/integration/ackermann_steering_system.cc | 2 +- test/integration/air_pressure_system.cc | 2 +- test/integration/altimeter_system.cc | 2 +- test/integration/apply_joint_force_system.cc | 2 +- test/integration/battery_plugin.cc | 2 +- test/integration/breadcrumbs.cc | 2 +- test/integration/buoyancy.cc | 2 +- test/integration/buoyancy_engine.cc | 2 +- test/integration/camera_sensor_background.cc | 2 +- .../integration/camera_video_record_system.cc | 2 +- test/integration/collada_world_exporter.cc | 2 +- test/integration/components.cc | 2 +- test/integration/contact_system.cc | 2 +- test/integration/depth_camera.cc | 2 +- test/integration/detachable_joint.cc | 2 +- test/integration/diff_drive_system.cc | 2 +- test/integration/distortion_camera.cc | 2 +- test/integration/each_new_removed.cc | 2 +- test/integration/elevator_system.cc | 2 +- test/integration/entity_erase.cc | 2 +- test/integration/events.cc | 2 +- test/integration/examples_build.cc | 2 +- test/integration/follow_actor_system.cc | 2 +- test/integration/force_torque_system.cc | 2 +- test/integration/gpu_lidar.cc | 2 +- test/integration/halt_motion.cc | 2 +- test/integration/imu_system.cc | 2 +- test/integration/joint_controller_system.cc | 2 +- .../joint_position_controller_system.cc | 2 +- .../joint_state_publisher_system.cc | 2 +- .../joint_trajectory_controller_system.cc | 2 +- .../kinetic_energy_monitor_system.cc | 2 +- test/integration/level_manager.cc | 2 +- .../level_manager_runtime_performers.cc | 2 +- test/integration/lift_drag_system.cc | 2 +- test/integration/log_system.cc | 2 +- .../logical_audio_sensor_plugin.cc | 2 +- test/integration/logical_camera_system.cc | 2 +- test/integration/magnetometer_system.cc | 2 +- test/integration/multicopter.cc | 2 +- test/integration/navsat_system.cc | 2 +- test/integration/nested_model_physics.cc | 2 +- test/integration/network_handshake.cc | 2 +- test/integration/odometry_publisher.cc | 2 +- test/integration/optical_tactile_plugin.cc | 2 +- test/integration/particle_emitter.cc | 2 +- test/integration/perfect_comms.cc | 2 +- test/integration/performer_detector.cc | 2 +- test/integration/physics_system.cc | 2 +- test/integration/play_pause.cc | 2 +- test/integration/pose_publisher_system.cc | 2 +- test/integration/recreate_entities.cc | 2 +- test/integration/rf_comms.cc | 2 +- test/integration/rgbd_camera.cc | 2 +- test/integration/save_world.cc | 2 +- test/integration/scene_broadcaster_system.cc | 2 +- test/integration/sdf_frame_semantics.cc | 2 +- test/integration/sdf_include.cc | 2 +- test/integration/sensors_system.cc | 2 +- test/integration/sensors_system_battery.cc | 2 +- test/integration/shader_param_system.cc | 2 +- test/integration/spherical_coordinates.cc | 2 +- test/integration/thermal_sensor_system.cc | 2 +- test/integration/thermal_system.cc | 2 +- test/integration/thruster.cc | 2 +- test/integration/touch_plugin.cc | 2 +- test/integration/tracked_vehicle_system.cc | 2 +- test/integration/triggered_publisher.cc | 2 +- test/integration/user_commands.cc | 2 +- test/integration/velocity_control_system.cc | 2 +- test/integration/wheel_slip.cc | 2 +- test/integration/wide_angle_camera.cc | 2 +- test/integration/wind_effects.cc | 2 +- test/integration/world_control_state.cc | 2 +- test/performance/level_manager.cc | 2 +- test/performance/sdf_runner.cc | 2 +- 534 files changed, 2826 insertions(+), 2826 deletions(-) diff --git a/examples/plugin/command_actor/CommandActor.cc b/examples/plugin/command_actor/CommandActor.cc index 82ad0d2150d..20d02527dc5 100644 --- a/examples/plugin/command_actor/CommandActor.cc +++ b/examples/plugin/command_actor/CommandActor.cc @@ -16,8 +16,8 @@ */ #include "CommandActor.hh" -#include -#include +#include +#include IGNITION_ADD_PLUGIN( command_actor::CommandActor, diff --git a/examples/plugin/command_actor/CommandActor.hh b/examples/plugin/command_actor/CommandActor.hh index feeab87f166..3e989a08404 100644 --- a/examples/plugin/command_actor/CommandActor.hh +++ b/examples/plugin/command_actor/CommandActor.hh @@ -18,7 +18,7 @@ #define SYSTEM_PLUGIN_COMMANDACTOR_HH_ #include -#include +#include namespace command_actor { diff --git a/examples/plugin/custom_component/CustomComponentPlugin.cc b/examples/plugin/custom_component/CustomComponentPlugin.cc index 7896ea30888..70240785e66 100644 --- a/examples/plugin/custom_component/CustomComponentPlugin.cc +++ b/examples/plugin/custom_component/CustomComponentPlugin.cc @@ -16,7 +16,7 @@ */ #include "CustomComponentPlugin.hh" -#include +#include IGNITION_ADD_PLUGIN(examples::CustomComponentPlugin, ignition::gazebo::System, diff --git a/examples/plugin/custom_component/CustomComponentPlugin.hh b/examples/plugin/custom_component/CustomComponentPlugin.hh index 1ae04b2453c..ed2483ba2a7 100644 --- a/examples/plugin/custom_component/CustomComponentPlugin.hh +++ b/examples/plugin/custom_component/CustomComponentPlugin.hh @@ -18,13 +18,13 @@ #define EXAMPLES_PLUGINS_CUSTOMCOMPONENTPLUGIN_HH_ // This header provides components::Component -#include +#include // This header provides the registration macro -#include +#include -#include -#include +#include +#include namespace examples { diff --git a/examples/plugin/custom_sensor_system/OdometerSystem.cc b/examples/plugin/custom_sensor_system/OdometerSystem.cc index 3da7b2b3353..893666ec303 100644 --- a/examples/plugin/custom_sensor_system/OdometerSystem.cc +++ b/examples/plugin/custom_sensor_system/OdometerSystem.cc @@ -15,26 +15,26 @@ * */ -#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 "Odometer.hh" #include "OdometerSystem.hh" diff --git a/examples/plugin/custom_sensor_system/OdometerSystem.hh b/examples/plugin/custom_sensor_system/OdometerSystem.hh index 63bdcec04b8..0e4044433b2 100644 --- a/examples/plugin/custom_sensor_system/OdometerSystem.hh +++ b/examples/plugin/custom_sensor_system/OdometerSystem.hh @@ -17,9 +17,9 @@ #ifndef ODOMETERSYSTEM_HH_ #define ODOMETERSYSTEM_HH_ -#include -#include -#include +#include +#include +#include namespace custom { diff --git a/examples/plugin/gui_system_plugin/GuiSystemPlugin.cc b/examples/plugin/gui_system_plugin/GuiSystemPlugin.cc index e1abf119ce2..b4de66bc4c2 100644 --- a/examples/plugin/gui_system_plugin/GuiSystemPlugin.cc +++ b/examples/plugin/gui_system_plugin/GuiSystemPlugin.cc @@ -15,11 +15,11 @@ * */ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include "GuiSystemPlugin.hh" diff --git a/examples/plugin/gui_system_plugin/GuiSystemPlugin.hh b/examples/plugin/gui_system_plugin/GuiSystemPlugin.hh index c9ff0826f15..c0bd0e47957 100644 --- a/examples/plugin/gui_system_plugin/GuiSystemPlugin.hh +++ b/examples/plugin/gui_system_plugin/GuiSystemPlugin.hh @@ -15,10 +15,10 @@ * */ -#ifndef IGNITION_GAZEBO_GUISYSTEMPLUGIN_HH_ -#define IGNITION_GAZEBO_GUISYSTEMPLUGIN_HH_ +#ifndef GZ_GAZEBO_GUISYSTEMPLUGIN_HH_ +#define GZ_GAZEBO_GUISYSTEMPLUGIN_HH_ -#include +#include /// \brief Example of a GUI plugin that has access to entities and components. class GuiSystemPlugin : public ignition::gazebo::GuiSystem diff --git a/examples/plugin/hello_world/HelloWorld.cc b/examples/plugin/hello_world/HelloWorld.cc index d73ed28b6c3..ed361a72aa1 100644 --- a/examples/plugin/hello_world/HelloWorld.cc +++ b/examples/plugin/hello_world/HelloWorld.cc @@ -18,11 +18,11 @@ // We'll use a string and the ignmsg command below for a brief example. // Remove these includes if your plugin doesn't need them. #include -#include +#include // This header is required to register plugins. It's good practice to place it // in the cc file, like it's done here. -#include +#include // Don't forget to include the plugin's header. #include "HelloWorld.hh" diff --git a/examples/plugin/hello_world/HelloWorld.hh b/examples/plugin/hello_world/HelloWorld.hh index ff60e093924..536e706eca3 100644 --- a/examples/plugin/hello_world/HelloWorld.hh +++ b/examples/plugin/hello_world/HelloWorld.hh @@ -20,7 +20,7 @@ // The only required include in the header is this one. // All others will depend on what your plugin does. -#include +#include // It's good practice to use a custom namespace for your project. namespace hello_world diff --git a/examples/plugin/rendering_plugins/RenderingGuiPlugin.cc b/examples/plugin/rendering_plugins/RenderingGuiPlugin.cc index e0c629f09b2..201466ca79c 100644 --- a/examples/plugin/rendering_plugins/RenderingGuiPlugin.cc +++ b/examples/plugin/rendering_plugins/RenderingGuiPlugin.cc @@ -15,16 +15,16 @@ * */ -#include +#include //! [includeGuiEvents] -#include +#include //! [includeGuiEvents] -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include "RenderingGuiPlugin.hh" diff --git a/examples/plugin/rendering_plugins/RenderingGuiPlugin.hh b/examples/plugin/rendering_plugins/RenderingGuiPlugin.hh index 7958c38b07c..c79ebdbd36a 100644 --- a/examples/plugin/rendering_plugins/RenderingGuiPlugin.hh +++ b/examples/plugin/rendering_plugins/RenderingGuiPlugin.hh @@ -18,9 +18,9 @@ #ifndef RENDERING_GUI_PLUGIN_HH_ #define RENDERING_GUI_PLUGIN_HH_ -#include -#include -#include +#include +#include +#include /// \brief Example of a GUI plugin that uses Ignition Rendering. /// This plugin works with either Ignition GUI's Scene3D or Ignition Gazebo's diff --git a/examples/plugin/rendering_plugins/RenderingServerPlugin.cc b/examples/plugin/rendering_plugins/RenderingServerPlugin.cc index 2054975787c..4c9e583bde3 100644 --- a/examples/plugin/rendering_plugins/RenderingServerPlugin.cc +++ b/examples/plugin/rendering_plugins/RenderingServerPlugin.cc @@ -17,13 +17,13 @@ #include "RenderingServerPlugin.hh" //! [includeRenderingEvents] -#include +#include //! [includeRenderingEvents] -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include using namespace std::literals::chrono_literals; diff --git a/examples/plugin/rendering_plugins/RenderingServerPlugin.hh b/examples/plugin/rendering_plugins/RenderingServerPlugin.hh index 9f9218f4c67..55515cd3a21 100644 --- a/examples/plugin/rendering_plugins/RenderingServerPlugin.hh +++ b/examples/plugin/rendering_plugins/RenderingServerPlugin.hh @@ -17,8 +17,8 @@ #ifndef RENDERING_SERVER_PLUGIN_HH_ #define RENDERING_SERVER_PLUGIN_HH_ -#include -#include +#include +#include /// \brief Server-side system that uses Ignition Rendering APIs. /// It changes the ambient color every 2 simulation seconds. diff --git a/examples/plugin/system_plugin/SampleSystem.cc b/examples/plugin/system_plugin/SampleSystem.cc index 66b813f9631..7573a94e674 100644 --- a/examples/plugin/system_plugin/SampleSystem.cc +++ b/examples/plugin/system_plugin/SampleSystem.cc @@ -1,7 +1,7 @@ #include "SampleSystem.hh" //! [registerSampleSystem] -#include +#include // Include a line in your source file for each interface implemented. IGNITION_ADD_PLUGIN( diff --git a/examples/plugin/system_plugin/SampleSystem.hh b/examples/plugin/system_plugin/SampleSystem.hh index e17bf1d98d9..235860c835f 100644 --- a/examples/plugin/system_plugin/SampleSystem.hh +++ b/examples/plugin/system_plugin/SampleSystem.hh @@ -18,7 +18,7 @@ #define SYSTEM_PLUGIN_SAMPLESYSTEM_HH_ //! [header] -#include +#include namespace sample_system { diff --git a/examples/plugin/system_plugin/SampleSystem2.cc b/examples/plugin/system_plugin/SampleSystem2.cc index 837d0cfd5ac..a6bec142bfb 100644 --- a/examples/plugin/system_plugin/SampleSystem2.cc +++ b/examples/plugin/system_plugin/SampleSystem2.cc @@ -1,7 +1,7 @@ #include "SampleSystem.hh" //! [registerSampleSystem2] -#include +#include IGNITION_ADD_PLUGIN( sample_system::SampleSystem2, diff --git a/examples/standalone/comms/publisher.cc b/examples/standalone/comms/publisher.cc index d84d767df72..27c2b99bc0c 100644 --- a/examples/standalone/comms/publisher.cc +++ b/examples/standalone/comms/publisher.cc @@ -24,8 +24,8 @@ #include #include -#include -#include +#include +#include /// \brief Flag used to break the publisher loop and terminate the program. static std::atomic g_terminatePub(false); diff --git a/examples/standalone/custom_server/custom_server.cc b/examples/standalone/custom_server/custom_server.cc index 6746a309576..56a3f769635 100644 --- a/examples/standalone/custom_server/custom_server.cc +++ b/examples/standalone/custom_server/custom_server.cc @@ -15,8 +15,8 @@ * */ -#include -#include +#include +#include ///////////////////////////////////////////////// int main() diff --git a/examples/standalone/each_performance/each.cc b/examples/standalone/each_performance/each.cc index d6d278e3071..a9407ca6d21 100644 --- a/examples/standalone/each_performance/each.cc +++ b/examples/standalone/each_performance/each.cc @@ -16,12 +16,12 @@ */ #include -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include using namespace ignition; using namespace gazebo; diff --git a/examples/standalone/entity_creation/entity_creation.cc b/examples/standalone/entity_creation/entity_creation.cc index ff7a2c980e8..60ba90e99ce 100644 --- a/examples/standalone/entity_creation/entity_creation.cc +++ b/examples/standalone/entity_creation/entity_creation.cc @@ -15,11 +15,11 @@ * */ -#include +#include #include -#include +#include // Create a transport node. ignition::transport::Node node; diff --git a/examples/standalone/external_ecm/external_ecm.cc b/examples/standalone/external_ecm/external_ecm.cc index 6c9fa3f354e..f7faff8176f 100644 --- a/examples/standalone/external_ecm/external_ecm.cc +++ b/examples/standalone/external_ecm/external_ecm.cc @@ -16,11 +16,11 @@ */ #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include ////////////////////////////////////////////////// int main(int argc, char **argv) diff --git a/examples/standalone/gtest_setup/command_TEST.cc b/examples/standalone/gtest_setup/command_TEST.cc index f8e4f4583f5..b32569abc92 100644 --- a/examples/standalone/gtest_setup/command_TEST.cc +++ b/examples/standalone/gtest_setup/command_TEST.cc @@ -17,16 +17,16 @@ #include -#include - -#include -#include -#include -#include -#include -#include -#include -#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include using namespace std::chrono_literals; diff --git a/examples/standalone/gtest_setup/gravity_TEST.cc b/examples/standalone/gtest_setup/gravity_TEST.cc index 6bae7b3e781..02e18da59cf 100644 --- a/examples/standalone/gtest_setup/gravity_TEST.cc +++ b/examples/standalone/gtest_setup/gravity_TEST.cc @@ -17,12 +17,12 @@ #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include ////////////////////////////////////////////////// // Test that an object falls due to gravity diff --git a/examples/standalone/joy_to_twist/joy_to_twist.cc b/examples/standalone/joy_to_twist/joy_to_twist.cc index bae34786c09..68489925612 100644 --- a/examples/standalone/joy_to_twist/joy_to_twist.cc +++ b/examples/standalone/joy_to_twist/joy_to_twist.cc @@ -19,7 +19,7 @@ * Adapted from https://github.com/ros-teleop/teleop_twist_joy */ -#include +#include #include ignition::transport::Node::Publisher cmdVelPub; diff --git a/examples/standalone/joystick/joystick.cc b/examples/standalone/joystick/joystick.cc index 07c01393495..55ffd15ab11 100644 --- a/examples/standalone/joystick/joystick.cc +++ b/examples/standalone/joystick/joystick.cc @@ -19,8 +19,8 @@ #include #include #include -#include -#include +#include +#include #include ////////////////////////////////////////////////// diff --git a/examples/standalone/keyboard/keyboard.cc b/examples/standalone/keyboard/keyboard.cc index 33a0c637f20..d6db34b274e 100644 --- a/examples/standalone/keyboard/keyboard.cc +++ b/examples/standalone/keyboard/keyboard.cc @@ -24,10 +24,10 @@ */ -#include -#include +#include +#include #include -#include +#include #include #include #include diff --git a/examples/standalone/light_control/light_control.cc b/examples/standalone/light_control/light_control.cc index 8b5cf4118a2..568496eaaaf 100644 --- a/examples/standalone/light_control/light_control.cc +++ b/examples/standalone/light_control/light_control.cc @@ -18,10 +18,10 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include using namespace std::chrono_literals; diff --git a/examples/standalone/multi_lrauv_race/multi_lrauv_race.cc b/examples/standalone/multi_lrauv_race/multi_lrauv_race.cc index a180748fd1b..d24291d5254 100644 --- a/examples/standalone/multi_lrauv_race/multi_lrauv_race.cc +++ b/examples/standalone/multi_lrauv_race/multi_lrauv_race.cc @@ -26,8 +26,8 @@ #include #include -#include -#include +#include +#include // Fin joint limits from tethys model.sdf double random_angle_within_limits(double min=-0.261799, double max=0.261799) diff --git a/examples/standalone/scene_requester/scene_requester.cc b/examples/standalone/scene_requester/scene_requester.cc index 6175a197421..4ca074c8929 100644 --- a/examples/standalone/scene_requester/scene_requester.cc +++ b/examples/standalone/scene_requester/scene_requester.cc @@ -16,8 +16,8 @@ */ #include -#include -#include +#include +#include ////////////////////////////////////////////////// int main(int argc, char **argv) diff --git a/include/gz/sim/Conversions.hh b/include/gz/sim/Conversions.hh index 985bec6a972..0fc0be3dcd5 100644 --- a/include/gz/sim/Conversions.hh +++ b/include/gz/sim/Conversions.hh @@ -14,31 +14,31 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_CONVERSIONS_HH_ -#define IGNITION_GAZEBO_CONVERSIONS_HH_ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#ifndef GZ_GAZEBO_CONVERSIONS_HH_ +#define GZ_GAZEBO_CONVERSIONS_HH_ + +#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 @@ -53,9 +53,9 @@ #include #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" +#include "gz/sim/config.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Types.hh" namespace ignition { diff --git a/include/gz/sim/Entity.hh b/include/gz/sim/Entity.hh index 4ac16e82def..b4a8f08c75b 100644 --- a/include/gz/sim/Entity.hh +++ b/include/gz/sim/Entity.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_ENTITY_HH_ -#define IGNITION_GAZEBO_ENTITY_HH_ +#ifndef GZ_GAZEBO_ENTITY_HH_ +#define GZ_GAZEBO_ENTITY_HH_ #include -#include -#include +#include +#include /// \brief This library is part of the [Ignition /// Robotics](https://ignitionrobotics.org) project. diff --git a/include/gz/sim/EntityComponentManager.hh b/include/gz/sim/EntityComponentManager.hh index 3624f49ff20..2717264da95 100644 --- a/include/gz/sim/EntityComponentManager.hh +++ b/include/gz/sim/EntityComponentManager.hh @@ -14,11 +14,11 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_ENTITYCOMPONENTMANAGER_HH_ -#define IGNITION_GAZEBO_ENTITYCOMPONENTMANAGER_HH_ +#ifndef GZ_GAZEBO_ENTITYCOMPONENTMANAGER_HH_ +#define GZ_GAZEBO_ENTITYCOMPONENTMANAGER_HH_ -#include -#include +#include +#include #include #include @@ -32,14 +32,14 @@ #include #include -#include -#include -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" +#include +#include +#include "gz/sim/Entity.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Types.hh" -#include "ignition/gazebo/components/Component.hh" -#include "ignition/gazebo/detail/View.hh" +#include "gz/sim/components/Component.hh" +#include "gz/sim/detail/View.hh" namespace ignition { @@ -58,7 +58,7 @@ namespace ignition using EntityGraph = math::graph::DirectedGraph; /** \class EntityComponentManager EntityComponentManager.hh \ - * ignition/gazebo/EntityComponentManager.hh + * gz/sim/EntityComponentManager.hh **/ /// \brief The EntityComponentManager constructs, deletes, and returns /// components and entities. @@ -851,6 +851,6 @@ namespace ignition } } -#include "ignition/gazebo/detail/EntityComponentManager.hh" +#include "gz/sim/detail/EntityComponentManager.hh" #endif diff --git a/include/gz/sim/EventManager.hh b/include/gz/sim/EventManager.hh index bd1331cfbcc..c6484d2247b 100644 --- a/include/gz/sim/EventManager.hh +++ b/include/gz/sim/EventManager.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_EVENTMANAGER_HH_ -#define IGNITION_GAZEBO_EVENTMANAGER_HH_ +#ifndef GZ_GAZEBO_EVENTMANAGER_HH_ +#define GZ_GAZEBO_EVENTMANAGER_HH_ #include #include @@ -23,12 +23,12 @@ #include #include -#include -#include +#include +#include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -149,4 +149,4 @@ namespace ignition } } -#endif // IGNITION_GAZEBO_EVENTMANAGER_HH_ +#endif // GZ_GAZEBO_EVENTMANAGER_HH_ diff --git a/include/gz/sim/Events.hh b/include/gz/sim/Events.hh index 672c264c03a..bc4df207443 100644 --- a/include/gz/sim/Events.hh +++ b/include/gz/sim/Events.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_EVENTS_HH_ -#define IGNITION_GAZEBO_EVENTS_HH_ +#ifndef GZ_GAZEBO_EVENTS_HH_ +#define GZ_GAZEBO_EVENTS_HH_ #include -#include +#include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Entity.hh" +#include "gz/sim/config.hh" +#include "gz/sim/Entity.hh" namespace ignition { @@ -63,4 +63,4 @@ namespace ignition } // namespace gazebo } // namespace ignition -#endif // IGNITION_GAZEBO_EVENTS_HH_ +#endif // GZ_GAZEBO_EVENTS_HH_ diff --git a/include/gz/sim/Link.hh b/include/gz/sim/Link.hh index df967d30ca8..1c53b555034 100644 --- a/include/gz/sim/Link.hh +++ b/include/gz/sim/Link.hh @@ -14,23 +14,23 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_LINK_HH_ -#define IGNITION_GAZEBO_LINK_HH_ +#ifndef GZ_GAZEBO_LINK_HH_ +#define GZ_GAZEBO_LINK_HH_ #include #include #include #include -#include -#include -#include +#include +#include +#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { @@ -41,7 +41,7 @@ namespace ignition // Forward declarations. class IGNITION_GAZEBO_HIDDEN LinkPrivate; // - /// \class Link Link.hh ignition/gazebo/Link.hh + /// \class Link Link.hh gz/sim/Link.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. diff --git a/include/gz/sim/Model.hh b/include/gz/sim/Model.hh index b79b5ec055e..c8a3ff4cf7f 100644 --- a/include/gz/sim/Model.hh +++ b/include/gz/sim/Model.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_MODEL_HH_ -#define IGNITION_GAZEBO_MODEL_HH_ +#ifndef GZ_GAZEBO_MODEL_HH_ +#define GZ_GAZEBO_MODEL_HH_ #include #include #include -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -37,7 +37,7 @@ namespace ignition // Forward declarations. class IGNITION_GAZEBO_HIDDEN ModelPrivate; // - /// \class Model Model.hh ignition/gazebo/Model.hh + /// \class Model Model.hh gz/sim/Model.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. diff --git a/include/gz/sim/Primitives.hh b/include/gz/sim/Primitives.hh index eff9a97b837..3f2f950a49f 100644 --- a/include/gz/sim/Primitives.hh +++ b/include/gz/sim/Primitives.hh @@ -15,11 +15,11 @@ * */ -#ifndef IGNITION_GAZEBO_PRIMITIVES_HH_ -#define IGNITION_GAZEBO_PRIMITIVES_HH_ +#ifndef GZ_GAZEBO_PRIMITIVES_HH_ +#define GZ_GAZEBO_PRIMITIVES_HH_ -#include -#include +#include +#include #include @@ -78,6 +78,6 @@ namespace ignition } // namespace ignition -#endif // IGNITION_GAZEBO_PRIMITIVES_HH_ +#endif // GZ_GAZEBO_PRIMITIVES_HH_ diff --git a/include/gz/sim/SdfEntityCreator.hh b/include/gz/sim/SdfEntityCreator.hh index c54f8effe37..641aa5e1279 100644 --- a/include/gz/sim/SdfEntityCreator.hh +++ b/include/gz/sim/SdfEntityCreator.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_CREATEREMOVE_HH_ -#define IGNITION_GAZEBO_CREATEREMOVE_HH_ +#ifndef GZ_GAZEBO_CREATEREMOVE_HH_ +#define GZ_GAZEBO_CREATEREMOVE_HH_ #include @@ -32,10 +32,10 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -47,7 +47,7 @@ namespace ignition class SdfEntityCreatorPrivate; // /// \class SdfEntityCreator SdfEntityCreator.hh - /// ignition/gazebo/SdfEntityCreator.hh + /// gz/sim/SdfEntityCreator.hh /// \brief Provides convenient functions to spawn entities and load their /// plugins from SDF elements, to remove them, and to change their /// hierarchy. diff --git a/include/gz/sim/Server.hh b/include/gz/sim/Server.hh index 088fda99d8d..d29e9b08e56 100644 --- a/include/gz/sim/Server.hh +++ b/include/gz/sim/Server.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SERVER_HH_ -#define IGNITION_GAZEBO_SERVER_HH_ +#ifndef GZ_GAZEBO_SERVER_HH_ +#define GZ_GAZEBO_SERVER_HH_ #include #include #include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { @@ -36,7 +36,7 @@ namespace ignition // Forware declarations class ServerPrivate; - /// \class Server Server.hh ignition/gazebo/Server.hh + /// \class Server Server.hh gz/sim/Server.hh /// \brief The server instantiates and controls simulation. /// /// ## Example Usage diff --git a/include/gz/sim/ServerConfig.hh b/include/gz/sim/ServerConfig.hh index 7311d092e80..90fad6b5d5d 100644 --- a/include/gz/sim/ServerConfig.hh +++ b/include/gz/sim/ServerConfig.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SERVERCONFIG_HH_ -#define IGNITION_GAZEBO_SERVERCONFIG_HH_ +#ifndef GZ_GAZEBO_SERVERCONFIG_HH_ +#define GZ_GAZEBO_SERVERCONFIG_HH_ #include #include @@ -25,8 +25,8 @@ #include #include #include -#include -#include +#include +#include namespace ignition { @@ -37,7 +37,7 @@ namespace ignition // Forward declarations. class ServerConfigPrivate; - /// \class ServerConfig ServerConfig.hh ignition/gazebo/ServerConfig.hh + /// \class ServerConfig ServerConfig.hh gz/sim/ServerConfig.hh /// \brief Configuration parameters for a Server. An instance of this /// object can be used to construct a Server with a particular /// configuration. @@ -328,14 +328,14 @@ namespace ignition /// from fuel.ignitionrobotics.org, should be stored. /// \return Path to a location on disk. An empty string indicates that /// the default value will be used, which is currently - /// ~/.ignition/fuel. + /// ~/.gz/fuel. public: const std::string &ResourceCache() const; /// \brief Set the path to where simulation resources, such as models /// downloaded from fuel.ignitionrobotics.org, should be stored. /// \param[in] _path Path to a location on disk. An empty string /// indicates that the default value will be used, which is currently - /// ~/.ignition/fuel. + /// ~/.gz/fuel. public: void SetResourceCache(const std::string &_path); /// \brief Physics engine plugin library to load. @@ -444,7 +444,7 @@ namespace ignition /// variable. /// * If IGN_GAZEBO_SERVER_CONFIG_PATH is set but empty, no plugins /// are loaded. - /// 2. File at ${IGN_HOMEDIR}/.ignition/gazebo/server.config + /// 2. File at ${IGN_HOMEDIR}/.gz/sim/server.config /// 3. File at ${IGN_DATA_INSTALL_DIR}/server.config /// /// If any of the above files exist but are empty, resolution diff --git a/include/gz/sim/System.hh b/include/gz/sim/System.hh index 178dea43f99..45fbb2ecde6 100644 --- a/include/gz/sim/System.hh +++ b/include/gz/sim/System.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEM_HH_ -#define IGNITION_GAZEBO_SYSTEM_HH_ +#ifndef GZ_GAZEBO_SYSTEM_HH_ +#define GZ_GAZEBO_SYSTEM_HH_ #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include @@ -37,7 +37,7 @@ namespace ignition /// more information about systems. namespace systems {} - /// \class System System.hh ignition/gazebo/System.hh + /// \class System System.hh gz/sim/System.hh /// \brief Base class for a System. /// /// A System operates on Entities that have certain Components. A System @@ -79,7 +79,7 @@ namespace ignition public: virtual ~System() = default; }; - /// \class ISystemConfigure ISystem.hh ignition/gazebo/System.hh + /// \class ISystemConfigure ISystem.hh gz/sim/System.hh /// \brief Interface for a system that implements optional configuration /// /// Configure is called after the system is instantiated and all entities @@ -105,21 +105,21 @@ namespace ignition EntityComponentManager &_ecm) = 0; }; - /// \class ISystemPreUpdate ISystem.hh ignition/gazebo/System.hh + /// \class ISystemPreUpdate ISystem.hh gz/sim/System.hh /// \brief Interface for a system that uses the PreUpdate phase class ISystemPreUpdate { public: virtual void PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ecm) = 0; }; - /// \class ISystemUpdate ISystem.hh ignition/gazebo/System.hh + /// \class ISystemUpdate ISystem.hh gz/sim/System.hh /// \brief Interface for a system that uses the Update phase class ISystemUpdate { public: virtual void Update(const UpdateInfo &_info, EntityComponentManager &_ecm) = 0; }; - /// \class ISystemPostUpdate ISystem.hh ignition/gazebo/System.hh + /// \class ISystemPostUpdate ISystem.hh gz/sim/System.hh /// \brief Interface for a system that uses the PostUpdate phase class ISystemPostUpdate{ public: virtual void PostUpdate(const UpdateInfo &_info, diff --git a/include/gz/sim/SystemLoader.hh b/include/gz/sim/SystemLoader.hh index 7b8537b0615..c44cac13675 100644 --- a/include/gz/sim/SystemLoader.hh +++ b/include/gz/sim/SystemLoader.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMLOADER_HH_ -#define IGNITION_GAZEBO_SYSTEMLOADER_HH_ +#ifndef GZ_GAZEBO_SYSTEMLOADER_HH_ +#define GZ_GAZEBO_SYSTEMLOADER_HH_ #include #include @@ -23,9 +23,9 @@ #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -36,7 +36,7 @@ namespace ignition // Forward declarations. class IGNITION_GAZEBO_HIDDEN SystemLoaderPrivate; - /// \class SystemLoader SystemLoader.hh ignition/gazebo/SystemLoader.hh + /// \class SystemLoader SystemLoader.hh gz/sim/SystemLoader.hh /// \brief Class for loading/unloading System plugins. class IGNITION_GAZEBO_VISIBLE SystemLoader { @@ -77,5 +77,5 @@ namespace ignition using SystemLoaderPtr = std::shared_ptr; } } -#endif // IGNITION_GAZEBO_SYSTEMLOADER_HH_ +#endif // GZ_GAZEBO_SYSTEMLOADER_HH_ diff --git a/include/gz/sim/SystemPluginPtr.hh b/include/gz/sim/SystemPluginPtr.hh index f2170dcb50e..b90b5002b84 100644 --- a/include/gz/sim/SystemPluginPtr.hh +++ b/include/gz/sim/SystemPluginPtr.hh @@ -14,11 +14,11 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMPLUGINPTR_HH_ -#define IGNITION_GAZEBO_SYSTEMPLUGINPTR_HH_ +#ifndef GZ_GAZEBO_SYSTEMPLUGINPTR_HH_ +#define GZ_GAZEBO_SYSTEMPLUGINPTR_HH_ -#include -#include +#include +#include namespace ignition { diff --git a/include/gz/sim/TestFixture.hh b/include/gz/sim/TestFixture.hh index 75d371f4377..a0c758fa4e6 100644 --- a/include/gz/sim/TestFixture.hh +++ b/include/gz/sim/TestFixture.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_TESTFIXTURE_HH_ -#define IGNITION_GAZEBO_TESTFIXTURE_HH_ +#ifndef GZ_GAZEBO_TESTFIXTURE_HH_ +#define GZ_GAZEBO_TESTFIXTURE_HH_ #include #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/ServerConfig.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/ServerConfig.hh" namespace ignition { diff --git a/include/gz/sim/Types.hh b/include/gz/sim/Types.hh index 67dbe2ea3bd..0080e469051 100644 --- a/include/gz/sim/Types.hh +++ b/include/gz/sim/Types.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_TYPES_HH_ -#define IGNITION_GAZEBO_TYPES_HH_ +#ifndef GZ_GAZEBO_TYPES_HH_ +#define GZ_GAZEBO_TYPES_HH_ #include #include #include #include -#include "ignition/gazebo/Entity.hh" +#include "gz/sim/Entity.hh" namespace ignition { diff --git a/include/gz/sim/Util.hh b/include/gz/sim/Util.hh index 18cc6798c93..e718b6b575e 100644 --- a/include/gz/sim/Util.hh +++ b/include/gz/sim/Util.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_UTIL_HH_ -#define IGNITION_GAZEBO_UTIL_HH_ +#ifndef GZ_GAZEBO_UTIL_HH_ +#define GZ_GAZEBO_UTIL_HH_ #include #include #include -#include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" +#include +#include "gz/sim/config.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Types.hh" namespace ignition { diff --git a/include/gz/sim/World.hh b/include/gz/sim/World.hh index 9e6d8ccfb02..8de195532db 100644 --- a/include/gz/sim/World.hh +++ b/include/gz/sim/World.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_WORLD_HH_ -#define IGNITION_GAZEBO_WORLD_HH_ +#ifndef GZ_GAZEBO_WORLD_HH_ +#define GZ_GAZEBO_WORLD_HH_ #include #include @@ -23,13 +23,13 @@ #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" +#include "gz/sim/config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Types.hh" namespace ignition { @@ -40,7 +40,7 @@ namespace ignition // Forward declarations. class IGNITION_GAZEBO_HIDDEN WorldPrivate; // - /// \class World World.hh ignition/gazebo/World.hh + /// \class World World.hh gz/sim/World.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. diff --git a/include/gz/sim/comms/Broker.hh b/include/gz/sim/comms/Broker.hh index bf06cdf3834..f8825a29a6c 100644 --- a/include/gz/sim/comms/Broker.hh +++ b/include/gz/sim/comms/Broker.hh @@ -15,15 +15,15 @@ * */ -#ifndef IGNITION_GAZEBO_BROKER_HH_ -#define IGNITION_GAZEBO_BROKER_HH_ +#ifndef GZ_GAZEBO_BROKER_HH_ +#define GZ_GAZEBO_BROKER_HH_ #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 367cbe975ba..add9811a3fb 100644 --- a/include/gz/sim/comms/ICommsModel.hh +++ b/include/gz/sim/comms/ICommsModel.hh @@ -15,16 +15,16 @@ * */ -#ifndef IGNITION_GAZEBO_ICOMMSMODEL_HH_ -#define IGNITION_GAZEBO_ICOMMSMODEL_HH_ +#ifndef GZ_GAZEBO_ICOMMSMODEL_HH_ +#define GZ_GAZEBO_ICOMMSMODEL_HH_ #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 aa5bde7f4d8..8b50a33f061 100644 --- a/include/gz/sim/comms/MsgManager.hh +++ b/include/gz/sim/comms/MsgManager.hh @@ -15,19 +15,19 @@ * */ -#ifndef IGNITION_GAZEBO_MSGMANAGER_HH_ -#define IGNITION_GAZEBO_MSGMANAGER_HH_ +#ifndef GZ_GAZEBO_MSGMANAGER_HH_ +#define GZ_GAZEBO_MSGMANAGER_HH_ #include #include #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/Actor.hh b/include/gz/sim/components/Actor.hh index 024aa64c428..056a38d0fb7 100644 --- a/include/gz/sim/components/Actor.hh +++ b/include/gz/sim/components/Actor.hh @@ -14,10 +14,10 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_ACTOR_HH_ -#define IGNITION_GAZEBO_COMPONENTS_ACTOR_HH_ +#ifndef GZ_SIM_COMPONENTS_ACTOR_HH_ +#define GZ_SIM_COMPONENTS_ACTOR_HH_ -#include +#include #include #include @@ -25,11 +25,11 @@ #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { @@ -78,18 +78,18 @@ namespace components /// element](http://sdformat.org/spec?ver=1.6&elem=actor). using Actor = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Actor", Actor) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Actor", Actor) /// \brief Time in seconds within animation being currently played. using AnimationTime = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.AnimationTime", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.AnimationTime", AnimationTime) /// \brief Name of animation being currently played. using AnimationName = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.AnimationName", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.AnimationName", AnimationName) } } diff --git a/include/gz/sim/components/Actuators.hh b/include/gz/sim/components/Actuators.hh index 987e63fecae..dd719f85077 100644 --- a/include/gz/sim/components/Actuators.hh +++ b/include/gz/sim/components/Actuators.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_ACTUATORS_HH_ -#define IGNITION_GAZEBO_COMPONENTS_ACTUATORS_HH_ +#ifndef GZ_SIM_COMPONENTS_ACTUATORS_HH_ +#define GZ_SIM_COMPONENTS_ACTUATORS_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { @@ -37,7 +37,7 @@ namespace components using Actuators = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Actuators", Actuators) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Actuators", Actuators) } } } diff --git a/include/gz/sim/components/AirPressureSensor.hh b/include/gz/sim/components/AirPressureSensor.hh index 02f825ffd56..bd5619dcb5f 100644 --- a/include/gz/sim/components/AirPressureSensor.hh +++ b/include/gz/sim/components/AirPressureSensor.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_AIRPRESSURE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_AIRPRESSURE_HH_ +#ifndef GZ_SIM_COMPONENTS_AIRPRESSURE_HH_ +#define GZ_SIM_COMPONENTS_AIRPRESSURE_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -36,7 +36,7 @@ namespace components /// sdf::AirPressure, information. using AirPressureSensor = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.AirPressureSensor", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.AirPressureSensor", AirPressureSensor) } } diff --git a/include/gz/sim/components/Altimeter.hh b/include/gz/sim/components/Altimeter.hh index 2aa05827f05..453262e65a3 100644 --- a/include/gz/sim/components/Altimeter.hh +++ b/include/gz/sim/components/Altimeter.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_ALTIMETER_HH_ -#define IGNITION_GAZEBO_COMPONENTS_ALTIMETER_HH_ +#ifndef GZ_SIM_COMPONENTS_ALTIMETER_HH_ +#define GZ_SIM_COMPONENTS_ALTIMETER_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -36,7 +36,7 @@ namespace components /// sdf::Altimeter, information. using Altimeter = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Altimeter", Altimeter) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Altimeter", Altimeter) } } } diff --git a/include/gz/sim/components/AngularAcceleration.hh b/include/gz/sim/components/AngularAcceleration.hh index 71c9be1b89b..7f736203c2f 100644 --- a/include/gz/sim/components/AngularAcceleration.hh +++ b/include/gz/sim/components/AngularAcceleration.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_ANGULARACCELERATION_HH_ -#define IGNITION_GAZEBO_COMPONENTS_ANGULARACCELERATION_HH_ +#ifndef GZ_SIM_COMPONENTS_ANGULARACCELERATION_HH_ +#define GZ_SIM_COMPONENTS_ANGULARACCELERATION_HH_ -#include +#include -#include -#include +#include +#include -#include -#include "ignition/gazebo/components/Component.hh" +#include +#include "gz/sim/components/Component.hh" namespace ignition { @@ -37,7 +37,7 @@ namespace components /// represented by ignition::math::Vector3d. using AngularAcceleration = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.AngularAcceleration", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.AngularAcceleration", AngularAcceleration) /// \brief A component type that contains angular acceleration of an entity in @@ -45,7 +45,7 @@ namespace components using WorldAngularAcceleration = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.WorldAngularAcceleration", + "gz_sim_components.WorldAngularAcceleration", WorldAngularAcceleration) } } diff --git a/include/gz/sim/components/AngularVelocity.hh b/include/gz/sim/components/AngularVelocity.hh index 1005c2a8992..05fab4422de 100644 --- a/include/gz/sim/components/AngularVelocity.hh +++ b/include/gz/sim/components/AngularVelocity.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_ANGULARVELOCITY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_ANGULARVELOCITY_HH_ +#ifndef GZ_SIM_COMPONENTS_ANGULARVELOCITY_HH_ +#define GZ_SIM_COMPONENTS_ANGULARVELOCITY_HH_ -#include +#include -#include -#include +#include +#include -#include -#include "ignition/gazebo/components/Component.hh" +#include +#include "gz/sim/components/Component.hh" namespace ignition { @@ -37,14 +37,14 @@ namespace components /// represented by ignition::math::Vector3d. using AngularVelocity = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.AngularVelocity", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.AngularVelocity", AngularVelocity) /// \brief A component type that contains angular velocity of an entity in the /// world frame represented by ignition::math::Vector3d. using WorldAngularVelocity = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WorldAngularVelocity", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.WorldAngularVelocity", WorldAngularVelocity) } } diff --git a/include/gz/sim/components/AngularVelocityCmd.hh b/include/gz/sim/components/AngularVelocityCmd.hh index 1a221714564..1e6e4eb5de0 100644 --- a/include/gz/sim/components/AngularVelocityCmd.hh +++ b/include/gz/sim/components/AngularVelocityCmd.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_ANGULARVELOCITYCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_ANGULARVELOCITYCMD_HH_ +#ifndef GZ_SIM_COMPONENTS_ANGULARVELOCITYCMD_HH_ +#define GZ_SIM_COMPONENTS_ANGULARVELOCITYCMD_HH_ -#include +#include -#include +#include -#include -#include "ignition/gazebo/components/Component.hh" +#include +#include "gz/sim/components/Component.hh" namespace ignition { @@ -37,14 +37,14 @@ namespace components using AngularVelocityCmd = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.AngularVelocityCmd", AngularVelocityCmd) + "gz_sim_components.AngularVelocityCmd", AngularVelocityCmd) /// \brief A component type that contains the commanded angular velocity /// of an entity in the world frame represented by ignition::math::Vector3d. using WorldAngularVelocityCmd = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.WorldAngularVelocityCmd", WorldAngularVelocityCmd) + "gz_sim_components.WorldAngularVelocityCmd", WorldAngularVelocityCmd) } } } diff --git a/include/gz/sim/components/Atmosphere.hh b/include/gz/sim/components/Atmosphere.hh index dd66848b7a5..7af0fdbe851 100644 --- a/include/gz/sim/components/Atmosphere.hh +++ b/include/gz/sim/components/Atmosphere.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_ATMOSPHERE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_ATMOSPHERE_HH_ +#ifndef GZ_SIM_COMPONENTS_ATMOSPHERE_HH_ +#define GZ_SIM_COMPONENTS_ATMOSPHERE_HH_ #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { @@ -43,7 +43,7 @@ namespace components Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.Atmosphere", Atmosphere) + "gz_sim_components.Atmosphere", Atmosphere) } } } diff --git a/include/gz/sim/components/AxisAlignedBox.hh b/include/gz/sim/components/AxisAlignedBox.hh index 24226895bb5..cf61b6f22d8 100644 --- a/include/gz/sim/components/AxisAlignedBox.hh +++ b/include/gz/sim/components/AxisAlignedBox.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_AxisAlignedBox_HH_ -#define IGNITION_GAZEBO_COMPONENTS_AxisAlignedBox_HH_ +#ifndef GZ_SIM_COMPONENTS_AxisAlignedBox_HH_ +#define GZ_SIM_COMPONENTS_AxisAlignedBox_HH_ -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include namespace ignition { @@ -45,7 +45,7 @@ namespace components /// The axis aligned box is created from collisions in the entity using AxisAlignedBox = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.AxisAlignedBox", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.AxisAlignedBox", AxisAlignedBox) } } diff --git a/include/gz/sim/components/BatterySoC.hh b/include/gz/sim/components/BatterySoC.hh index 0a384f6f7b9..c8efdf44558 100644 --- a/include/gz/sim/components/BatterySoC.hh +++ b/include/gz/sim/components/BatterySoC.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_BATTERY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_BATTERY_HH_ +#ifndef GZ_SIM_COMPONENTS_BATTERY_HH_ +#define GZ_SIM_COMPONENTS_BATTERY_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { @@ -32,7 +32,7 @@ namespace components /// A component that identifies an entity as being a battery. /// Float value indicates state of charge. using BatterySoC = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.BatterySoC", BatterySoC) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.BatterySoC", BatterySoC) } } } diff --git a/include/gz/sim/components/Camera.hh b/include/gz/sim/components/Camera.hh index b9649886924..f8d22a7af1b 100644 --- a/include/gz/sim/components/Camera.hh +++ b/include/gz/sim/components/Camera.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_CAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CAMERA_HH_ +#ifndef GZ_SIM_COMPONENTS_CAMERA_HH_ +#define GZ_SIM_COMPONENTS_CAMERA_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -36,7 +36,7 @@ namespace components /// sdf::Camera, information. using Camera = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Camera", Camera) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Camera", Camera) } } } diff --git a/include/gz/sim/components/CanonicalLink.hh b/include/gz/sim/components/CanonicalLink.hh index 567e3bdedfe..0087ad6ca1e 100644 --- a/include/gz/sim/components/CanonicalLink.hh +++ b/include/gz/sim/components/CanonicalLink.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_CANONICALLINK_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CANONICALLINK_HH_ +#ifndef GZ_SIM_COMPONENTS_CANONICALLINK_HH_ +#define GZ_SIM_COMPONENTS_CANONICALLINK_HH_ -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -33,13 +33,13 @@ namespace components /// \brief A component that identifies an entity as being a canonical link. using CanonicalLink = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.CanonicalLink", CanonicalLink) + "gz_sim_components.CanonicalLink", CanonicalLink) /// \brief A component that contains a reference to the canonical link entity /// of a model. using ModelCanonicalLink = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.ModelCanonicalLink", ModelCanonicalLink) + "gz_sim_components.ModelCanonicalLink", ModelCanonicalLink) } } } diff --git a/include/gz/sim/components/CastShadows.hh b/include/gz/sim/components/CastShadows.hh index d5e0f7ce09f..5d9a0a48ae8 100644 --- a/include/gz/sim/components/CastShadows.hh +++ b/include/gz/sim/components/CastShadows.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_CASTSHADOWS_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CASTSHADOWS_HH_ +#ifndef GZ_SIM_COMPONENTS_CASTSHADOWS_HH_ +#define GZ_SIM_COMPONENTS_CASTSHADOWS_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { @@ -32,7 +32,7 @@ namespace components /// \brief A component used to indicate that an entity casts shadows /// e.g. visual entities using CastShadows = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.CastShadows", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.CastShadows", CastShadows) } } diff --git a/include/gz/sim/components/CenterOfVolume.hh b/include/gz/sim/components/CenterOfVolume.hh index 2096d2d5d02..92770e6402f 100644 --- a/include/gz/sim/components/CenterOfVolume.hh +++ b/include/gz/sim/components/CenterOfVolume.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_CENTEROFVOLUME_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CENTEROFVOLUME_HH_ +#ifndef GZ_SIM_COMPONENTS_CENTEROFVOLUME_HH_ +#define GZ_SIM_COMPONENTS_CENTEROFVOLUME_HH_ -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -35,7 +35,7 @@ namespace components /// position of the center of volume is relative to the pose of the parent /// entity, which is usually a link. using CenterOfVolume = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.CenterOfVolume", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.CenterOfVolume", CenterOfVolume) } } diff --git a/include/gz/sim/components/ChildLinkName.hh b/include/gz/sim/components/ChildLinkName.hh index 2381684d19b..b099140b963 100644 --- a/include/gz/sim/components/ChildLinkName.hh +++ b/include/gz/sim/components/ChildLinkName.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_CHILDLINKNAME_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CHILDLINKNAME_HH_ +#ifndef GZ_SIM_COMPONENTS_CHILDLINKNAME_HH_ +#define GZ_SIM_COMPONENTS_CHILDLINKNAME_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -36,7 +36,7 @@ namespace components using ChildLinkName = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.ChildLinkName", ChildLinkName) + "gz_sim_components.ChildLinkName", ChildLinkName) } } } diff --git a/include/gz/sim/components/Collision.hh b/include/gz/sim/components/Collision.hh index f35f0e95d96..f38cd1e3551 100644 --- a/include/gz/sim/components/Collision.hh +++ b/include/gz/sim/components/Collision.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_COLLISION_HH_ -#define IGNITION_GAZEBO_COMPONENTS_COLLISION_HH_ +#ifndef GZ_SIM_COMPONENTS_COLLISION_HH_ +#define GZ_SIM_COMPONENTS_COLLISION_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -41,7 +41,7 @@ namespace components /// \brief A component that identifies an entity as being a collision. using Collision = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.Collision", Collision) + "gz_sim_components.Collision", Collision) // TODO(anyone) The sdf::Collision DOM object does not yet contain // surface information. @@ -49,7 +49,7 @@ namespace components using CollisionElement = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.CollisionElement", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.CollisionElement", CollisionElement) /// \brief A component used to enable customization of contact surface for a @@ -58,7 +58,7 @@ namespace components using EnableContactSurfaceCustomization = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.EnableContactSurfaceCustomization", + "gz_sim_components.EnableContactSurfaceCustomization", EnableContactSurfaceCustomization) } } diff --git a/include/gz/sim/components/Component.hh b/include/gz/sim/components/Component.hh index 6425279a139..2414f4b1c6a 100644 --- a/include/gz/sim/components/Component.hh +++ b/include/gz/sim/components/Component.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_COMPONENT_HH_ -#define IGNITION_GAZEBO_COMPONENTS_COMPONENT_HH_ +#ifndef GZ_SIM_COMPONENTS_COMPONENT_HH_ +#define GZ_SIM_COMPONENTS_COMPONENT_HH_ #include #include @@ -23,11 +23,11 @@ #include #include -#include +#include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/ContactSensor.hh b/include/gz/sim/components/ContactSensor.hh index f7721015799..05993244569 100644 --- a/include/gz/sim/components/ContactSensor.hh +++ b/include/gz/sim/components/ContactSensor.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_CONTACTSENSOR_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CONTACTSENSOR_HH_ +#ifndef GZ_SIM_COMPONENTS_CONTACTSENSOR_HH_ +#define GZ_SIM_COMPONENTS_CONTACTSENSOR_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -33,7 +33,7 @@ namespace components /// \brief TODO(anyone) Substitute with sdf::Contact once that exists? /// This is currently the whole `` element. using ContactSensor = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ContactSensor", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.ContactSensor", ContactSensor) } } diff --git a/include/gz/sim/components/ContactSensorData.hh b/include/gz/sim/components/ContactSensorData.hh index 29a43a160ea..a3321a4a485 100644 --- a/include/gz/sim/components/ContactSensorData.hh +++ b/include/gz/sim/components/ContactSensorData.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_CONTACTDATASENSOR_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CONTACTDATASENSOR_HH_ +#ifndef GZ_SIM_COMPONENTS_CONTACTDATASENSOR_HH_ +#define GZ_SIM_COMPONENTS_CONTACTDATASENSOR_HH_ -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include namespace ignition { @@ -36,7 +36,7 @@ namespace components using ContactSensorData = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ContactSensorData", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.ContactSensorData", ContactSensorData) } } diff --git a/include/gz/sim/components/CustomSensor.hh b/include/gz/sim/components/CustomSensor.hh index 98712492416..47e01bb81cb 100644 --- a/include/gz/sim/components/CustomSensor.hh +++ b/include/gz/sim/components/CustomSensor.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_CUSTOMSENSOR_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CUSTOMSENSOR_HH_ +#ifndef GZ_SIM_COMPONENTS_CUSTOMSENSOR_HH_ +#define GZ_SIM_COMPONENTS_CUSTOMSENSOR_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -36,7 +36,7 @@ namespace components /// the SDF spec. using CustomSensor = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.CustomSensor", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.CustomSensor", CustomSensor) } } diff --git a/include/gz/sim/components/DepthCamera.hh b/include/gz/sim/components/DepthCamera.hh index c5962964c1a..e47a6416fb0 100644 --- a/include/gz/sim/components/DepthCamera.hh +++ b/include/gz/sim/components/DepthCamera.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_DEPTHCAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_DEPTHCAMERA_HH_ +#ifndef GZ_SIM_COMPONENTS_DEPTHCAMERA_HH_ +#define GZ_SIM_COMPONENTS_DEPTHCAMERA_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -36,7 +36,7 @@ namespace components /// sdf::Camera, information. using DepthCamera = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.DepthCamera", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.DepthCamera", DepthCamera) } } diff --git a/include/gz/sim/components/DetachableJoint.hh b/include/gz/sim/components/DetachableJoint.hh index 0c4b6ec59da..d7c438cfb81 100644 --- a/include/gz/sim/components/DetachableJoint.hh +++ b/include/gz/sim/components/DetachableJoint.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_DETACHABLE_JOINT_HH_ -#define IGNITION_GAZEBO_COMPONENTS_DETACHABLE_JOINT_HH_ +#ifndef GZ_SIM_COMPONENTS_DETACHABLE_JOINT_HH_ +#define GZ_SIM_COMPONENTS_DETACHABLE_JOINT_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -94,7 +94,7 @@ namespace components using DetachableJoint = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.DetachableJoint", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.DetachableJoint", DetachableJoint) } } diff --git a/include/gz/sim/components/ExternalWorldWrenchCmd.hh b/include/gz/sim/components/ExternalWorldWrenchCmd.hh index 018ed4fd51b..9394e183922 100644 --- a/include/gz/sim/components/ExternalWorldWrenchCmd.hh +++ b/include/gz/sim/components/ExternalWorldWrenchCmd.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_EXTERNALWORLDWRENCHCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_EXTERNALWORLDWRENCHCMD_HH_ +#ifndef GZ_SIM_COMPONENTS_EXTERNALWORLDWRENCHCMD_HH_ +#define GZ_SIM_COMPONENTS_EXTERNALWORLDWRENCHCMD_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { @@ -41,7 +41,7 @@ namespace components using ExternalWorldWrenchCmd = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ExternalWorldWrenchCmd", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.ExternalWorldWrenchCmd", ExternalWorldWrenchCmd) } } diff --git a/include/gz/sim/components/Factory.hh b/include/gz/sim/components/Factory.hh index 5e280a906c1..b766e334662 100644 --- a/include/gz/sim/components/Factory.hh +++ b/include/gz/sim/components/Factory.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_FACTORY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_FACTORY_HH_ +#ifndef GZ_SIM_COMPONENTS_FACTORY_HH_ +#define GZ_SIM_COMPONENTS_FACTORY_HH_ #include #include @@ -24,13 +24,13 @@ #include #include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include namespace ignition { @@ -371,9 +371,9 @@ namespace components /// \param[in] _compType Component type name. /// \param[in] _classname Class name for component. #define IGN_GAZEBO_REGISTER_COMPONENT(_compType, _classname) \ - class IgnGazeboComponents##_classname \ + class GzGazeboComponents##_classname \ { \ - public: IgnGazeboComponents##_classname() \ + public: GzGazeboComponents##_classname() \ { \ if (_classname::typeId != 0) \ return; \ @@ -383,7 +383,7 @@ namespace components _compType, new Desc());\ } \ }; \ - static IgnGazeboComponents##_classname\ + static GzGazeboComponents##_classname\ IgnitionGazeboComponentsInitializer##_classname; } } diff --git a/include/gz/sim/components/ForceTorque.hh b/include/gz/sim/components/ForceTorque.hh index 12da2780774..3b7433101de 100644 --- a/include/gz/sim/components/ForceTorque.hh +++ b/include/gz/sim/components/ForceTorque.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_FORCETORQUE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_FORCETORQUE_HH_ +#ifndef GZ_SIM_COMPONENTS_FORCETORQUE_HH_ +#define GZ_SIM_COMPONENTS_FORCETORQUE_HH_ #include -#include -#include +#include +#include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -38,7 +38,7 @@ namespace components /// sdf::ForceTorque, information. using ForceTorque = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ForceTorque", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.ForceTorque", ForceTorque) } } diff --git a/include/gz/sim/components/Geometry.hh b/include/gz/sim/components/Geometry.hh index 5a8b75835eb..7bf5cf3fe03 100644 --- a/include/gz/sim/components/Geometry.hh +++ b/include/gz/sim/components/Geometry.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_GEOMETRY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_GEOMETRY_HH_ +#ifndef GZ_SIM_COMPONENTS_GEOMETRY_HH_ +#define GZ_SIM_COMPONENTS_GEOMETRY_HH_ -#include +#include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { @@ -45,7 +45,7 @@ namespace components using Geometry = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Geometry", Geometry) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Geometry", Geometry) } } diff --git a/include/gz/sim/components/GpuLidar.hh b/include/gz/sim/components/GpuLidar.hh index ba1f50f047d..007e1e4caf2 100644 --- a/include/gz/sim/components/GpuLidar.hh +++ b/include/gz/sim/components/GpuLidar.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_GPU_LIDAR_HH_ -#define IGNITION_GAZEBO_COMPONENTS_GPU_LIDAR_HH_ +#ifndef GZ_SIM_COMPONENTS_GPU_LIDAR_HH_ +#define GZ_SIM_COMPONENTS_GPU_LIDAR_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -35,7 +35,7 @@ namespace components /// sdf::Lidar, information. using GpuLidar = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.GpuLidar", GpuLidar) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.GpuLidar", GpuLidar) } } } diff --git a/include/gz/sim/components/Gravity.hh b/include/gz/sim/components/Gravity.hh index bceedf278a2..222339259c8 100644 --- a/include/gz/sim/components/Gravity.hh +++ b/include/gz/sim/components/Gravity.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_GRAVITY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_GRAVITY_HH_ +#ifndef GZ_SIM_COMPONENTS_GRAVITY_HH_ +#define GZ_SIM_COMPONENTS_GRAVITY_HH_ -#include +#include -#include -#include +#include +#include -#include -#include "ignition/gazebo/components/Component.hh" +#include +#include "gz/sim/components/Component.hh" namespace ignition { @@ -35,7 +35,7 @@ namespace components { /// \brief Store the gravity acceleration. using Gravity = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Gravity", Gravity) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Gravity", Gravity) } } } diff --git a/include/gz/sim/components/HaltMotion.hh b/include/gz/sim/components/HaltMotion.hh index 2b44fa5bb8c..2d2a191bfb2 100644 --- a/include/gz/sim/components/HaltMotion.hh +++ b/include/gz/sim/components/HaltMotion.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_HALT_MOTION_HH_ -#define IGNITION_GAZEBO_COMPONENTS_HALT_MOTION_HH_ +#ifndef GZ_SIM_COMPONENTS_HALT_MOTION_HH_ +#define GZ_SIM_COMPONENTS_HALT_MOTION_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { @@ -31,7 +31,7 @@ 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", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.HaltMotion", HaltMotion) } } diff --git a/include/gz/sim/components/Imu.hh b/include/gz/sim/components/Imu.hh index fbd023c3459..25474a3d1a6 100644 --- a/include/gz/sim/components/Imu.hh +++ b/include/gz/sim/components/Imu.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_IMU_HH_ -#define IGNITION_GAZEBO_COMPONENTS_IMU_HH_ +#ifndef GZ_SIM_COMPONENTS_IMU_HH_ +#define GZ_SIM_COMPONENTS_IMU_HH_ #include -#include -#include +#include +#include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -38,7 +38,7 @@ namespace components /// sdf::IMU, information. using Imu = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Imu", Imu) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Imu", Imu) } } } diff --git a/include/gz/sim/components/Inertial.hh b/include/gz/sim/components/Inertial.hh index 5f467f05c17..df2cba2556e 100644 --- a/include/gz/sim/components/Inertial.hh +++ b/include/gz/sim/components/Inertial.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_INERTIAL_HH_ -#define IGNITION_GAZEBO_COMPONENTS_INERTIAL_HH_ +#ifndef GZ_SIM_COMPONENTS_INERTIAL_HH_ +#define GZ_SIM_COMPONENTS_INERTIAL_HH_ -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include namespace ignition { @@ -42,7 +42,7 @@ namespace components /// \brief This component holds an entity's inertial. using Inertial = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Inertial", Inertial) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Inertial", Inertial) } } } diff --git a/include/gz/sim/components/Joint.hh b/include/gz/sim/components/Joint.hh index effb4520ef5..7d87cc96283 100644 --- a/include/gz/sim/components/Joint.hh +++ b/include/gz/sim/components/Joint.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINT_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINT_HH_ +#ifndef GZ_SIM_COMPONENTS_JOINT_HH_ +#define GZ_SIM_COMPONENTS_JOINT_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { @@ -31,7 +31,7 @@ namespace components { /// \brief A component that identifies an entity as being a joint. using Joint = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Joint", Joint) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Joint", Joint) } } } diff --git a/include/gz/sim/components/JointAxis.hh b/include/gz/sim/components/JointAxis.hh index 5bfc5885c7e..a72949dd783 100644 --- a/include/gz/sim/components/JointAxis.hh +++ b/include/gz/sim/components/JointAxis.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTAXIS_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTAXIS_HH_ +#ifndef GZ_SIM_COMPONENTS_JOINTAXIS_HH_ +#define GZ_SIM_COMPONENTS_JOINTAXIS_HH_ -#include +#include #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -42,14 +42,14 @@ namespace components using JointAxis = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointAxis", JointAxis) + "gz_sim_components.JointAxis", JointAxis) /// \brief A component that contains the second joint axis for joints with two /// axes. This is a simple wrapper around sdf::JointAxis using JointAxis2 = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointAxis2", JointAxis2) + "gz_sim_components.JointAxis2", JointAxis2) } } } diff --git a/include/gz/sim/components/JointEffortLimitsCmd.hh b/include/gz/sim/components/JointEffortLimitsCmd.hh index b8b9217974b..124f3711f6e 100644 --- a/include/gz/sim/components/JointEffortLimitsCmd.hh +++ b/include/gz/sim/components/JointEffortLimitsCmd.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTEFFORTLIMITSCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTEFFORTLIMITSCMD_HH_ +#ifndef GZ_SIM_COMPONENTS_JOINTEFFORTLIMITSCMD_HH_ +#define GZ_SIM_COMPONENTS_JOINTEFFORTLIMITSCMD_HH_ #include -#include +#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { @@ -50,7 +50,7 @@ using JointEffortLimitsCmd = Component< >; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointEffortLimitsCmd", JointEffortLimitsCmd) + "gz_sim_components.JointEffortLimitsCmd", JointEffortLimitsCmd) } } diff --git a/include/gz/sim/components/JointForce.hh b/include/gz/sim/components/JointForce.hh index 2152d25d988..76074670eae 100644 --- a/include/gz/sim/components/JointForce.hh +++ b/include/gz/sim/components/JointForce.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTFORCE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTFORCE_HH_ +#ifndef GZ_SIM_COMPONENTS_JOINTFORCE_HH_ +#define GZ_SIM_COMPONENTS_JOINTFORCE_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -37,7 +37,7 @@ namespace components using JointForce = Component, class JointForceTag, serializers::VectorDoubleSerializer>; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointForce", JointForce) + "gz_sim_components.JointForce", JointForce) } } } diff --git a/include/gz/sim/components/JointForceCmd.hh b/include/gz/sim/components/JointForceCmd.hh index ffcee4c4df2..42afcc9b8f2 100644 --- a/include/gz/sim/components/JointForceCmd.hh +++ b/include/gz/sim/components/JointForceCmd.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTFORCECMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTFORCECMD_HH_ +#ifndef GZ_SIM_COMPONENTS_JOINTFORCECMD_HH_ +#define GZ_SIM_COMPONENTS_JOINTFORCECMD_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -36,7 +36,7 @@ namespace components /// std::vector and systems that set this component need to ensure that the /// vector has the same size as the degrees of freedom of the joint. using JointForceCmd = Component, class JointForceCmdTag>; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.JointForceCmd", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.JointForceCmd", JointForceCmd) } } diff --git a/include/gz/sim/components/JointPosition.hh b/include/gz/sim/components/JointPosition.hh index f215b931e97..ae5dd5b79d0 100644 --- a/include/gz/sim/components/JointPosition.hh +++ b/include/gz/sim/components/JointPosition.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTPOSITION_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTPOSITION_HH_ +#ifndef GZ_SIM_COMPONENTS_JOINTPOSITION_HH_ +#define GZ_SIM_COMPONENTS_JOINTPOSITION_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -38,7 +38,7 @@ namespace components using JointPosition = Component, class JointPositionTag, serializers::VectorDoubleSerializer>; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointPosition", JointPosition) + "gz_sim_components.JointPosition", JointPosition) } } } diff --git a/include/gz/sim/components/JointPositionLimitsCmd.hh b/include/gz/sim/components/JointPositionLimitsCmd.hh index 775937fbff5..59d36390503 100644 --- a/include/gz/sim/components/JointPositionLimitsCmd.hh +++ b/include/gz/sim/components/JointPositionLimitsCmd.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTPOSITIONLIMITSCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTPOSITIONLIMITSCMD_HH_ +#ifndef GZ_SIM_COMPONENTS_JOINTPOSITIONLIMITSCMD_HH_ +#define GZ_SIM_COMPONENTS_JOINTPOSITIONLIMITSCMD_HH_ #include -#include +#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { @@ -49,7 +49,7 @@ using JointPositionLimitsCmd = Component< >; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointPositionLimitsCmd", JointPositionLimitsCmd) + "gz_sim_components.JointPositionLimitsCmd", JointPositionLimitsCmd) } } } diff --git a/include/gz/sim/components/JointPositionReset.hh b/include/gz/sim/components/JointPositionReset.hh index aee79983b18..c178424c9f7 100644 --- a/include/gz/sim/components/JointPositionReset.hh +++ b/include/gz/sim/components/JointPositionReset.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTPOSITIONRESET_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTPOSITIONRESET_HH_ +#ifndef GZ_SIM_COMPONENTS_JOINTPOSITIONRESET_HH_ +#define GZ_SIM_COMPONENTS_JOINTPOSITIONRESET_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -40,7 +40,7 @@ namespace components class JointPositionResetTag, serializers::VectorDoubleSerializer>; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointPositionReset", JointPositionReset) + "gz_sim_components.JointPositionReset", JointPositionReset) } } } diff --git a/include/gz/sim/components/JointTransmittedWrench.hh b/include/gz/sim/components/JointTransmittedWrench.hh index a723fdc2856..9265b4157d1 100644 --- a/include/gz/sim/components/JointTransmittedWrench.hh +++ b/include/gz/sim/components/JointTransmittedWrench.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ +#ifndef GZ_SIM_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ +#define GZ_SIM_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -46,7 +46,7 @@ namespace components using JointTransmittedWrench = Component; -IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.JointTransmittedWrench", +IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.JointTransmittedWrench", JointTransmittedWrench) } // namespace components } diff --git a/include/gz/sim/components/JointType.hh b/include/gz/sim/components/JointType.hh index 1d63995ccfa..ab1a6c61faf 100644 --- a/include/gz/sim/components/JointType.hh +++ b/include/gz/sim/components/JointType.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTTYPE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTTYPE_HH_ +#ifndef GZ_SIM_COMPONENTS_JOINTTYPE_HH_ +#define GZ_SIM_COMPONENTS_JOINTTYPE_HH_ #include #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -65,7 +65,7 @@ namespace components using JointType = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointType", JointType) + "gz_sim_components.JointType", JointType) } } } diff --git a/include/gz/sim/components/JointVelocity.hh b/include/gz/sim/components/JointVelocity.hh index 7b0867c3836..65b58e4e0f0 100644 --- a/include/gz/sim/components/JointVelocity.hh +++ b/include/gz/sim/components/JointVelocity.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTVELOCITY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTVELOCITY_HH_ +#ifndef GZ_SIM_COMPONENTS_JOINTVELOCITY_HH_ +#define GZ_SIM_COMPONENTS_JOINTVELOCITY_HH_ #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { @@ -37,7 +37,7 @@ namespace components using JointVelocity = Component, class JointVelocityTag, serializers::VectorDoubleSerializer>; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointVelocity", JointVelocity) + "gz_sim_components.JointVelocity", JointVelocity) } } } diff --git a/include/gz/sim/components/JointVelocityCmd.hh b/include/gz/sim/components/JointVelocityCmd.hh index d37b3b263dc..9c373d35e39 100644 --- a/include/gz/sim/components/JointVelocityCmd.hh +++ b/include/gz/sim/components/JointVelocityCmd.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTVELOCITYCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTVELOCITYCMD_HH_ +#ifndef GZ_SIM_COMPONENTS_JOINTVELOCITYCMD_HH_ +#define GZ_SIM_COMPONENTS_JOINTVELOCITYCMD_HH_ #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { @@ -39,7 +39,7 @@ namespace components serializers::VectorDoubleSerializer>; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointVelocityCmd", JointVelocityCmd) + "gz_sim_components.JointVelocityCmd", JointVelocityCmd) } } } diff --git a/include/gz/sim/components/JointVelocityLimitsCmd.hh b/include/gz/sim/components/JointVelocityLimitsCmd.hh index e85905095f4..8470a74a6e4 100644 --- a/include/gz/sim/components/JointVelocityLimitsCmd.hh +++ b/include/gz/sim/components/JointVelocityLimitsCmd.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTVELOCITYLIMITSCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTVELOCITYLIMITSCMD_HH_ +#ifndef GZ_SIM_COMPONENTS_JOINTVELOCITYLIMITSCMD_HH_ +#define GZ_SIM_COMPONENTS_JOINTVELOCITYLIMITSCMD_HH_ #include -#include +#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { @@ -49,7 +49,7 @@ using JointVelocityLimitsCmd = Component< >; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointVelocityLimitsCmd", JointVelocityLimitsCmd) + "gz_sim_components.JointVelocityLimitsCmd", JointVelocityLimitsCmd) } } } diff --git a/include/gz/sim/components/JointVelocityReset.hh b/include/gz/sim/components/JointVelocityReset.hh index f4cb92e0150..16d335cb7a1 100644 --- a/include/gz/sim/components/JointVelocityReset.hh +++ b/include/gz/sim/components/JointVelocityReset.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTVELOCITYRESET_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTVELOCITYRESET_HH_ +#ifndef GZ_SIM_COMPONENTS_JOINTVELOCITYRESET_HH_ +#define GZ_SIM_COMPONENTS_JOINTVELOCITYRESET_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -41,7 +41,7 @@ namespace components class JointVelocityResetTag, serializers::VectorDoubleSerializer>; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointVelocityReset", JointVelocityReset) + "gz_sim_components.JointVelocityReset", JointVelocityReset) } } } diff --git a/include/gz/sim/components/LaserRetro.hh b/include/gz/sim/components/LaserRetro.hh index 75d1145e924..a78e2a2766b 100644 --- a/include/gz/sim/components/LaserRetro.hh +++ b/include/gz/sim/components/LaserRetro.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LASERRETRO_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LASERRETRO_HH_ +#ifndef GZ_SIM_COMPONENTS_LASERRETRO_HH_ +#define GZ_SIM_COMPONENTS_LASERRETRO_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { @@ -31,7 +31,7 @@ namespace components { /// \brief A component used to indicate an lidar reflective value using LaserRetro = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LaserRetro", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.LaserRetro", LaserRetro) } } diff --git a/include/gz/sim/components/Level.hh b/include/gz/sim/components/Level.hh index e95a6dc30ce..d7e60ab4f1a 100644 --- a/include/gz/sim/components/Level.hh +++ b/include/gz/sim/components/Level.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LEVEL_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LEVEL_HH_ +#ifndef GZ_SIM_COMPONENTS_LEVEL_HH_ +#define GZ_SIM_COMPONENTS_LEVEL_HH_ -#include -#include +#include +#include -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Component.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Component.hh" namespace ignition { @@ -33,11 +33,11 @@ namespace components { /// \brief This component identifies an entity as being a level. using Level = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Level", Level) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Level", Level) /// \brief This component identifies an entity as being a default level. using DefaultLevel = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.DefaultLevel", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.DefaultLevel", DefaultLevel) } } diff --git a/include/gz/sim/components/LevelBuffer.hh b/include/gz/sim/components/LevelBuffer.hh index 3cea1172e4a..a8198ac4c23 100644 --- a/include/gz/sim/components/LevelBuffer.hh +++ b/include/gz/sim/components/LevelBuffer.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LEVELBUFFER_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LEVELBUFFER_HH_ +#ifndef GZ_SIM_COMPONENTS_LEVELBUFFER_HH_ +#define GZ_SIM_COMPONENTS_LEVELBUFFER_HH_ -#include -#include +#include +#include -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Component.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Component.hh" namespace ignition { @@ -33,7 +33,7 @@ namespace components { /// \brief A component that holds the buffer setting of a level's geometry using LevelBuffer = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LevelBuffer", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.LevelBuffer", LevelBuffer) } } diff --git a/include/gz/sim/components/LevelEntityNames.hh b/include/gz/sim/components/LevelEntityNames.hh index 43324b08a70..65fb8c74c6c 100644 --- a/include/gz/sim/components/LevelEntityNames.hh +++ b/include/gz/sim/components/LevelEntityNames.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LEVELENTITYNAMES_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LEVELENTITYNAMES_HH_ +#ifndef GZ_SIM_COMPONENTS_LEVELENTITYNAMES_HH_ +#define GZ_SIM_COMPONENTS_LEVELENTITYNAMES_HH_ #include #include #include -#include -#include +#include +#include -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Component.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Component.hh" namespace ignition { @@ -81,7 +81,7 @@ namespace components Component, class LevelEntityNamesTag, serializers::LevelEntityNamesSerializer>; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LevelEntityNames", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.LevelEntityNames", LevelEntityNames) } } diff --git a/include/gz/sim/components/Lidar.hh b/include/gz/sim/components/Lidar.hh index 770c4b9664d..5835d890a82 100644 --- a/include/gz/sim/components/Lidar.hh +++ b/include/gz/sim/components/Lidar.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LIDAR_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LIDAR_HH_ +#ifndef GZ_SIM_COMPONENTS_LIDAR_HH_ +#define GZ_SIM_COMPONENTS_LIDAR_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -35,7 +35,7 @@ namespace components /// sdf::Lidar, information. using Lidar = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Lidar", Lidar) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Lidar", Lidar) } } } diff --git a/include/gz/sim/components/Light.hh b/include/gz/sim/components/Light.hh index 13964b35ef9..b55a31bd0f9 100644 --- a/include/gz/sim/components/Light.hh +++ b/include/gz/sim/components/Light.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LIGHT_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LIGHT_HH_ +#ifndef GZ_SIM_COMPONENTS_LIGHT_HH_ +#define GZ_SIM_COMPONENTS_LIGHT_HH_ -#include +#include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { @@ -46,7 +46,7 @@ namespace components /// element](http://sdformat.org/spec?ver=1.6&elem=light). using Light = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Light", Light) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Light", Light) } } } diff --git a/include/gz/sim/components/LightCmd.hh b/include/gz/sim/components/LightCmd.hh index fdba5858fc6..a3bab15c588 100644 --- a/include/gz/sim/components/LightCmd.hh +++ b/include/gz/sim/components/LightCmd.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LIGHTCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LIGHTCMD_HH_ +#ifndef GZ_SIM_COMPONENTS_LIGHTCMD_HH_ +#define GZ_SIM_COMPONENTS_LIGHTCMD_HH_ #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include +#include namespace ignition { @@ -39,7 +39,7 @@ namespace components /// entity in the world frame represented by msgs::Light. using LightCmd = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LightCmd", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.LightCmd", LightCmd) } } diff --git a/include/gz/sim/components/LightType.hh b/include/gz/sim/components/LightType.hh index 249eb8602fd..d193ac7c339 100644 --- a/include/gz/sim/components/LightType.hh +++ b/include/gz/sim/components/LightType.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LIGHTTYPE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LIGHTTYPE_HH_ +#ifndef GZ_SIM_COMPONENTS_LIGHTTYPE_HH_ +#define GZ_SIM_COMPONENTS_LIGHTTYPE_HH_ #include #include #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -37,7 +37,7 @@ namespace components /// around std::string using LightType = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LightType", LightType) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.LightType", LightType) } } } diff --git a/include/gz/sim/components/LinearAcceleration.hh b/include/gz/sim/components/LinearAcceleration.hh index 23cf1c87fc4..386c7b53632 100644 --- a/include/gz/sim/components/LinearAcceleration.hh +++ b/include/gz/sim/components/LinearAcceleration.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LINEARACCELERATION_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LINEARACCELERATION_HH_ +#ifndef GZ_SIM_COMPONENTS_LINEARACCELERATION_HH_ +#define GZ_SIM_COMPONENTS_LINEARACCELERATION_HH_ -#include +#include -#include -#include +#include +#include -#include -#include "ignition/gazebo/components/Component.hh" +#include +#include "gz/sim/components/Component.hh" namespace ignition { @@ -37,14 +37,14 @@ namespace components /// represented by ignition::math::Vector3d. using LinearAcceleration = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LinearAcceleration", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.LinearAcceleration", LinearAcceleration) /// \brief A component type that contains linear acceleration of an entity /// in the world frame represented by ignition::math::Vector3d. using WorldLinearAcceleration = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WorldLinearAcceleration", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.WorldLinearAcceleration", WorldLinearAcceleration) } } diff --git a/include/gz/sim/components/LinearVelocity.hh b/include/gz/sim/components/LinearVelocity.hh index 3fc93cf5ec4..7f0671ecc9e 100644 --- a/include/gz/sim/components/LinearVelocity.hh +++ b/include/gz/sim/components/LinearVelocity.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LINEARVELOCITY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LINEARVELOCITY_HH_ +#ifndef GZ_SIM_COMPONENTS_LINEARVELOCITY_HH_ +#define GZ_SIM_COMPONENTS_LINEARVELOCITY_HH_ -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -34,14 +34,14 @@ namespace components /// represented by ignition::math::Vector3d. using LinearVelocity = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.LinearVelocity", LinearVelocity) + "gz_sim_components.LinearVelocity", LinearVelocity) /// \brief A component type that contains linear velocity of an entity in the /// world frame represented by ignition::math::Vector3d. using WorldLinearVelocity = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.WorldLinearVelocity", WorldLinearVelocity) + "gz_sim_components.WorldLinearVelocity", WorldLinearVelocity) } } } diff --git a/include/gz/sim/components/LinearVelocityCmd.hh b/include/gz/sim/components/LinearVelocityCmd.hh index cf03bea0ced..4636e234bff 100644 --- a/include/gz/sim/components/LinearVelocityCmd.hh +++ b/include/gz/sim/components/LinearVelocityCmd.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LINEARVELOCITYCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LINEARVELOCITYCMD_HH_ +#ifndef GZ_SIM_COMPONENTS_LINEARVELOCITYCMD_HH_ +#define GZ_SIM_COMPONENTS_LINEARVELOCITYCMD_HH_ -#include +#include -#include +#include -#include -#include +#include +#include namespace ignition { @@ -38,7 +38,7 @@ namespace components using LinearVelocityCmd = Component< math::Vector3d, class LinearVelocityCmdTag>; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.LinearVelocityCmd", LinearVelocityCmd) + "gz_sim_components.LinearVelocityCmd", LinearVelocityCmd) /// \brief A component type that contains the commanded linear velocity of an /// entity represented by ignition::math::Vector3d, expressed in the world @@ -46,7 +46,7 @@ namespace components using WorldLinearVelocityCmd = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.WorldLinearVelocityCmd", WorldLinearVelocityCmd) + "gz_sim_components.WorldLinearVelocityCmd", WorldLinearVelocityCmd) } } } diff --git a/include/gz/sim/components/LinearVelocitySeed.hh b/include/gz/sim/components/LinearVelocitySeed.hh index 1bb69b905a6..b60cbf72163 100644 --- a/include/gz/sim/components/LinearVelocitySeed.hh +++ b/include/gz/sim/components/LinearVelocitySeed.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LINEARVELOCITYSEED_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LINEARVELOCITYSEED_HH_ +#ifndef GZ_SIM_COMPONENTS_LINEARVELOCITYSEED_HH_ +#define GZ_SIM_COMPONENTS_LINEARVELOCITYSEED_HH_ -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -36,7 +36,7 @@ namespace components /// by applying transformations and adding noise. using LinearVelocitySeed = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LinearVelocitySeed", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.LinearVelocitySeed", LinearVelocitySeed) /// \brief A component type that contains linear velocity seed of an entity in @@ -45,7 +45,7 @@ namespace components /// noise. using WorldLinearVelocitySeed = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WorldLinearVelocitySeed", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.WorldLinearVelocitySeed", WorldLinearVelocitySeed) } } diff --git a/include/gz/sim/components/Link.hh b/include/gz/sim/components/Link.hh index 433dac2ef5c..ce9b76c5444 100644 --- a/include/gz/sim/components/Link.hh +++ b/include/gz/sim/components/Link.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LINK_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LINK_HH_ +#ifndef GZ_SIM_COMPONENTS_LINK_HH_ +#define GZ_SIM_COMPONENTS_LINK_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { @@ -31,7 +31,7 @@ namespace components { /// \brief A component that identifies an entity as being a link. using Link = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Link", Link) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Link", Link) } } } diff --git a/include/gz/sim/components/LogPlaybackStatistics.hh b/include/gz/sim/components/LogPlaybackStatistics.hh index 973eec38578..8d84f9deea6 100644 --- a/include/gz/sim/components/LogPlaybackStatistics.hh +++ b/include/gz/sim/components/LogPlaybackStatistics.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LogPlaybackStatistics_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LogPlaybackStatistics_HH_ +#ifndef GZ_SIM_COMPONENTS_LogPlaybackStatistics_HH_ +#define GZ_SIM_COMPONENTS_LogPlaybackStatistics_HH_ -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include namespace ignition { @@ -38,7 +38,7 @@ namespace components /// being loaded using LogPlaybackStatistics = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LogPlaybackStatistics", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.LogPlaybackStatistics", LogPlaybackStatistics) } } diff --git a/include/gz/sim/components/LogicalAudio.hh b/include/gz/sim/components/LogicalAudio.hh index 7b465e61782..58bc69cd503 100644 --- a/include/gz/sim/components/LogicalAudio.hh +++ b/include/gz/sim/components/LogicalAudio.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LOGICALAUDIO_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LOGICALAUDIO_HH_ +#ifndef GZ_SIM_COMPONENTS_LOGICALAUDIO_HH_ +#define GZ_SIM_COMPONENTS_LOGICALAUDIO_HH_ #include #include @@ -23,9 +23,9 @@ #include #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -292,7 +292,7 @@ namespace components using LogicalAudioSource = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LogicalAudioSource", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.LogicalAudioSource", LogicalAudioSource) } @@ -304,7 +304,7 @@ namespace components class LogicalAudioSourcePlayInfoTag, serializers::LogicalAudioSourcePlayInfoSerializer>; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.LogicalAudioSourcePlayInfo", + "gz_sim_components.LogicalAudioSourcePlayInfo", LogicalAudioSourcePlayInfo) } @@ -315,7 +315,7 @@ namespace components using LogicalMicrophone = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LogicalMicrophone", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.LogicalMicrophone", LogicalMicrophone) } } diff --git a/include/gz/sim/components/LogicalCamera.hh b/include/gz/sim/components/LogicalCamera.hh index 7ed64631635..47eccd29ee8 100644 --- a/include/gz/sim/components/LogicalCamera.hh +++ b/include/gz/sim/components/LogicalCamera.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LOGICALCAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LOGICALCAMERA_HH_ +#ifndef GZ_SIM_COMPONENTS_LOGICALCAMERA_HH_ +#define GZ_SIM_COMPONENTS_LOGICALCAMERA_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -33,7 +33,7 @@ namespace components /// \brief TODO(anyone) Substitute with sdf::LogicalCamera once that exists? /// This is currently the whole `` element. using LogicalCamera = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LogicalCamera", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.LogicalCamera", LogicalCamera) } } diff --git a/include/gz/sim/components/MagneticField.hh b/include/gz/sim/components/MagneticField.hh index 8986f47813d..0bd27f232c2 100644 --- a/include/gz/sim/components/MagneticField.hh +++ b/include/gz/sim/components/MagneticField.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_MAGNETICFIELD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_MAGNETICFIELD_HH_ +#ifndef GZ_SIM_COMPONENTS_MAGNETICFIELD_HH_ +#define GZ_SIM_COMPONENTS_MAGNETICFIELD_HH_ -#include +#include -#include -#include +#include +#include -#include -#include "ignition/gazebo/components/Component.hh" +#include +#include "gz/sim/components/Component.hh" namespace ignition { @@ -36,7 +36,7 @@ namespace components /// \brief Stores the 3D magnetic field in teslas. using MagneticField = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.MagneticField", MagneticField) + "gz_sim_components.MagneticField", MagneticField) } } } diff --git a/include/gz/sim/components/Magnetometer.hh b/include/gz/sim/components/Magnetometer.hh index daa7c5a8602..59dc9fab1f6 100644 --- a/include/gz/sim/components/Magnetometer.hh +++ b/include/gz/sim/components/Magnetometer.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_MAGNETOMETER_HH_ -#define IGNITION_GAZEBO_COMPONENTS_MAGNETOMETER_HH_ +#ifndef GZ_SIM_COMPONENTS_MAGNETOMETER_HH_ +#define GZ_SIM_COMPONENTS_MAGNETOMETER_HH_ #include -#include -#include +#include +#include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -40,7 +40,7 @@ namespace components serializers::SensorSerializer>; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.Magnetometer", Magnetometer) + "gz_sim_components.Magnetometer", Magnetometer) } } } diff --git a/include/gz/sim/components/Material.hh b/include/gz/sim/components/Material.hh index 2acf7a839a7..c3d2661c430 100644 --- a/include/gz/sim/components/Material.hh +++ b/include/gz/sim/components/Material.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_MATERIAL_HH_ -#define IGNITION_GAZEBO_COMPONENTS_MATERIAL_HH_ +#ifndef GZ_SIM_COMPONENTS_MATERIAL_HH_ +#define GZ_SIM_COMPONENTS_MATERIAL_HH_ -#include +#include #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -42,7 +42,7 @@ namespace components /// \brief This component holds an entity's material. using Material = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Material", Material) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Material", Material) } } } diff --git a/include/gz/sim/components/Model.hh b/include/gz/sim/components/Model.hh index 5ba0420d942..84fec11d37f 100644 --- a/include/gz/sim/components/Model.hh +++ b/include/gz/sim/components/Model.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_MODEL_HH_ -#define IGNITION_GAZEBO_COMPONENTS_MODEL_HH_ +#ifndef GZ_SIM_COMPONENTS_MODEL_HH_ +#define GZ_SIM_COMPONENTS_MODEL_HH_ #include #include #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -84,13 +84,13 @@ namespace components { /// \brief A component that identifies an entity as being a model. using Model = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Model", Model) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Model", Model) /// \brief A component that holds the model's SDF DOM using ModelSdf = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ModelSdf", ModelSdf) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.ModelSdf", ModelSdf) } } } diff --git a/include/gz/sim/components/Name.hh b/include/gz/sim/components/Name.hh index e41cc6fd8bc..a543832029d 100644 --- a/include/gz/sim/components/Name.hh +++ b/include/gz/sim/components/Name.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_NAME_HH_ -#define IGNITION_GAZEBO_COMPONENTS_NAME_HH_ +#ifndef GZ_SIM_COMPONENTS_NAME_HH_ +#define GZ_SIM_COMPONENTS_NAME_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -35,7 +35,7 @@ namespace components /// of scoped names nor does it care about uniqueness. using Name = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Name", Name) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Name", Name) } } } diff --git a/include/gz/sim/components/NavSat.hh b/include/gz/sim/components/NavSat.hh index ae3358b9b4f..4f4209676ee 100644 --- a/include/gz/sim/components/NavSat.hh +++ b/include/gz/sim/components/NavSat.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_NAVSAT_HH_ -#define IGNITION_GAZEBO_COMPONENTS_NAVSAT_HH_ +#ifndef GZ_SIM_COMPONENTS_NAVSAT_HH_ +#define GZ_SIM_COMPONENTS_NAVSAT_HH_ #include -#include -#include +#include +#include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -38,7 +38,7 @@ namespace components /// sdf::NavSat, information. using NavSat = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.NavSat", NavSat) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.NavSat", NavSat) } } } diff --git a/include/gz/sim/components/ParentEntity.hh b/include/gz/sim/components/ParentEntity.hh index 5871d5a3d56..bb3a3ec773f 100644 --- a/include/gz/sim/components/ParentEntity.hh +++ b/include/gz/sim/components/ParentEntity.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_PARENTENTITY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PARENTENTITY_HH_ +#ifndef GZ_SIM_COMPONENTS_PARENTENTITY_HH_ +#define GZ_SIM_COMPONENTS_PARENTENTITY_HH_ -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -40,7 +40,7 @@ namespace components /// the `gazebo::SdfEntityCreator` class. using ParentEntity = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.ParentEntity", ParentEntity) + "gz_sim_components.ParentEntity", ParentEntity) } } } diff --git a/include/gz/sim/components/ParentLinkName.hh b/include/gz/sim/components/ParentLinkName.hh index 3081d163da9..67b7a4cb07a 100644 --- a/include/gz/sim/components/ParentLinkName.hh +++ b/include/gz/sim/components/ParentLinkName.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_PARENTLINKNAME_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PARENTLINKNAME_HH_ +#ifndef GZ_SIM_COMPONENTS_PARENTLINKNAME_HH_ +#define GZ_SIM_COMPONENTS_PARENTLINKNAME_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -35,7 +35,7 @@ namespace components using ParentLinkName = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.ParentLinkName", ParentLinkName) + "gz_sim_components.ParentLinkName", ParentLinkName) } } } diff --git a/include/gz/sim/components/ParticleEmitter.hh b/include/gz/sim/components/ParticleEmitter.hh index 86fc36bd883..52eb838cddc 100644 --- a/include/gz/sim/components/ParticleEmitter.hh +++ b/include/gz/sim/components/ParticleEmitter.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ +#ifndef GZ_SIM_COMPONENTS_PARTICLEEMITTER_HH_ +#define GZ_SIM_COMPONENTS_PARTICLEEMITTER_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { @@ -35,14 +35,14 @@ namespace components using ParticleEmitter = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ParticleEmitter", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.ParticleEmitter", ParticleEmitter) /// \brief A component that contains a particle emitter command. using ParticleEmitterCmd = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ParticleEmitterCmd", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.ParticleEmitterCmd", ParticleEmitterCmd) } } diff --git a/include/gz/sim/components/Performer.hh b/include/gz/sim/components/Performer.hh index e4580586092..cfa8a74f604 100644 --- a/include/gz/sim/components/Performer.hh +++ b/include/gz/sim/components/Performer.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_PERFORMER_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PERFORMER_HH_ +#ifndef GZ_SIM_COMPONENTS_PERFORMER_HH_ +#define GZ_SIM_COMPONENTS_PERFORMER_HH_ -#include -#include +#include +#include -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Component.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Component.hh" namespace ignition { @@ -33,7 +33,7 @@ namespace components { /// \brief This component identifies an entity as being a performer. using Performer = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Performer", Performer) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Performer", Performer) } } } diff --git a/include/gz/sim/components/PerformerAffinity.hh b/include/gz/sim/components/PerformerAffinity.hh index 0afe760d0cb..0936adc4168 100644 --- a/include/gz/sim/components/PerformerAffinity.hh +++ b/include/gz/sim/components/PerformerAffinity.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_PERFORMERAFFINITY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PERFORMERAFFINITY_HH_ +#ifndef GZ_SIM_COMPONENTS_PERFORMERAFFINITY_HH_ +#define GZ_SIM_COMPONENTS_PERFORMERAFFINITY_HH_ #include -#include -#include +#include +#include -#include "ignition/gazebo/components/Component.hh" -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Serialization.hh" +#include "gz/sim/components/Component.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Serialization.hh" namespace ignition { @@ -38,7 +38,7 @@ namespace components /// this performer is associated with. using PerformerAffinity = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.PerformerAffinity", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.PerformerAffinity", PerformerAffinity) } } diff --git a/include/gz/sim/components/PerformerLevels.hh b/include/gz/sim/components/PerformerLevels.hh index a9f84faa94d..556eeadb8f3 100644 --- a/include/gz/sim/components/PerformerLevels.hh +++ b/include/gz/sim/components/PerformerLevels.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_PERFORMERLEVELS_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PERFORMERLEVELS_HH_ +#ifndef GZ_SIM_COMPONENTS_PERFORMERLEVELS_HH_ +#define GZ_SIM_COMPONENTS_PERFORMERLEVELS_HH_ #include -#include -#include +#include +#include -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Component.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Component.hh" namespace ignition { @@ -75,7 +75,7 @@ namespace components /// \brief Holds all the levels which a performer is in. using PerformerLevels = Component, class PerformerLevelsTag, serializers::PerformerLevelsSerializer>; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.PerformerLevels", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.PerformerLevels", PerformerLevels) } } diff --git a/include/gz/sim/components/Physics.hh b/include/gz/sim/components/Physics.hh index 117c258367a..640c3b62e4e 100644 --- a/include/gz/sim/components/Physics.hh +++ b/include/gz/sim/components/Physics.hh @@ -14,22 +14,22 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_PHYSICS_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PHYSICS_HH_ +#ifndef GZ_SIM_COMPONENTS_PHYSICS_HH_ +#define GZ_SIM_COMPONENTS_PHYSICS_HH_ #include -#include +#include #include -#include -#include +#include +#include -#include -#include "ignition/gazebo/components/Component.hh" -#include -#include +#include +#include "gz/sim/components/Component.hh" +#include +#include namespace ignition { @@ -48,7 +48,7 @@ namespace components /// the World entity. using Physics = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Physics", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Physics", Physics) /// \brief The name of the collision detector to be used. The supported @@ -56,14 +56,14 @@ namespace components using PhysicsCollisionDetector = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.PhysicsCollisionDetector", + "gz_sim_components.PhysicsCollisionDetector", PhysicsCollisionDetector) /// \brief The name of the solver to be used. The supported options will /// depend on the physics engine being used. using PhysicsSolver = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.PhysicsSolver", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.PhysicsSolver", PhysicsSolver) } } diff --git a/include/gz/sim/components/PhysicsCmd.hh b/include/gz/sim/components/PhysicsCmd.hh index f72dc328b04..bcfd403fb16 100644 --- a/include/gz/sim/components/PhysicsCmd.hh +++ b/include/gz/sim/components/PhysicsCmd.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_PHYSICSCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PHYSICSCMD_HH_ +#ifndef GZ_SIM_COMPONENTS_PHYSICSCMD_HH_ +#define GZ_SIM_COMPONENTS_PHYSICSCMD_HH_ -#include +#include -#include -#include +#include +#include -#include -#include "ignition/gazebo/components/Component.hh" +#include +#include "gz/sim/components/Component.hh" namespace ignition { @@ -36,7 +36,7 @@ namespace components /// \brief A component type that contains the physics properties of /// the World entity. using PhysicsCmd = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.PhysicsCmd", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.PhysicsCmd", PhysicsCmd) } } diff --git a/include/gz/sim/components/PhysicsEnginePlugin.hh b/include/gz/sim/components/PhysicsEnginePlugin.hh index dda8fa86df7..97db12a254c 100644 --- a/include/gz/sim/components/PhysicsEnginePlugin.hh +++ b/include/gz/sim/components/PhysicsEnginePlugin.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_PHYSICSENGINEPLUGIN_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PHYSICSENGINEPLUGIN_HH_ +#ifndef GZ_SIM_COMPONENTS_PHYSICSENGINEPLUGIN_HH_ +#define GZ_SIM_COMPONENTS_PHYSICSENGINEPLUGIN_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -34,7 +34,7 @@ namespace components /// \brief Holds the physics engine shared library. using PhysicsEnginePlugin = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.PhysicsEnginePlugin", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.PhysicsEnginePlugin", PhysicsEnginePlugin) } } diff --git a/include/gz/sim/components/Pose.hh b/include/gz/sim/components/Pose.hh index 8d67c51d3c1..fc029048e51 100644 --- a/include/gz/sim/components/Pose.hh +++ b/include/gz/sim/components/Pose.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_POSE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_POSE_HH_ +#ifndef GZ_SIM_COMPONENTS_POSE_HH_ +#define GZ_SIM_COMPONENTS_POSE_HH_ -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -33,20 +33,20 @@ namespace components /// \brief A component type that contains pose, ignition::math::Pose3d, /// information. using Pose = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Pose", Pose) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Pose", Pose) /// \brief A component type that contains pose, ignition::math::Pose3d, /// information in world frame. using WorldPose = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.WorldPose", WorldPose) + "gz_sim_components.WorldPose", WorldPose) /// \brief A component type that contains pose, ignition::math::Pose3d, /// information within a trajectory. using TrajectoryPose = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.TrajectoryPose", TrajectoryPose) + "gz_sim_components.TrajectoryPose", TrajectoryPose) } } } diff --git a/include/gz/sim/components/PoseCmd.hh b/include/gz/sim/components/PoseCmd.hh index 8f63faefee3..53957457d6e 100644 --- a/include/gz/sim/components/PoseCmd.hh +++ b/include/gz/sim/components/PoseCmd.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_POSECMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_POSECMD_HH_ +#ifndef GZ_SIM_COMPONENTS_POSECMD_HH_ +#define GZ_SIM_COMPONENTS_POSECMD_HH_ -#include +#include -#include -#include +#include +#include -#include -#include "ignition/gazebo/components/Component.hh" +#include +#include "gz/sim/components/Component.hh" namespace ignition { @@ -36,7 +36,7 @@ namespace components /// \brief A component type that contains commanded pose of an /// entity in the world frame represented by ignition::math::Pose3d. using WorldPoseCmd = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WorldPoseCmd", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.WorldPoseCmd", WorldPoseCmd) } } diff --git a/include/gz/sim/components/Recreate.hh b/include/gz/sim/components/Recreate.hh index bb053fe5f90..d58aa6af108 100644 --- a/include/gz/sim/components/Recreate.hh +++ b/include/gz/sim/components/Recreate.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_RECREATE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_RECREATE_HH_ +#ifndef GZ_SIM_COMPONENTS_RECREATE_HH_ +#define GZ_SIM_COMPONENTS_RECREATE_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { @@ -39,7 +39,7 @@ namespace components /// 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) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Recreate", Recreate) } } } diff --git a/include/gz/sim/components/RenderEngineGuiPlugin.hh b/include/gz/sim/components/RenderEngineGuiPlugin.hh index e2539e1331f..79b75006b05 100644 --- a/include/gz/sim/components/RenderEngineGuiPlugin.hh +++ b/include/gz/sim/components/RenderEngineGuiPlugin.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_RENDERENGINEGUIPLUGIN_HH_ -#define IGNITION_GAZEBO_COMPONENTS_RENDERENGINEGUIPLUGIN_HH_ +#ifndef GZ_SIM_COMPONENTS_RENDERENGINEGUIPLUGIN_HH_ +#define GZ_SIM_COMPONENTS_RENDERENGINEGUIPLUGIN_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -34,7 +34,7 @@ namespace components /// \brief Holds the render engine gui shared library. using RenderEngineGuiPlugin = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.RenderEngineGuiPlugin", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.RenderEngineGuiPlugin", RenderEngineGuiPlugin) } } diff --git a/include/gz/sim/components/RenderEngineServerHeadless.hh b/include/gz/sim/components/RenderEngineServerHeadless.hh index 9746e4b0aa2..006be7ad4e6 100644 --- a/include/gz/sim/components/RenderEngineServerHeadless.hh +++ b/include/gz/sim/components/RenderEngineServerHeadless.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ -#define IGNITION_GAZEBO_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ +#ifndef GZ_SIM_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ +#define GZ_SIM_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -35,7 +35,7 @@ namespace components using RenderEngineServerHeadless = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.RenderEngineServerHeadless", + "gz_sim_components.RenderEngineServerHeadless", RenderEngineServerHeadless) } } diff --git a/include/gz/sim/components/RenderEngineServerPlugin.hh b/include/gz/sim/components/RenderEngineServerPlugin.hh index 6d32db368e4..d894ef47a6a 100644 --- a/include/gz/sim/components/RenderEngineServerPlugin.hh +++ b/include/gz/sim/components/RenderEngineServerPlugin.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_RENDERENGINESERVERPLUGIN_HH_ -#define IGNITION_GAZEBO_COMPONENTS_RENDERENGINESERVERPLUGIN_HH_ +#ifndef GZ_SIM_COMPONENTS_RENDERENGINESERVERPLUGIN_HH_ +#define GZ_SIM_COMPONENTS_RENDERENGINESERVERPLUGIN_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -35,7 +35,7 @@ namespace components using RenderEngineServerPlugin = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.RenderEngineServerPlugin", + "gz_sim_components.RenderEngineServerPlugin", RenderEngineServerPlugin) } } diff --git a/include/gz/sim/components/RgbdCamera.hh b/include/gz/sim/components/RgbdCamera.hh index 54347b7bdd9..7f6c69e109b 100644 --- a/include/gz/sim/components/RgbdCamera.hh +++ b/include/gz/sim/components/RgbdCamera.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_RGBDCAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_RGBDCAMERA_HH_ +#ifndef GZ_SIM_COMPONENTS_RGBDCAMERA_HH_ +#define GZ_SIM_COMPONENTS_RGBDCAMERA_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -36,7 +36,7 @@ namespace components /// sdf::Camera, information. using RgbdCamera = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.RgbdCamera", RgbdCamera) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.RgbdCamera", RgbdCamera) } } } diff --git a/include/gz/sim/components/Scene.hh b/include/gz/sim/components/Scene.hh index 20ea32123c2..9cad199576f 100644 --- a/include/gz/sim/components/Scene.hh +++ b/include/gz/sim/components/Scene.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_SCENE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SCENE_HH_ +#ifndef GZ_SIM_COMPONENTS_SCENE_HH_ +#define GZ_SIM_COMPONENTS_SCENE_HH_ -#include +#include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { @@ -44,7 +44,7 @@ namespace components using Scene = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.Scene", Scene) + "gz_sim_components.Scene", Scene) } } } diff --git a/include/gz/sim/components/SegmentationCamera.hh b/include/gz/sim/components/SegmentationCamera.hh index c476fc8ba82..2b8efd10929 100644 --- a/include/gz/sim/components/SegmentationCamera.hh +++ b/include/gz/sim/components/SegmentationCamera.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_SEGMENTATIONCAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SEGMENTATIONCAMERA_HH_ +#ifndef GZ_SIM_COMPONENTS_SEGMENTATIONCAMERA_HH_ +#define GZ_SIM_COMPONENTS_SEGMENTATIONCAMERA_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -36,7 +36,7 @@ namespace components /// sdf::Camera, information. using SegmentationCamera = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SegmentationCamera", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.SegmentationCamera", SegmentationCamera) } } diff --git a/include/gz/sim/components/SelfCollide.hh b/include/gz/sim/components/SelfCollide.hh index ae0ddc6be32..18949baecee 100644 --- a/include/gz/sim/components/SelfCollide.hh +++ b/include/gz/sim/components/SelfCollide.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_SELFCOLLIDE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SELFCOLLIDE_HH_ +#ifndef GZ_SIM_COMPONENTS_SELFCOLLIDE_HH_ +#define GZ_SIM_COMPONENTS_SELFCOLLIDE_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { @@ -32,7 +32,7 @@ namespace components /// \brief A component used to hold a model's self collide property. using SelfCollide = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SelfCollide", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.SelfCollide", SelfCollide) } } diff --git a/include/gz/sim/components/SemanticLabel.hh b/include/gz/sim/components/SemanticLabel.hh index 3139b753105..13bf80704c1 100644 --- a/include/gz/sim/components/SemanticLabel.hh +++ b/include/gz/sim/components/SemanticLabel.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LABEL_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LABEL_HH_ +#ifndef GZ_SIM_COMPONENTS_LABEL_HH_ +#define GZ_SIM_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 { @@ -34,7 +34,7 @@ namespace components /// 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", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.SemanticLabel", SemanticLabel) } } diff --git a/include/gz/sim/components/Sensor.hh b/include/gz/sim/components/Sensor.hh index 2d7ddb39a35..9ff92281726 100644 --- a/include/gz/sim/components/Sensor.hh +++ b/include/gz/sim/components/Sensor.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_SENSOR_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SENSOR_HH_ +#ifndef GZ_SIM_COMPONENTS_SENSOR_HH_ +#define GZ_SIM_COMPONENTS_SENSOR_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -33,7 +33,7 @@ namespace components { /// \brief A component that identifies an entity as being a sensor. using Sensor = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Sensor", Sensor) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Sensor", Sensor) /// \brief Name of the transport topic where a sensor is publishing its /// data. @@ -41,7 +41,7 @@ namespace components /// prefix common to all topics of that sensor. using SensorTopic = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SensorTopic", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.SensorTopic", SensorTopic) } } diff --git a/include/gz/sim/components/Serialization.hh b/include/gz/sim/components/Serialization.hh index 7ef0dd66393..6edd2b1beb1 100644 --- a/include/gz/sim/components/Serialization.hh +++ b/include/gz/sim/components/Serialization.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_SERIALIZATION_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SERIALIZATION_HH_ +#ifndef GZ_SIM_COMPONENTS_SERIALIZATION_HH_ +#define GZ_SIM_COMPONENTS_SERIALIZATION_HH_ #include -#include +#include #include #include #include -#include -#include +#include +#include // This header holds serialization operators which are shared among several // components diff --git a/include/gz/sim/components/SlipComplianceCmd.hh b/include/gz/sim/components/SlipComplianceCmd.hh index f8122b7c41d..4e72a78696f 100644 --- a/include/gz/sim/components/SlipComplianceCmd.hh +++ b/include/gz/sim/components/SlipComplianceCmd.hh @@ -15,16 +15,16 @@ * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_SLIPCOMPLIANCECMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SLIPCOMPLIANCECMD_HH_ +#ifndef GZ_SIM_COMPONENTS_SLIPCOMPLIANCECMD_HH_ +#define GZ_SIM_COMPONENTS_SLIPCOMPLIANCECMD_HH_ #include -#include -#include +#include +#include -#include -#include "ignition/gazebo/components/Component.hh" +#include +#include "gz/sim/components/Component.hh" namespace ignition { @@ -40,7 +40,7 @@ namespace components /// direction 2 (fdir2) respectively. using SlipComplianceCmd = Component, class SlipComplianceCmdTag>; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SlipComplianceCmd ", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.SlipComplianceCmd ", SlipComplianceCmd) } } diff --git a/include/gz/sim/components/SourceFilePath.hh b/include/gz/sim/components/SourceFilePath.hh index d5919e1a439..70f748d62c5 100644 --- a/include/gz/sim/components/SourceFilePath.hh +++ b/include/gz/sim/components/SourceFilePath.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_SOURCEFILEPATH_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SOURCEFILEPATH_HH_ +#ifndef GZ_SIM_COMPONENTS_SOURCEFILEPATH_HH_ +#define GZ_SIM_COMPONENTS_SOURCEFILEPATH_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -37,7 +37,7 @@ namespace components using SourceFilePath = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SourceFilePath", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.SourceFilePath", SourceFilePath) } } diff --git a/include/gz/sim/components/SphericalCoordinates.hh b/include/gz/sim/components/SphericalCoordinates.hh index 93ebd43fa82..b97fef7e63a 100644 --- a/include/gz/sim/components/SphericalCoordinates.hh +++ b/include/gz/sim/components/SphericalCoordinates.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ +#ifndef GZ_SIM_COMPONENTS_SPHERICALCOORDINATES_HH_ +#define GZ_SIM_COMPONENTS_SPHERICALCOORDINATES_HH_ -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include namespace ignition { @@ -44,7 +44,7 @@ namespace components Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.SphericalCoordinates", SphericalCoordinates) + "gz_sim_components.SphericalCoordinates", SphericalCoordinates) } } } diff --git a/include/gz/sim/components/Static.hh b/include/gz/sim/components/Static.hh index d9b876a584a..c65976d52a5 100644 --- a/include/gz/sim/components/Static.hh +++ b/include/gz/sim/components/Static.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_STATIC_HH_ -#define IGNITION_GAZEBO_COMPONENTS_STATIC_HH_ +#ifndef GZ_SIM_COMPONENTS_STATIC_HH_ +#define GZ_SIM_COMPONENTS_STATIC_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { @@ -32,7 +32,7 @@ namespace components /// \brief A component used to indicate that a model is static (i.e. not /// moveable). using Static = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Static", Static) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Static", Static) } } } diff --git a/include/gz/sim/components/Temperature.hh b/include/gz/sim/components/Temperature.hh index cfd8df53275..5b5381505aa 100644 --- a/include/gz/sim/components/Temperature.hh +++ b/include/gz/sim/components/Temperature.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_TEMPERATURE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_TEMPERATURE_HH_ +#ifndef GZ_SIM_COMPONENTS_TEMPERATURE_HH_ +#define GZ_SIM_COMPONENTS_TEMPERATURE_HH_ -#include +#include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -33,13 +33,13 @@ namespace components { /// \brief A component that stores temperature data in Kelvin using Temperature = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Temperature", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Temperature", Temperature) /// \brief A component that stores temperature linear resolution in Kelvin using TemperatureLinearResolution = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.TemperatureLinearResolution", + "gz_sim_components.TemperatureLinearResolution", TemperatureLinearResolution) } } diff --git a/include/gz/sim/components/TemperatureRange.hh b/include/gz/sim/components/TemperatureRange.hh index 99e4a26151f..b56d938dae0 100644 --- a/include/gz/sim/components/TemperatureRange.hh +++ b/include/gz/sim/components/TemperatureRange.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_TEMPERATURERANGE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_TEMPERATURERANGE_HH_ +#ifndef GZ_SIM_COMPONENTS_TEMPERATURERANGE_HH_ +#define GZ_SIM_COMPONENTS_TEMPERATURERANGE_HH_ #include #include -#include +#include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -89,7 +89,7 @@ namespace components /// \brief A component that stores a temperature range in kelvin using TemperatureRange = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.TemperatureRange", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.TemperatureRange", TemperatureRange) } } diff --git a/include/gz/sim/components/ThermalCamera.hh b/include/gz/sim/components/ThermalCamera.hh index 5061070f84a..b636123287c 100644 --- a/include/gz/sim/components/ThermalCamera.hh +++ b/include/gz/sim/components/ThermalCamera.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_THERMALCAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_THERMALCAMERA_HH_ +#ifndef GZ_SIM_COMPONENTS_THERMALCAMERA_HH_ +#define GZ_SIM_COMPONENTS_THERMALCAMERA_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -36,7 +36,7 @@ namespace components /// sdf::Sensor, information. using ThermalCamera = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ThermalCamera", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.ThermalCamera", ThermalCamera) } } diff --git a/include/gz/sim/components/ThreadPitch.hh b/include/gz/sim/components/ThreadPitch.hh index 0a9f2c0551f..3a29a94e930 100644 --- a/include/gz/sim/components/ThreadPitch.hh +++ b/include/gz/sim/components/ThreadPitch.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_THREADPITCH_HH_ -#define IGNITION_GAZEBO_COMPONENTS_THREADPITCH_HH_ +#ifndef GZ_SIM_COMPONENTS_THREADPITCH_HH_ +#define GZ_SIM_COMPONENTS_THREADPITCH_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { @@ -32,7 +32,7 @@ namespace components /// \brief A component used to store the thread pitch of a screw joint using ThreadPitch = Component; IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.ThreadPitch", ThreadPitch) + "gz_sim_components.ThreadPitch", ThreadPitch) } } } diff --git a/include/gz/sim/components/Transparency.hh b/include/gz/sim/components/Transparency.hh index 1c2a9f3c3d2..abb3dafe469 100644 --- a/include/gz/sim/components/Transparency.hh +++ b/include/gz/sim/components/Transparency.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_TRANSPARENCY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_TRANSPARENCY_HH_ +#ifndef GZ_SIM_COMPONENTS_TRANSPARENCY_HH_ +#define GZ_SIM_COMPONENTS_TRANSPARENCY_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { @@ -33,7 +33,7 @@ namespace components /// e.g. visual entities. Value is in the range from 0 (opaque) to /// 1 (transparent). using Transparency = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Transparency", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Transparency", Transparency) } } diff --git a/include/gz/sim/components/Visibility.hh b/include/gz/sim/components/Visibility.hh index 7a53ddbb3e7..c4056ea87e2 100644 --- a/include/gz/sim/components/Visibility.hh +++ b/include/gz/sim/components/Visibility.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_VISIBILITY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_VISIBILITY_HH_ +#ifndef GZ_SIM_COMPONENTS_VISIBILITY_HH_ +#define GZ_SIM_COMPONENTS_VISIBILITY_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -32,13 +32,13 @@ namespace components { /// \brief This component holds an entity's visibility flags (visual entities) using VisibilityFlags = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.VisibilityFlags", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_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", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.VisibilityMask", VisibilityMask) } } diff --git a/include/gz/sim/components/Visual.hh b/include/gz/sim/components/Visual.hh index de948180598..6336117d8b6 100644 --- a/include/gz/sim/components/Visual.hh +++ b/include/gz/sim/components/Visual.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_VISUAL_HH_ -#define IGNITION_GAZEBO_COMPONENTS_VISUAL_HH_ +#ifndef GZ_SIM_COMPONENTS_VISUAL_HH_ +#define GZ_SIM_COMPONENTS_VISUAL_HH_ #include #include #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -78,13 +78,13 @@ namespace components { /// \brief A component that identifies an entity as being a visual. using Visual = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Visual", Visual) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Visual", Visual) /// \brief A component that contains a visual plugin's SDF element. using VisualPlugin = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.VisualPlugin", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.VisualPlugin", VisualPlugin) } } diff --git a/include/gz/sim/components/VisualCmd.hh b/include/gz/sim/components/VisualCmd.hh index 794057aabb7..7d1cc2a9376 100644 --- a/include/gz/sim/components/VisualCmd.hh +++ b/include/gz/sim/components/VisualCmd.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_VISUALCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_VISUALCMD_HH_ +#ifndef GZ_SIM_COMPONENTS_VISUALCMD_HH_ +#define GZ_SIM_COMPONENTS_VISUALCMD_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include +#include #include @@ -39,7 +39,7 @@ namespace components /// entity in the world frame represented by msgs::Visual. using VisualCmd = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.VisualCmd", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.VisualCmd", VisualCmd) } } diff --git a/include/gz/sim/components/Volume.hh b/include/gz/sim/components/Volume.hh index 75a0ee8135a..e70c9d69a52 100644 --- a/include/gz/sim/components/Volume.hh +++ b/include/gz/sim/components/Volume.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_VOLUME_HH_ -#define IGNITION_GAZEBO_COMPONENTS_VOLUME_HH_ +#ifndef GZ_SIM_COMPONENTS_VOLUME_HH_ +#define GZ_SIM_COMPONENTS_VOLUME_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { @@ -32,7 +32,7 @@ namespace components /// \brief A volume component where the units are m^3. /// Double value indicates volume of an entity. using Volume = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Volume", Volume) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Volume", Volume) } } } diff --git a/include/gz/sim/components/WheelSlipCmd.hh b/include/gz/sim/components/WheelSlipCmd.hh index 4daf7ee249b..10be1a46147 100644 --- a/include/gz/sim/components/WheelSlipCmd.hh +++ b/include/gz/sim/components/WheelSlipCmd.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ +#ifndef GZ_SIM_COMPONENTS_WHEELSLIPCMD_HH_ +#define GZ_SIM_COMPONENTS_WHEELSLIPCMD_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include +#include namespace ignition { @@ -37,7 +37,7 @@ namespace components /// an entity in the world frame represented by msgs::WheelSlipParameters. using WheelSlipCmd = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WheelSlipCmd", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.WheelSlipCmd", WheelSlipCmd) } } diff --git a/include/gz/sim/components/WideAngleCamera.hh b/include/gz/sim/components/WideAngleCamera.hh index ebb166a7a7a..ec2b8d81458 100644 --- a/include/gz/sim/components/WideAngleCamera.hh +++ b/include/gz/sim/components/WideAngleCamera.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_WIDEANGLECAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_WIDEANGLECAMERA_HH_ +#ifndef GZ_SIM_COMPONENTS_WIDEANGLECAMERA_HH_ +#define GZ_SIM_COMPONENTS_WIDEANGLECAMERA_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -36,7 +36,7 @@ namespace components /// sdf::Camera, information. using WideAngleCamera = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WideAngleCamera", + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.WideAngleCamera", WideAngleCamera) } } diff --git a/include/gz/sim/components/Wind.hh b/include/gz/sim/components/Wind.hh index 1fc93494937..310fb3e28de 100644 --- a/include/gz/sim/components/Wind.hh +++ b/include/gz/sim/components/Wind.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_WIND_HH_ -#define IGNITION_GAZEBO_COMPONENTS_WIND_HH_ +#ifndef GZ_SIM_COMPONENTS_WIND_HH_ +#define GZ_SIM_COMPONENTS_WIND_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { @@ -31,7 +31,7 @@ namespace components { /// \brief A component that identifies an entity as being a wind. using Wind = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Wind", Wind) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Wind", Wind) } } } diff --git a/include/gz/sim/components/WindMode.hh b/include/gz/sim/components/WindMode.hh index 04cac9ce3d3..0d17ee365d0 100644 --- a/include/gz/sim/components/WindMode.hh +++ b/include/gz/sim/components/WindMode.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_WINDMODE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_WINDMODE_HH_ +#ifndef GZ_SIM_COMPONENTS_WINDMODE_HH_ +#define GZ_SIM_COMPONENTS_WINDMODE_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { @@ -31,7 +31,7 @@ namespace components { /// \brief A component used to indicate whether an entity is affected by wind. using WindMode = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WindMode", WindMode) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.WindMode", WindMode) } } } diff --git a/include/gz/sim/components/World.hh b/include/gz/sim/components/World.hh index bb37c0e8d5a..48501e06644 100644 --- a/include/gz/sim/components/World.hh +++ b/include/gz/sim/components/World.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_WORLD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_WORLD_HH_ +#ifndef GZ_SIM_COMPONENTS_WORLD_HH_ +#define GZ_SIM_COMPONENTS_WORLD_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -33,11 +33,11 @@ namespace components { /// \brief A component that identifies an entity as being a world. using World = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.World", World) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.World", World) /// \brief A component that holds the world's SDF DOM using WorldSdf = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WorldSdf", WorldSdf) + IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.WorldSdf", WorldSdf) } } } diff --git a/include/gz/sim/detail/BaseView.hh b/include/gz/sim/detail/BaseView.hh index 9c1761d604b..3fc53d44537 100644 --- a/include/gz/sim/detail/BaseView.hh +++ b/include/gz/sim/detail/BaseView.hh @@ -14,17 +14,17 @@ * 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 #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/detail/ComponentStorageBase.hh b/include/gz/sim/detail/ComponentStorageBase.hh index c60c237162e..78e7cf9dc58 100644 --- a/include/gz/sim/detail/ComponentStorageBase.hh +++ b/include/gz/sim/detail/ComponentStorageBase.hh @@ -14,10 +14,10 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_DETAIL_COMPONENTSTORAGEBASE_HH_ -#define IGNITION_GAZEBO_DETAIL_COMPONENTSTORAGEBASE_HH_ +#ifndef GZ_GAZEBO_DETAIL_COMPONENTSTORAGEBASE_HH_ +#define GZ_GAZEBO_DETAIL_COMPONENTSTORAGEBASE_HH_ -#include "ignition/gazebo/Export.hh" +#include "gz/sim/Export.hh" namespace ignition { diff --git a/include/gz/sim/detail/EntityComponentManager.hh b/include/gz/sim/detail/EntityComponentManager.hh index 199be4bb7aa..9fa09d06e2c 100644 --- a/include/gz/sim/detail/EntityComponentManager.hh +++ b/include/gz/sim/detail/EntityComponentManager.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_DETAIL_ENTITYCOMPONENTMANAGER_HH_ -#define IGNITION_GAZEBO_DETAIL_ENTITYCOMPONENTMANAGER_HH_ +#ifndef GZ_GAZEBO_DETAIL_ENTITYCOMPONENTMANAGER_HH_ +#define GZ_GAZEBO_DETAIL_ENTITYCOMPONENTMANAGER_HH_ #include #include @@ -28,9 +28,9 @@ #include #include -#include +#include -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/EntityComponentManager.hh" namespace ignition { diff --git a/include/gz/sim/detail/View.hh b/include/gz/sim/detail/View.hh index 7a214cf1fb4..05c541bc458 100644 --- a/include/gz/sim/detail/View.hh +++ b/include/gz/sim/detail/View.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_DETAIL_VIEW_HH_ -#define IGNITION_GAZEBO_DETAIL_VIEW_HH_ +#ifndef GZ_GAZEBO_DETAIL_VIEW_HH_ +#define GZ_GAZEBO_DETAIL_VIEW_HH_ #include #include @@ -24,12 +24,12 @@ #include #include -#include +#include -#include "ignition/gazebo/components/Component.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/detail/BaseView.hh" +#include "gz/sim/components/Component.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/config.hh" +#include "gz/sim/detail/BaseView.hh" namespace ignition { diff --git a/include/gz/sim/gui/Gui.hh b/include/gz/sim/gui/Gui.hh index 39cb1f641c2..75f265afed6 100644 --- a/include/gz/sim/gui/Gui.hh +++ b/include/gz/sim/gui/Gui.hh @@ -15,14 +15,14 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_GUI_HH_ -#define IGNITION_GAZEBO_GUI_GUI_HH_ +#ifndef GZ_GAZEBO_GUI_GUI_HH_ +#define GZ_GAZEBO_GUI_GUI_HH_ #include -#include +#include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/gui/Export.hh" +#include "gz/sim/config.hh" +#include "gz/sim/gui/Export.hh" namespace ignition { @@ -40,7 +40,7 @@ namespace gui /// \param[in] _argv Command line arguments (Used when running without /// ign-tools. Set to the name of the application if using ign-tools) /// \param[in] _guiConfig The GUI configuration file. If nullptr, the default - /// configuration from IGN_HOMEDIR/.ignition/gazebo/gui.config will be used. + /// configuration from IGN_HOMEDIR/.gz/sim/gui.config will be used. /// \param[in] _renderEngineGui --render-engine-gui option /// \return -1 on failure, 0 on success IGNITION_GAZEBO_GUI_VISIBLE int runGui(int &_argc, @@ -54,12 +54,12 @@ namespace gui /// \param[in] _argv Command line arguments (Used when running without /// ign-tools. Set to the name of the application if using ign-tools) /// \param[in] _guiConfig The GUI configuration file. If nullptr, the default - /// configuration from IGN_HOMEDIR/.ignition/gazebo/gui.config will be used. + /// configuration from IGN_HOMEDIR/.gz/sim/gui.config will be used. /// \param[in] _defaultGuiConfig The default GUI configuration file. If no /// plugins were added from a world file or from _guiConfig, this /// configuration file will be loaded. If this argument is a nullptr or if the /// file does not exist, the default configuration from - /// IGN_HOMEDIR/.ignition/gazebo/gui.config will be used. + /// IGN_HOMEDIR/.gz/sim/gui.config will be used. /// \param[in] _loadPluginsFromSdf If true, plugins specified in the world /// SDFormat file will get loaded. /// \param[in] _renderEngineGui --render-engine-gui option diff --git a/include/gz/sim/gui/GuiEvents.hh b/include/gz/sim/gui/GuiEvents.hh index afbb751879e..27b20020377 100644 --- a/include/gz/sim/gui/GuiEvents.hh +++ b/include/gz/sim/gui/GuiEvents.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_GUIEVENTS_HH_ -#define IGNITION_GAZEBO_GUI_GUIEVENTS_HH_ +#ifndef GZ_GAZEBO_GUI_GUIEVENTS_HH_ +#define GZ_GAZEBO_GUI_GUIEVENTS_HH_ #include #include @@ -26,13 +26,13 @@ #include #include -#include -#include +#include +#include #include -#include "ignition/gazebo/gui/Export.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/config.hh" +#include "gz/sim/gui/Export.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/config.hh" namespace ignition { @@ -241,4 +241,4 @@ namespace events } // namespace gazebo } // namespace ignition -#endif // IGNITION_GAZEBO_GUI_GUIEVENTS_HH_ +#endif // GZ_GAZEBO_GUI_GUIEVENTS_HH_ diff --git a/include/gz/sim/gui/GuiSystem.hh b/include/gz/sim/gui/GuiSystem.hh index 4d2a836869a..eb4db4ac9dc 100644 --- a/include/gz/sim/gui/GuiSystem.hh +++ b/include/gz/sim/gui/GuiSystem.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_GUISYSTEM_HH_ -#define IGNITION_GAZEBO_GUI_GUISYSTEM_HH_ +#ifndef GZ_GAZEBO_GUI_GUISYSTEM_HH_ +#define GZ_GAZEBO_GUI_GUISYSTEM_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include #include diff --git a/include/gz/sim/physics/Events.hh b/include/gz/sim/physics/Events.hh index 668e19a2ad7..c49f39f13cc 100644 --- a/include/gz/sim/physics/Events.hh +++ b/include/gz/sim/physics/Events.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_PHYSICS_EVENTS_HH_ -#define IGNITION_GAZEBO_PHYSICS_EVENTS_HH_ +#ifndef GZ_GAZEBO_PHYSICS_EVENTS_HH_ +#define GZ_GAZEBO_PHYSICS_EVENTS_HH_ #include -#include +#include -#include +#include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Entity.hh" +#include "gz/sim/config.hh" +#include "gz/sim/Entity.hh" #include @@ -62,4 +62,4 @@ namespace ignition } // namespace gazebo } // namespace ignition -#endif // IGNITION_GAZEBO_PHYSICS_EVENTS_HH_ +#endif // GZ_GAZEBO_PHYSICS_EVENTS_HH_ diff --git a/include/gz/sim/rendering/Events.hh b/include/gz/sim/rendering/Events.hh index 683c66f5299..a2db9a7e82b 100644 --- a/include/gz/sim/rendering/Events.hh +++ b/include/gz/sim/rendering/Events.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_RENDERING_EVENTS_HH_ -#define IGNITION_GAZEBO_RENDERING_EVENTS_HH_ +#ifndef GZ_GAZEBO_RENDERING_EVENTS_HH_ +#define GZ_GAZEBO_RENDERING_EVENTS_HH_ -#include +#include -#include "ignition/gazebo/config.hh" +#include "gz/sim/config.hh" namespace ignition { @@ -70,4 +70,4 @@ namespace ignition } // namespace gazebo } // namespace ignition -#endif // IGNITION_GAZEBO_RENDEREVENTS_HH_ +#endif // GZ_GAZEBO_RENDEREVENTS_HH_ diff --git a/include/gz/sim/rendering/MarkerManager.hh b/include/gz/sim/rendering/MarkerManager.hh index 691d08fdbc8..18f4fbe643d 100644 --- a/include/gz/sim/rendering/MarkerManager.hh +++ b/include/gz/sim/rendering/MarkerManager.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_MARKERMANAGER_HH_ -#define IGNITION_GAZEBO_MARKERMANAGER_HH_ +#ifndef GZ_GAZEBO_MARKERMANAGER_HH_ +#define GZ_GAZEBO_MARKERMANAGER_HH_ #include #include -#include +#include -#include "ignition/rendering/RenderTypes.hh" +#include "gz/rendering/RenderTypes.hh" namespace ignition { diff --git a/include/gz/sim/rendering/RenderUtil.hh b/include/gz/sim/rendering/RenderUtil.hh index a757ec53786..2fd68e7169b 100644 --- a/include/gz/sim/rendering/RenderUtil.hh +++ b/include/gz/sim/rendering/RenderUtil.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_RENDERUTIL_HH_ -#define IGNITION_GAZEBO_RENDERUTIL_HH_ +#ifndef GZ_GAZEBO_RENDERUTIL_HH_ +#define GZ_GAZEBO_RENDERUTIL_HH_ #include #include @@ -24,12 +24,12 @@ #include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/rendering/SceneManager.hh" -#include "ignition/gazebo/rendering/MarkerManager.hh" +#include "gz/sim/rendering/SceneManager.hh" +#include "gz/sim/rendering/MarkerManager.hh" namespace ignition @@ -41,7 +41,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { // forward declaration class RenderUtilPrivate; - /// \class RenderUtil RenderUtil.hh ignition/gazebo/gui/plugins/RenderUtil.hh + /// \class RenderUtil RenderUtil.hh gz/sim/gui/plugins/RenderUtil.hh class IGNITION_GAZEBO_RENDERING_VISIBLE RenderUtil { /// \brief Constructor diff --git a/include/gz/sim/rendering/SceneManager.hh b/include/gz/sim/rendering/SceneManager.hh index 1ea41fb3488..31524aaaadf 100644 --- a/include/gz/sim/rendering/SceneManager.hh +++ b/include/gz/sim/rendering/SceneManager.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_SCENEMANAGER_HH_ -#define IGNITION_GAZEBO_SCENEMANAGER_HH_ +#ifndef GZ_GAZEBO_SCENEMANAGER_HH_ +#define GZ_GAZEBO_SCENEMANAGER_HH_ #include #include @@ -33,17 +33,17 @@ #include #include -#include -#include -#include +#include +#include +#include -#include +#include -#include +#include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/sim.hh.in b/include/gz/sim/sim.hh.in index d9d633cc593..8772fcbd3e2 100644 --- a/include/gz/sim/sim.hh.in +++ b/include/gz/sim/sim.hh.in @@ -1,3 +1,3 @@ // Automatically generated -#include /config.hh> +#include /config.hh> ${ign_headers} diff --git a/src/Barrier.hh b/src/Barrier.hh index e0f6dcf10d5..5b9792b722f 100644 --- a/src/Barrier.hh +++ b/src/Barrier.hh @@ -23,8 +23,8 @@ #include #include -#include -#include +#include +#include namespace ignition { diff --git a/src/BaseView.cc b/src/BaseView.cc index 276b2ac175c..d366d946c7a 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/BaseView_TEST.cc b/src/BaseView_TEST.cc index 4fa3db60c7f..b4365b41071 100644 --- a/src/BaseView_TEST.cc +++ b/src/BaseView_TEST.cc @@ -19,13 +19,13 @@ #include -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/Types.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/detail/BaseView.hh" -#include "ignition/gazebo/detail/View.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/Types.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/detail/BaseView.hh" +#include "gz/sim/detail/View.hh" #include "../test/helpers/EnvTestFixture.hh" diff --git a/src/ComponentFactory_TEST.cc b/src/ComponentFactory_TEST.cc index e9adeb972a5..5d8e1285b89 100644 --- a/src/ComponentFactory_TEST.cc +++ b/src/ComponentFactory_TEST.cc @@ -16,11 +16,11 @@ */ #include -#include "ignition/gazebo/test_config.hh" -#include "ignition/gazebo/components/Component.hh" -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" +#include "gz/sim/test_config.hh" +#include "gz/sim/components/Component.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" #include "../test/helpers/EnvTestFixture.hh" diff --git a/src/Component_TEST.cc b/src/Component_TEST.cc index 586b0dd4c4b..1f338dae4ce 100644 --- a/src/Component_TEST.cc +++ b/src/Component_TEST.cc @@ -25,10 +25,10 @@ #include #include -#include "ignition/gazebo/components/Component.hh" -#include "ignition/gazebo/components/Serialization.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/components/Component.hh" +#include "gz/sim/components/Serialization.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/EntityComponentManager.hh" #include "../test/helpers/EnvTestFixture.hh" diff --git a/src/Conversions.cc b/src/Conversions.cc index 95c28ed8104..57725481ec6 100644 --- a/src/Conversions.cc +++ b/src/Conversions.cc @@ -69,9 +69,9 @@ #include #include -#include "ignition/gazebo/Conversions.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Conversions.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Util.hh" using namespace ignition; diff --git a/src/Conversions_TEST.cc b/src/Conversions_TEST.cc index d4e67d8f494..3b15d8f8e82 100644 --- a/src/Conversions_TEST.cc +++ b/src/Conversions_TEST.cc @@ -40,7 +40,7 @@ #include -#include "ignition/gazebo/Conversions.hh" +#include "gz/sim/Conversions.hh" using namespace ignition; using namespace gazebo; diff --git a/src/EntityComponentManager.cc b/src/EntityComponentManager.cc index 201f21bf01c..1ebb5dafef6 100644 --- a/src/EntityComponentManager.cc +++ b/src/EntityComponentManager.cc @@ -15,7 +15,7 @@ * */ -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/EntityComponentManager.hh" #include "EntityComponentManagerDiff.hh" #include @@ -31,17 +31,17 @@ #include #include -#include "ignition/gazebo/components/CanonicalLink.hh" -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/Component.hh" -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Joint.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/Recreate.hh" -#include "ignition/gazebo/components/World.hh" +#include "gz/sim/components/CanonicalLink.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/Component.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Joint.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/Recreate.hh" +#include "gz/sim/components/World.hh" using namespace ignition; using namespace gazebo; diff --git a/src/EntityComponentManagerDiff.cc b/src/EntityComponentManagerDiff.cc index 6be7a87b951..09c9aef091d 100644 --- a/src/EntityComponentManagerDiff.cc +++ b/src/EntityComponentManagerDiff.cc @@ -17,7 +17,7 @@ #include "EntityComponentManagerDiff.hh" -#include "ignition/gazebo/Entity.hh" +#include "gz/sim/Entity.hh" using namespace ignition; using namespace gazebo; diff --git a/src/EntityComponentManagerDiff.hh b/src/EntityComponentManagerDiff.hh index 505040e120a..9a3c6b59ef5 100644 --- a/src/EntityComponentManagerDiff.hh +++ b/src/EntityComponentManagerDiff.hh @@ -18,9 +18,9 @@ #ifndef IGNITION_GAZEBO_ENTITYCOMPONENTMANAGER_DIFF_HH_ #define IGNITION_GAZEBO_ENTITYCOMPONENTMANAGER_DIFF_HH_ -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Types.hh" #include diff --git a/src/EntityComponentManager_TEST.cc b/src/EntityComponentManager_TEST.cc index 7a7a6ff1717..b082b750ea1 100644 --- a/src/EntityComponentManager_TEST.cc +++ b/src/EntityComponentManager_TEST.cc @@ -24,17 +24,17 @@ #include #include -#include "ignition/gazebo/components/CanonicalLink.hh" -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Joint.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/EntityComponentManager.hh" -#include "ignition/gazebo/config.hh" +#include "gz/sim/components/CanonicalLink.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Joint.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/EntityComponentManager.hh" +#include "gz/sim/config.hh" #include "EntityComponentManagerDiff.hh" #include "../test/helpers/EnvTestFixture.hh" diff --git a/src/EventManager_TEST.cc b/src/EventManager_TEST.cc index c68335e7235..dd32fc802d2 100644 --- a/src/EventManager_TEST.cc +++ b/src/EventManager_TEST.cc @@ -19,8 +19,8 @@ #include -#include "ignition/gazebo/Events.hh" -#include "ignition/gazebo/EventManager.hh" +#include "gz/sim/Events.hh" +#include "gz/sim/EventManager.hh" using namespace ignition::gazebo; diff --git a/src/LevelManager.cc b/src/LevelManager.cc index 81fa242484a..2aecfbb8f70 100644 --- a/src/LevelManager.cc +++ b/src/LevelManager.cc @@ -28,35 +28,35 @@ #include #include -#include "ignition/gazebo/Events.hh" -#include "ignition/gazebo/EntityComponentManager.hh" - -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/Atmosphere.hh" -#include "ignition/gazebo/components/Geometry.hh" -#include "ignition/gazebo/components/Gravity.hh" -#include "ignition/gazebo/components/Level.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/LevelBuffer.hh" -#include "ignition/gazebo/components/LevelEntityNames.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/Performer.hh" -#include "ignition/gazebo/components/PerformerLevels.hh" -#include "ignition/gazebo/components/Physics.hh" -#include "ignition/gazebo/components/PhysicsEnginePlugin.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/RenderEngineGuiPlugin.hh" -#include "ignition/gazebo/components/RenderEngineServerHeadless.hh" -#include "ignition/gazebo/components/RenderEngineServerPlugin.hh" -#include "ignition/gazebo/components/Scene.hh" -#include "ignition/gazebo/components/SphericalCoordinates.hh" -#include "ignition/gazebo/components/Wind.hh" -#include "ignition/gazebo/components/World.hh" +#include "gz/sim/Events.hh" +#include "gz/sim/EntityComponentManager.hh" + +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/Atmosphere.hh" +#include "gz/sim/components/Geometry.hh" +#include "gz/sim/components/Gravity.hh" +#include "gz/sim/components/Level.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/LevelBuffer.hh" +#include "gz/sim/components/LevelEntityNames.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/Performer.hh" +#include "gz/sim/components/PerformerLevels.hh" +#include "gz/sim/components/Physics.hh" +#include "gz/sim/components/PhysicsEnginePlugin.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/RenderEngineGuiPlugin.hh" +#include "gz/sim/components/RenderEngineServerHeadless.hh" +#include "gz/sim/components/RenderEngineServerPlugin.hh" +#include "gz/sim/components/Scene.hh" +#include "gz/sim/components/SphericalCoordinates.hh" +#include "gz/sim/components/Wind.hh" +#include "gz/sim/components/World.hh" #include "SimulationRunner.hh" diff --git a/src/LevelManager.hh b/src/LevelManager.hh index 556ad87d29e..63d4c8988eb 100644 --- a/src/LevelManager.hh +++ b/src/LevelManager.hh @@ -33,10 +33,10 @@ #include #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/SdfEntityCreator.hh" -#include "ignition/gazebo/Types.hh" +#include "gz/sim/config.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/SdfEntityCreator.hh" +#include "gz/sim/Types.hh" namespace ignition { diff --git a/src/Link.cc b/src/Link.cc index 82d860fdb1a..b24bbaa4a71 100644 --- a/src/Link.cc +++ b/src/Link.cc @@ -17,27 +17,27 @@ #include -#include "ignition/gazebo/components/AngularAcceleration.hh" -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/AngularVelocityCmd.hh" -#include "ignition/gazebo/components/CanonicalLink.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/ExternalWorldWrenchCmd.hh" -#include "ignition/gazebo/components/Inertial.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/LinearAcceleration.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/LinearVelocityCmd.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/Pose.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/WindMode.hh" -#include "ignition/gazebo/Util.hh" - -#include "ignition/gazebo/Link.hh" +#include "gz/sim/components/AngularAcceleration.hh" +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/AngularVelocityCmd.hh" +#include "gz/sim/components/CanonicalLink.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/ExternalWorldWrenchCmd.hh" +#include "gz/sim/components/Inertial.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/LinearAcceleration.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/LinearVelocityCmd.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/Pose.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/WindMode.hh" +#include "gz/sim/Util.hh" + +#include "gz/sim/Link.hh" class ignition::gazebo::LinkPrivate { diff --git a/src/Link_TEST.cc b/src/Link_TEST.cc index 5193c1f425e..c90937a8877 100644 --- a/src/Link_TEST.cc +++ b/src/Link_TEST.cc @@ -17,7 +17,7 @@ #include -#include "ignition/gazebo/Link.hh" +#include "gz/sim/Link.hh" ///////////////////////////////////////////////// TEST(LinkTest, Constructor) diff --git a/src/Model.cc b/src/Model.cc index 2dfa533e51b..356d0d78c67 100644 --- a/src/Model.cc +++ b/src/Model.cc @@ -15,17 +15,17 @@ * */ -#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/PoseCmd.hh" -#include "ignition/gazebo/components/SelfCollide.hh" -#include "ignition/gazebo/components/SourceFilePath.hh" -#include "ignition/gazebo/components/Static.hh" -#include "ignition/gazebo/components/WindMode.hh" -#include "ignition/gazebo/Model.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/PoseCmd.hh" +#include "gz/sim/components/SelfCollide.hh" +#include "gz/sim/components/SourceFilePath.hh" +#include "gz/sim/components/Static.hh" +#include "gz/sim/components/WindMode.hh" +#include "gz/sim/Model.hh" class ignition::gazebo::ModelPrivate { diff --git a/src/ModelCommandAPI_TEST.cc b/src/ModelCommandAPI_TEST.cc index 5102d589ec6..34362920f5b 100644 --- a/src/ModelCommandAPI_TEST.cc +++ b/src/ModelCommandAPI_TEST.cc @@ -22,8 +22,8 @@ #include #include -#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) static const std::string kIgnModelCommand( std::string(BREW_RUBY) + std::string(IGN_PATH) + "/ign model "); diff --git a/src/Model_TEST.cc b/src/Model_TEST.cc index 81304e2e16f..ad530f9bedf 100644 --- a/src/Model_TEST.cc +++ b/src/Model_TEST.cc @@ -19,12 +19,12 @@ #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Model.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 "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Model.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" ///////////////////////////////////////////////// TEST(ModelTest, Constructor) diff --git a/src/Primitives.cc b/src/Primitives.cc index 9e34eac618d..6e8de1aaed4 100644 --- a/src/Primitives.cc +++ b/src/Primitives.cc @@ -17,7 +17,7 @@ #include #include -#include "ignition/gazebo/Primitives.hh" +#include "gz/sim/Primitives.hh" using namespace ignition; using namespace gazebo; diff --git a/src/Primitives_TEST.cc b/src/Primitives_TEST.cc index b6635e61448..112e9480979 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.cc b/src/SdfEntityCreator.cc index d77dd33c36d..fa399bce8b9 100644 --- a/src/SdfEntityCreator.cc +++ b/src/SdfEntityCreator.cc @@ -19,66 +19,66 @@ #include #include -#include "ignition/gazebo/Events.hh" -#include "ignition/gazebo/SdfEntityCreator.hh" - -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/AirPressureSensor.hh" -#include "ignition/gazebo/components/Altimeter.hh" -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/Atmosphere.hh" -#include "ignition/gazebo/components/Camera.hh" -#include "ignition/gazebo/components/CanonicalLink.hh" -#include "ignition/gazebo/components/CastShadows.hh" -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/ContactSensor.hh" -#include "ignition/gazebo/components/CustomSensor.hh" -#include "ignition/gazebo/components/DepthCamera.hh" -#include "ignition/gazebo/components/ForceTorque.hh" -#include "ignition/gazebo/components/Geometry.hh" -#include "ignition/gazebo/components/GpuLidar.hh" -#include "ignition/gazebo/components/Gravity.hh" -#include "ignition/gazebo/components/Imu.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/LaserRetro.hh" -#include "ignition/gazebo/components/Lidar.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/LightType.hh" -#include "ignition/gazebo/components/LinearAcceleration.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/LogicalCamera.hh" -#include "ignition/gazebo/components/MagneticField.hh" -#include "ignition/gazebo/components/Magnetometer.hh" -#include "ignition/gazebo/components/Material.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/NavSat.hh" -#include "ignition/gazebo/components/ParentLinkName.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include -#include "ignition/gazebo/components/Physics.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/RgbdCamera.hh" -#include "ignition/gazebo/components/Scene.hh" -#include "ignition/gazebo/components/SegmentationCamera.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/ThermalCamera.hh" -#include "ignition/gazebo/components/ThreadPitch.hh" -#include "ignition/gazebo/components/Transparency.hh" -#include "ignition/gazebo/components/Visibility.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/WideAngleCamera.hh" -#include "ignition/gazebo/components/WindMode.hh" -#include "ignition/gazebo/components/World.hh" +#include "gz/sim/Events.hh" +#include "gz/sim/SdfEntityCreator.hh" + +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/AirPressureSensor.hh" +#include "gz/sim/components/Altimeter.hh" +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/Atmosphere.hh" +#include "gz/sim/components/Camera.hh" +#include "gz/sim/components/CanonicalLink.hh" +#include "gz/sim/components/CastShadows.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/ContactSensor.hh" +#include "gz/sim/components/CustomSensor.hh" +#include "gz/sim/components/DepthCamera.hh" +#include "gz/sim/components/ForceTorque.hh" +#include "gz/sim/components/Geometry.hh" +#include "gz/sim/components/GpuLidar.hh" +#include "gz/sim/components/Gravity.hh" +#include "gz/sim/components/Imu.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/LaserRetro.hh" +#include "gz/sim/components/Lidar.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/LightType.hh" +#include "gz/sim/components/LinearAcceleration.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/LogicalCamera.hh" +#include "gz/sim/components/MagneticField.hh" +#include "gz/sim/components/Magnetometer.hh" +#include "gz/sim/components/Material.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/NavSat.hh" +#include "gz/sim/components/ParentLinkName.hh" +#include "gz/sim/components/ParentEntity.hh" +#include +#include "gz/sim/components/Physics.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/RgbdCamera.hh" +#include "gz/sim/components/Scene.hh" +#include "gz/sim/components/SegmentationCamera.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/ThermalCamera.hh" +#include "gz/sim/components/ThreadPitch.hh" +#include "gz/sim/components/Transparency.hh" +#include "gz/sim/components/Visibility.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/WideAngleCamera.hh" +#include "gz/sim/components/WindMode.hh" +#include "gz/sim/components/World.hh" class ignition::gazebo::SdfEntityCreatorPrivate { diff --git a/src/SdfEntityCreator_TEST.cc b/src/SdfEntityCreator_TEST.cc index 12554dbf7ed..b8c9531d925 100644 --- a/src/SdfEntityCreator_TEST.cc +++ b/src/SdfEntityCreator_TEST.cc @@ -27,31 +27,31 @@ #include #include -#include "ignition/gazebo/test_config.hh" -#include "ignition/gazebo/components/CanonicalLink.hh" -#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/LaserRetro.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/Link.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/Physics.hh" -#include "ignition/gazebo/components/Pose.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/SdfEntityCreator.hh" +#include "gz/sim/test_config.hh" +#include "gz/sim/components/CanonicalLink.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/LaserRetro.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/Link.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/Physics.hh" +#include "gz/sim/components/Pose.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/SdfEntityCreator.hh" #include "../test/helpers/EnvTestFixture.hh" diff --git a/src/SdfGenerator.cc b/src/SdfGenerator.cc index 9f8b9286c2a..1722a18bce6 100644 --- a/src/SdfGenerator.cc +++ b/src/SdfGenerator.cc @@ -25,39 +25,39 @@ #include -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/components/AirPressureSensor.hh" -#include "ignition/gazebo/components/Altimeter.hh" -#include "ignition/gazebo/components/Camera.hh" -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/ContactSensor.hh" -#include "ignition/gazebo/components/DepthCamera.hh" -#include "ignition/gazebo/components/ForceTorque.hh" -#include "ignition/gazebo/components/GpuLidar.hh" -#include "ignition/gazebo/components/Imu.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/Light.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/LogicalCamera.hh" -#include "ignition/gazebo/components/Magnetometer.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/RgbdCamera.hh" -#include "ignition/gazebo/components/SelfCollide.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/SourceFilePath.hh" -#include "ignition/gazebo/components/SegmentationCamera.hh" -#include "ignition/gazebo/components/Static.hh" -#include "ignition/gazebo/components/ThermalCamera.hh" -#include "ignition/gazebo/components/ThreadPitch.hh" -#include "ignition/gazebo/components/WindMode.hh" -#include "ignition/gazebo/components/World.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/components/AirPressureSensor.hh" +#include "gz/sim/components/Altimeter.hh" +#include "gz/sim/components/Camera.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/ContactSensor.hh" +#include "gz/sim/components/DepthCamera.hh" +#include "gz/sim/components/ForceTorque.hh" +#include "gz/sim/components/GpuLidar.hh" +#include "gz/sim/components/Imu.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/Light.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/LogicalCamera.hh" +#include "gz/sim/components/Magnetometer.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/RgbdCamera.hh" +#include "gz/sim/components/SelfCollide.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/SourceFilePath.hh" +#include "gz/sim/components/SegmentationCamera.hh" +#include "gz/sim/components/Static.hh" +#include "gz/sim/components/ThermalCamera.hh" +#include "gz/sim/components/ThreadPitch.hh" +#include "gz/sim/components/WindMode.hh" +#include "gz/sim/components/World.hh" namespace ignition diff --git a/src/SdfGenerator.hh b/src/SdfGenerator.hh index 83a7844c293..c4327ddb241 100644 --- a/src/SdfGenerator.hh +++ b/src/SdfGenerator.hh @@ -24,7 +24,7 @@ #include #include -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/EntityComponentManager.hh" namespace ignition { diff --git a/src/SdfGenerator_TEST.cc b/src/SdfGenerator_TEST.cc index 817ea26a09a..1e0d603c803 100644 --- a/src/SdfGenerator_TEST.cc +++ b/src/SdfGenerator_TEST.cc @@ -26,19 +26,19 @@ #include #include -#include "ignition/gazebo/EventManager.hh" -#include "ignition/gazebo/SdfEntityCreator.hh" -#include "ignition/gazebo/components/Collision.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/Pose.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/EventManager.hh" +#include "gz/sim/SdfEntityCreator.hh" +#include "gz/sim/components/Collision.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/Pose.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/test_config.hh" #include "helpers/UniqueTestDirectoryEnv.hh" #include "helpers/EnvTestFixture.hh" diff --git a/src/Server.cc b/src/Server.cc index 87381ee516a..b16f0fa2a51 100644 --- a/src/Server.cc +++ b/src/Server.cc @@ -23,9 +23,9 @@ #include #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/Util.hh" #include "ServerPrivate.hh" #include "SimulationRunner.hh" diff --git a/src/ServerConfig.cc b/src/ServerConfig.cc index 1024eb5d11e..b6f4f8173a1 100644 --- a/src/ServerConfig.cc +++ b/src/ServerConfig.cc @@ -14,7 +14,7 @@ * limitations under the License. * */ -#include "ignition/gazebo/ServerConfig.hh" +#include "gz/sim/ServerConfig.hh" #include @@ -25,7 +25,7 @@ #include #include -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/ServerConfig_TEST.cc b/src/ServerConfig_TEST.cc index bc93120ef23..943dae03c55 100644 --- a/src/ServerConfig_TEST.cc +++ b/src/ServerConfig_TEST.cc @@ -18,9 +18,9 @@ #include #include -#include -#include -#include +#include +#include +#include using namespace ignition; using namespace gazebo; diff --git a/src/ServerPrivate.cc b/src/ServerPrivate.cc index 7bd36065ce0..f9de05dc435 100644 --- a/src/ServerPrivate.cc +++ b/src/ServerPrivate.cc @@ -26,7 +26,7 @@ #include -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Util.hh" #include "SimulationRunner.hh" using namespace ignition; diff --git a/src/ServerPrivate.hh b/src/ServerPrivate.hh index b7f23c26d92..bdba559bdd1 100644 --- a/src/ServerPrivate.hh +++ b/src/ServerPrivate.hh @@ -42,10 +42,10 @@ #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/ServerConfig.hh" -#include "ignition/gazebo/SystemLoader.hh" +#include "gz/sim/config.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/ServerConfig.hh" +#include "gz/sim/SystemLoader.hh" using namespace std::chrono_literals; diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc index 3abe257a93f..66e677a42c0 100644 --- a/src/Server_TEST.cc +++ b/src/Server_TEST.cc @@ -25,17 +25,17 @@ #include #include -#include "ignition/gazebo/components/AxisAlignedBox.hh" -#include "ignition/gazebo/components/Geometry.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/System.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/Types.hh" -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/components/AxisAlignedBox.hh" +#include "gz/sim/components/Geometry.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/System.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/Types.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../test/helpers/Relay.hh" diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc index 0481a2df21b..f5f42277e60 100644 --- a/src/SimulationRunner.cc +++ b/src/SimulationRunner.cc @@ -22,18 +22,18 @@ #include #include "ignition/common/Profiler.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Physics.hh" -#include "ignition/gazebo/components/PhysicsCmd.hh" -#include "ignition/gazebo/components/Recreate.hh" -#include "ignition/gazebo/Events.hh" -#include "ignition/gazebo/SdfEntityCreator.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.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" +#include "gz/sim/Events.hh" +#include "gz/sim/SdfEntityCreator.hh" +#include "gz/sim/Util.hh" #include "network/NetworkManagerPrimary.hh" #include "SdfGenerator.hh" diff --git a/src/SimulationRunner.hh b/src/SimulationRunner.hh index 1b35c8c3d35..ff4dd51b44f 100644 --- a/src/SimulationRunner.hh +++ b/src/SimulationRunner.hh @@ -42,14 +42,14 @@ #include #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Conversions.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/EventManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/ServerConfig.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/Types.hh" +#include "gz/sim/config.hh" +#include "gz/sim/Conversions.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/EventManager.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/ServerConfig.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/Types.hh" #include "network/NetworkManager.hh" #include "LevelManager.hh" diff --git a/src/SimulationRunner_TEST.cc b/src/SimulationRunner_TEST.cc index 1ee191d7100..0329e66f0eb 100644 --- a/src/SimulationRunner_TEST.cc +++ b/src/SimulationRunner_TEST.cc @@ -33,30 +33,30 @@ #include -#include "ignition/gazebo/test_config.hh" -#include "ignition/gazebo/components/CanonicalLink.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/Light.hh" -#include "ignition/gazebo/components/Link.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/Pose.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/Wind.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Events.hh" -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/config.hh" +#include "gz/sim/test_config.hh" +#include "gz/sim/components/CanonicalLink.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/Light.hh" +#include "gz/sim/components/Link.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/Pose.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/Wind.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Events.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/config.hh" #include "../test/helpers/EnvTestFixture.hh" #include "SimulationRunner.hh" diff --git a/src/SystemInternal.hh b/src/SystemInternal.hh index cca49a965bd..01b1dfb6fcf 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/SystemLoader.cc b/src/SystemLoader.cc index 3a78dda509d..6e46c9f8d64 100644 --- a/src/SystemLoader.cc +++ b/src/SystemLoader.cc @@ -19,7 +19,7 @@ #include #include -#include +#include #include @@ -31,7 +31,7 @@ #include -#include +#include using namespace ignition::gazebo; @@ -54,7 +54,7 @@ class ignition::gazebo::SystemLoaderPrivate std::string homePath; ignition::common::env(IGN_HOMEDIR, homePath); - systemPaths.AddPluginPaths(homePath + "/.ignition/gazebo/plugins"); + systemPaths.AddPluginPaths(homePath + "/.gz/sim/plugins"); systemPaths.AddPluginPaths(IGN_GAZEBO_PLUGIN_INSTALL_DIR); auto pathToLib = systemPaths.FindSharedLibrary(_filename); diff --git a/src/SystemLoader_TEST.cc b/src/SystemLoader_TEST.cc index 2a06a7daacf..25f8df7313c 100644 --- a/src/SystemLoader_TEST.cc +++ b/src/SystemLoader_TEST.cc @@ -21,10 +21,10 @@ #include #include -#include "ignition/gazebo/System.hh" -#include "ignition/gazebo/SystemLoader.hh" +#include "gz/sim/System.hh" +#include "gz/sim/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/test_config.hh" // NOLINT(build/include) using namespace ignition; diff --git a/src/SystemManager.hh b/src/SystemManager.hh index f6f1e214a2e..1a6071ab0ef 100644 --- a/src/SystemManager.hh +++ b/src/SystemManager.hh @@ -21,11 +21,11 @@ #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 454f53e45a7..c5699701c37 100644 --- a/src/SystemManager_TEST.cc +++ b/src/SystemManager_TEST.cc @@ -17,11 +17,11 @@ #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/System.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/Types.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/test_config.hh" // NOLINT(build/include) #include "SystemManager.hh" diff --git a/src/System_TEST.cc b/src/System_TEST.cc index 03344009323..dbe29eef856 100644 --- a/src/System_TEST.cc +++ b/src/System_TEST.cc @@ -17,7 +17,7 @@ #include -#include "ignition/gazebo/System.hh" +#include "gz/sim/System.hh" using namespace ignition; diff --git a/src/TestFixture.cc b/src/TestFixture.cc index 8f1dffd9f55..cbe06851784 100644 --- a/src/TestFixture.cc +++ b/src/TestFixture.cc @@ -15,10 +15,10 @@ * */ -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/ServerConfig.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/ServerConfig.hh" -#include "ignition/gazebo/TestFixture.hh" +#include "gz/sim/TestFixture.hh" using namespace ignition; using namespace gazebo; diff --git a/src/TestFixture_TEST.cc b/src/TestFixture_TEST.cc index 4c6d244f872..0b3f8b6bb6b 100644 --- a/src/TestFixture_TEST.cc +++ b/src/TestFixture_TEST.cc @@ -20,11 +20,11 @@ #include #include -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/ServerConfig.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/ServerConfig.hh" +#include "gz/sim/test_config.hh" #include "../test/helpers/EnvTestFixture.hh" -#include "ignition/gazebo/TestFixture.hh" +#include "gz/sim/TestFixture.hh" using namespace ignition; using namespace gazebo; diff --git a/src/Util.cc b/src/Util.cc index b603697cf48..498e7806520 100644 --- a/src/Util.cc +++ b/src/Util.cc @@ -24,22 +24,22 @@ #include #include -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/Light.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/ParticleEmitter.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/SphericalCoordinates.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/World.hh" - -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/Light.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/ParticleEmitter.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/SphericalCoordinates.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.hh" + +#include "gz/sim/Util.hh" namespace ignition { diff --git a/src/Util_TEST.cc b/src/Util_TEST.cc index 3f2b4443a9d..fab30f7276a 100644 --- a/src/Util_TEST.cc +++ b/src/Util_TEST.cc @@ -23,20 +23,20 @@ #include -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/Light.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/ParticleEmitter.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/Light.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/ParticleEmitter.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Util.hh" #include "helpers/EnvTestFixture.hh" diff --git a/src/View.cc b/src/View.cc index 1b3fcc8df55..d5d48433ea8 100644 --- a/src/View.cc +++ b/src/View.cc @@ -15,7 +15,7 @@ * */ -#include "ignition/gazebo/detail/View.hh" +#include "gz/sim/detail/View.hh" namespace ignition { diff --git a/src/World.cc b/src/World.cc index 2d1514f79c5..598196310ea 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 "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/SphericalCoordinates.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/World.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 "gz/sim/components/SphericalCoordinates.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/World.hh" class ignition::gazebo::WorldPrivate { diff --git a/src/WorldControl.hh b/src/WorldControl.hh index 9016e8c8f43..9e57ac458f5 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/World_TEST.cc b/src/World_TEST.cc index 7c3a03d5326..06cd31b3dab 100644 --- a/src/World_TEST.cc +++ b/src/World_TEST.cc @@ -17,7 +17,7 @@ #include -#include "ignition/gazebo/World.hh" +#include "gz/sim/World.hh" ///////////////////////////////////////////////// TEST(WorldTest, Constructor) diff --git a/src/cmd/ModelCommandAPI.cc b/src/cmd/ModelCommandAPI.cc index 8e482b412dd..8418cab7628 100644 --- a/src/cmd/ModelCommandAPI.cc +++ b/src/cmd/ModelCommandAPI.cc @@ -35,27 +35,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 +#include +#include +#include +#include +#include +#include +#include #include using namespace ignition; diff --git a/src/cmd/cmdgazebo.rb.in b/src/cmd/cmdgazebo.rb.in index dfb46fec7b1..36fd7c65171 100755 --- a/src/cmd/cmdgazebo.rb.in +++ b/src/cmd/cmdgazebo.rb.in @@ -64,7 +64,7 @@ COMMANDS = { 'gazebo' => "\n"\ " --record Use logging system to record states and \n"\ " console messages to the default location, \n"\ - " in ~/.ignition/gazebo/log. \n"\ + " in ~/.gz/sim/log. \n"\ "\n"\ " --record-path [arg] Implicitly invokes --record, and specifies \n"\ " custom path to put recorded files. Argument \n"\ diff --git a/src/cmd/ign.cc b/src/cmd/ign.cc index ac3ff8932d8..277039047bf 100644 --- a/src/cmd/ign.cc +++ b/src/cmd/ign.cc @@ -24,9 +24,9 @@ #include #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/ServerConfig.hh" +#include "gz/sim/config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/ServerConfig.hh" #include "gui/GuiRunner.hh" #include "ign.hh" @@ -401,7 +401,7 @@ extern "C" int runGui(const char *_guiConfig) if (plugins.empty()) { // Check if there's a default config file under - // ~/.ignition/gazebo and use that. If there isn't, copy + // ~/.gz/sim and use that. If there isn't, copy // the installed file there first. if (!ignition::common::exists(defaultConfig)) { @@ -439,7 +439,7 @@ extern "C" int runGui(const char *_guiConfig) } } - // Also set ~/.ignition/gazebo/ver/gui.config as the default path + // Also set ~/.gz/sim/ver/gui.config as the default path if (!app.LoadConfig(defaultConfig)) { ignerr << "Failed to load config file[" << _guiConfig << "]." diff --git a/src/comms/Broker.cc b/src/comms/Broker.cc index 8c33c5fa21c..d3618d8e622 100644 --- a/src/comms/Broker.cc +++ b/src/comms/Broker.cc @@ -24,10 +24,10 @@ #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 "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 66e263fa9bd..b91efd08f87 100644 --- a/src/comms/Broker_TEST.cc +++ b/src/comms/Broker_TEST.cc @@ -20,8 +20,8 @@ #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 7b0074821c0..4bde665a6d5 100644 --- a/src/comms/ICommsModel.cc +++ b/src/comms/ICommsModel.cc @@ -22,11 +22,11 @@ #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 42195880994..6238736bbce 100644 --- a/src/comms/MsgManager.cc +++ b/src/comms/MsgManager.cc @@ -22,8 +22,8 @@ #include #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/comms/MsgManager.hh" +#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 b0e0989405b..8010c864c98 100644 --- a/src/comms/MsgManager_TEST.cc +++ b/src/comms/MsgManager_TEST.cc @@ -20,7 +20,7 @@ #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/AboutDialogHandler.hh b/src/gui/AboutDialogHandler.hh index 14f1bbd20c2..876c2f6ee1e 100644 --- a/src/gui/AboutDialogHandler.hh +++ b/src/gui/AboutDialogHandler.hh @@ -21,8 +21,8 @@ #include #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Export.hh" namespace ignition { diff --git a/src/gui/Gui.cc b/src/gui/Gui.cc index 7de934c158e..1d36c19a444 100644 --- a/src/gui/Gui.cc +++ b/src/gui/Gui.cc @@ -23,8 +23,8 @@ #include #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/gui/Gui.hh" +#include "gz/sim/config.hh" +#include "gz/sim/gui/Gui.hh" #include "AboutDialogHandler.hh" #include "GuiFileHandler.hh" @@ -265,7 +265,7 @@ std::unique_ptr createGui( if (plugins.empty()) { // Check if there's a default config file under - // ~/.ignition/gazebo and use that. If there isn't, copy + // ~/.gz/sim and use that. If there isn't, copy // the installed file there first. if (!ignition::common::exists(defaultConfig)) { @@ -305,7 +305,7 @@ std::unique_ptr createGui( } } - // Also set ~/.ignition/gazebo/ver/gui.config as the default path + // Also set ~/.gz/sim/ver/gui.config as the default path if (!app->LoadConfig(defaultConfig)) { ignerr << "Failed to load config file[" << defaultConfig << "]." diff --git a/src/gui/GuiEvents.cc b/src/gui/GuiEvents.cc index a89a5d82548..762a78393eb 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 cb0bebc9996..c0b5e133785 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/GuiFileHandler.hh b/src/gui/GuiFileHandler.hh index 981b9fb7698..2aa5efaf333 100644 --- a/src/gui/GuiFileHandler.hh +++ b/src/gui/GuiFileHandler.hh @@ -24,8 +24,8 @@ #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Export.hh" namespace ignition { diff --git a/src/gui/GuiRunner.cc b/src/gui/GuiRunner.cc index 2a70c033ac5..5fd3c952568 100644 --- a/src/gui/GuiRunner.cc +++ b/src/gui/GuiRunner.cc @@ -29,12 +29,12 @@ #include // Include all components so they have first-class support -#include "ignition/gazebo/components/components.hh" -#include "ignition/gazebo/Conversions.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include -#include "ignition/gazebo/gui/GuiSystem.hh" -#include "ignition/gazebo/SystemLoader.hh" +#include "gz/sim/components/components.hh" +#include "gz/sim/Conversions.hh" +#include "gz/sim/EntityComponentManager.hh" +#include +#include "gz/sim/gui/GuiSystem.hh" +#include "gz/sim/SystemLoader.hh" #include "GuiRunner.hh" diff --git a/src/gui/GuiRunner.hh b/src/gui/GuiRunner.hh index bc5a730553d..e3f87911c6d 100644 --- a/src/gui/GuiRunner.hh +++ b/src/gui/GuiRunner.hh @@ -24,9 +24,9 @@ #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EventManager.hh" -#include "ignition/gazebo/gui/Export.hh" +#include "gz/sim/config.hh" +#include "gz/sim/EventManager.hh" +#include "gz/sim/gui/Export.hh" namespace ignition { diff --git a/src/gui/Gui_TEST.cc b/src/gui/Gui_TEST.cc index 3eea1c217fb..cf6eaa9481f 100644 --- a/src/gui/Gui_TEST.cc +++ b/src/gui/Gui_TEST.cc @@ -25,8 +25,8 @@ #include #include -#include "ignition/gazebo/gui/Gui.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/gui/Gui.hh" +#include "gz/sim/test_config.hh" #include "../../test/helpers/EnvTestFixture.hh" diff --git a/src/gui/Gui_clean_exit_TEST.cc b/src/gui/Gui_clean_exit_TEST.cc index 4ac3fb465d4..40788d5504f 100644 --- a/src/gui/Gui_clean_exit_TEST.cc +++ b/src/gui/Gui_clean_exit_TEST.cc @@ -24,9 +24,9 @@ #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/PathManager.cc b/src/gui/PathManager.cc index a1f920519a3..a21df9b67be 100644 --- a/src/gui/PathManager.cc +++ b/src/gui/PathManager.cc @@ -26,7 +26,7 @@ #include #include -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/gui/PathManager.hh b/src/gui/PathManager.hh index 341e382cf2a..3e38c550775 100644 --- a/src/gui/PathManager.hh +++ b/src/gui/PathManager.hh @@ -21,8 +21,8 @@ #include -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/config.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/config.hh" namespace ignition { diff --git a/src/gui/plugins/align_tool/AlignTool.cc b/src/gui/plugins/align_tool/AlignTool.cc index ca397093d39..f478ac18cef 100644 --- a/src/gui/plugins/align_tool/AlignTool.cc +++ b/src/gui/plugins/align_tool/AlignTool.cc @@ -40,11 +40,11 @@ #include #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" -#include "ignition/gazebo/rendering/RenderUtil.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/gui/GuiEvents.hh" +#include "gz/sim/rendering/RenderUtil.hh" #include "AlignTool.hh" diff --git a/src/gui/plugins/align_tool/AlignTool.hh b/src/gui/plugins/align_tool/AlignTool.hh index 8b4c0c001c8..293954a7e87 100644 --- a/src/gui/plugins/align_tool/AlignTool.hh +++ b/src/gui/plugins/align_tool/AlignTool.hh @@ -20,7 +20,7 @@ #include -#include +#include #include #include diff --git a/src/gui/plugins/banana_for_scale/BananaForScale.cc b/src/gui/plugins/banana_for_scale/BananaForScale.cc index 469a442950c..e1a34b5126d 100644 --- a/src/gui/plugins/banana_for_scale/BananaForScale.cc +++ b/src/gui/plugins/banana_for_scale/BananaForScale.cc @@ -30,7 +30,7 @@ #include #include -#include "ignition/gazebo/gui/GuiEvents.hh" +#include "gz/sim/gui/GuiEvents.hh" namespace ignition::gazebo { diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index b703d38420b..42d1d777d3d 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -25,51 +25,51 @@ #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/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 "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/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 "ComponentInspector.hh" #include "Pose3d.hh" diff --git a/src/gui/plugins/component_inspector/ComponentInspector.hh b/src/gui/plugins/component_inspector/ComponentInspector.hh index a4800795e29..70699fff268 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.hh +++ b/src/gui/plugins/component_inspector/ComponentInspector.hh @@ -28,9 +28,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include "Types.hh" diff --git a/src/gui/plugins/component_inspector/ComponentInspector.qml b/src/gui/plugins/component_inspector/ComponentInspector.qml index 90a1e53dcb2..559770e73b8 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.qml +++ b/src/gui/plugins/component_inspector/ComponentInspector.qml @@ -20,7 +20,7 @@ import QtQuick.Controls 2.2 import QtQuick.Controls.Material 2.1 import QtQuick.Layouts 1.3 import QtQuick.Controls.Styles 1.4 -import IgnGazebo 1.0 as IgnGazebo +import GzGazebo 1.0 as GzGazebo Rectangle { id: componentInspector @@ -155,7 +155,7 @@ Rectangle { anchors.fill: parent spacing: 0 - IgnGazebo.TypeIcon { + GzGazebo.TypeIcon { id: icon height: lockButton.height * 0.8 width: lockButton.height * 0.8 diff --git a/src/gui/plugins/component_inspector/Pose3d.hh b/src/gui/plugins/component_inspector/Pose3d.hh index 890cac25908..2706dcc36ab 100644 --- a/src/gui/plugins/component_inspector/Pose3d.hh +++ b/src/gui/plugins/component_inspector/Pose3d.hh @@ -19,9 +19,9 @@ #include -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/PoseCmd.hh" -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/PoseCmd.hh" +#include "gz/sim/EntityComponentManager.hh" #include "ComponentInspector.hh" #include "Types.hh" diff --git a/src/gui/plugins/component_inspector/Types.hh b/src/gui/plugins/component_inspector/Types.hh index 5e0b682027f..0ec0e598901 100644 --- a/src/gui/plugins/component_inspector/Types.hh +++ b/src/gui/plugins/component_inspector/Types.hh @@ -20,7 +20,7 @@ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/component_inspector_editor/AirPressure.cc b/src/gui/plugins/component_inspector_editor/AirPressure.cc index 5f8baf3d0a9..44dcb5a662b 100644 --- a/src/gui/plugins/component_inspector_editor/AirPressure.cc +++ b/src/gui/plugins/component_inspector_editor/AirPressure.cc @@ -17,8 +17,8 @@ #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 480a6c5eaa9..730293c17d6 100644 --- a/src/gui/plugins/component_inspector_editor/Altimeter.cc +++ b/src/gui/plugins/component_inspector_editor/Altimeter.cc @@ -17,7 +17,7 @@ #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 8c14082c2a2..28929cac2ad 100644 --- a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc +++ b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc @@ -30,54 +30,54 @@ #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 "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 f4e2ac3b8d6..7679aa4e82e 100644 --- a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.hh +++ b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.hh @@ -28,9 +28,9 @@ #include -#include -#include -#include +#include +#include +#include #include diff --git a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.qml b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.qml index 1434a599d27..1e8f45cb10d 100644 --- a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.qml +++ b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.qml @@ -21,7 +21,7 @@ import QtQuick.Controls.Material 2.1 import QtQuick.Dialogs 1.0 import QtQuick.Layouts 1.3 import QtQuick.Controls.Styles 1.4 -import IgnGazebo 1.0 as IgnGazebo +import GzGazebo 1.0 as GzGazebo Rectangle { @@ -237,7 +237,7 @@ Rectangle { anchors.fill: parent spacing: 0 - IgnGazebo.TypeIcon { + GzGazebo.TypeIcon { id: icon height: lockButton.height * 0.8 width: lockButton.height * 0.8 diff --git a/src/gui/plugins/component_inspector_editor/Imu.cc b/src/gui/plugins/component_inspector_editor/Imu.cc index 4dbd6a099aa..a3c3b3343f9 100644 --- a/src/gui/plugins/component_inspector_editor/Imu.cc +++ b/src/gui/plugins/component_inspector_editor/Imu.cc @@ -17,8 +17,8 @@ #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 b8f70106fea..f455b621458 100644 --- a/src/gui/plugins/component_inspector_editor/JointType.cc +++ b/src/gui/plugins/component_inspector_editor/JointType.cc @@ -17,10 +17,10 @@ #include #include -#include "ignition/gazebo/components/JointType.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Recreate.hh" -#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 36ae02162ff..5fd03f8388d 100644 --- a/src/gui/plugins/component_inspector_editor/Lidar.cc +++ b/src/gui/plugins/component_inspector_editor/Lidar.cc @@ -17,8 +17,8 @@ #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 3ba125ae704..94166935ab4 100644 --- a/src/gui/plugins/component_inspector_editor/Magnetometer.cc +++ b/src/gui/plugins/component_inspector_editor/Magnetometer.cc @@ -17,7 +17,7 @@ #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 91699dd5285..2f6960a4553 100644 --- a/src/gui/plugins/component_inspector_editor/ModelEditor.cc +++ b/src/gui/plugins/component_inspector_editor/ModelEditor.cc @@ -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 "ignition/gazebo/gui/GuiEvents.hh" -#include "ignition/gazebo/Util.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 "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 bfc09df8978..8234dfb5ac9 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 42a349d8f81..e6d650295ee 100644 --- a/src/gui/plugins/component_inspector_editor/Pose3d.cc +++ b/src/gui/plugins/component_inspector_editor/Pose3d.cc @@ -17,10 +17,10 @@ #include #include -#include -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Recreate.hh" -#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/Types.hh b/src/gui/plugins/component_inspector_editor/Types.hh index b8eb0ff4223..78e8463d1bd 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 7b633c31767..01411219a00 100644 --- a/src/gui/plugins/copy_paste/CopyPaste.cc +++ b/src/gui/plugins/copy_paste/CopyPaste.cc @@ -26,8 +26,8 @@ #include #include -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" +#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 9b54d85b949..f6c0067a841 100644 --- a/src/gui/plugins/copy_paste/CopyPaste.hh +++ b/src/gui/plugins/copy_paste/CopyPaste.hh @@ -22,7 +22,7 @@ #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.qml b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.qml index 98fd9afa71b..34ed2d26b9d 100644 --- a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.qml +++ b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.qml @@ -19,7 +19,7 @@ import QtQuick 2.9 import QtQuick.Controls 2.1 import QtQuick.Layouts 1.3 import RenderWindowOverlay 1.0 -import IgnGazebo 1.0 as IgnGazebo +import GzGazebo 1.0 as GzGazebo ColumnLayout { Layout.minimumWidth: 350 @@ -64,7 +64,7 @@ ColumnLayout { } } - IgnGazebo.EntityContextMenu { + GzGazebo.EntityContextMenu { id: entityContextMenu anchors.fill: parent } diff --git a/src/gui/plugins/entity_tree/EntityTree.cc b/src/gui/plugins/entity_tree/EntityTree.cc index 38a80a9557a..022fcf13923 100644 --- a/src/gui/plugins/entity_tree/EntityTree.cc +++ b/src/gui/plugins/entity_tree/EntityTree.cc @@ -32,23 +32,23 @@ #include #include -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/Level.hh" -#include "ignition/gazebo/components/Light.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/Performer.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" - -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Primitives.hh" +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/Level.hh" +#include "gz/sim/components/Light.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/Performer.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/gui/GuiEvents.hh" + +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Primitives.hh" namespace ignition::gazebo { diff --git a/src/gui/plugins/entity_tree/EntityTree.hh b/src/gui/plugins/entity_tree/EntityTree.hh index f4e861183ee..06a9ca55d83 100644 --- a/src/gui/plugins/entity_tree/EntityTree.hh +++ b/src/gui/plugins/entity_tree/EntityTree.hh @@ -22,8 +22,8 @@ #include #include -#include -#include +#include +#include namespace ignition { diff --git a/src/gui/plugins/entity_tree/EntityTree.qml b/src/gui/plugins/entity_tree/EntityTree.qml index c96c5d78a84..c7baf836ff8 100644 --- a/src/gui/plugins/entity_tree/EntityTree.qml +++ b/src/gui/plugins/entity_tree/EntityTree.qml @@ -22,7 +22,7 @@ import QtQuick.Controls.Material 2.1 import QtQuick.Layouts 1.3 import QtQuick.Controls.Styles 1.4 import QtQuick.Dialogs 1.0 -import IgnGazebo 1.0 as IgnGazebo +import GzGazebo 1.0 as GzGazebo Rectangle { id: entityTree @@ -378,7 +378,7 @@ Rectangle { height: itemHeight - IgnGazebo.TypeIcon { + GzGazebo.TypeIcon { id: icon height: itemHeight - 2 width: itemHeight - 2 @@ -432,7 +432,7 @@ Rectangle { } } - IgnGazebo.EntityContextMenu { + GzGazebo.EntityContextMenu { id: entityContextMenu } diff --git a/src/gui/plugins/joint_position_controller/JointPositionController.cc b/src/gui/plugins/joint_position_controller/JointPositionController.cc index c800f14afff..b4436826866 100644 --- a/src/gui/plugins/joint_position_controller/JointPositionController.cc +++ b/src/gui/plugins/joint_position_controller/JointPositionController.cc @@ -26,15 +26,15 @@ #include #include -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/JointType.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/JointType.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/gui/GuiEvents.hh" #include "JointPositionController.hh" diff --git a/src/gui/plugins/joint_position_controller/JointPositionController.hh b/src/gui/plugins/joint_position_controller/JointPositionController.hh index 3aa9ecfa574..d51e855d166 100644 --- a/src/gui/plugins/joint_position_controller/JointPositionController.hh +++ b/src/gui/plugins/joint_position_controller/JointPositionController.hh @@ -22,8 +22,8 @@ #include #include -#include -#include +#include +#include Q_DECLARE_METATYPE(ignition::gazebo::Entity) diff --git a/src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc b/src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc index 18bfa19a096..fd89b6aa1f2 100644 --- a/src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc +++ b/src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc @@ -30,15 +30,15 @@ #include #include -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/JointType.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/JointType.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/test_config.hh" #include "../../../../test/helpers/EnvTestFixture.hh" #include "../../GuiRunner.hh" diff --git a/src/gui/plugins/lights/Lights.cc b/src/gui/plugins/lights/Lights.cc index 81ff6554efd..b86b25de24f 100644 --- a/src/gui/plugins/lights/Lights.cc +++ b/src/gui/plugins/lights/Lights.cc @@ -32,8 +32,8 @@ #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/modules/EntityContextMenu.cc b/src/gui/plugins/modules/EntityContextMenu.cc index d2282c4dc0e..f2fcf46994d 100644 --- a/src/gui/plugins/modules/EntityContextMenu.cc +++ b/src/gui/plugins/modules/EntityContextMenu.cc @@ -26,7 +26,7 @@ #include #include -#include +#include #include #include @@ -83,7 +83,7 @@ using namespace ignition; using namespace gazebo; ///////////////////////////////////////////////// -void IgnGazeboPlugin::registerTypes(const char *_uri) +void GzGazeboPlugin::registerTypes(const char *_uri) { // Register our 'EntityContextMenuItem' in qml engine qmlRegisterType(_uri, 1, 0, diff --git a/src/gui/plugins/modules/EntityContextMenu.hh b/src/gui/plugins/modules/EntityContextMenu.hh index 80de7970282..fb0a4c9ce82 100644 --- a/src/gui/plugins/modules/EntityContextMenu.hh +++ b/src/gui/plugins/modules/EntityContextMenu.hh @@ -28,14 +28,14 @@ namespace gazebo { class EntityContextMenuPrivate; - /// \brief IgnGazebo QML Plugin that registers C++ class so that they are + /// \brief GzGazebo QML Plugin that registers C++ class so that they are /// accessible from QML. - class IgnGazeboPlugin : public QQmlExtensionPlugin + class GzGazeboPlugin : public QQmlExtensionPlugin { Q_OBJECT // unique id - Q_PLUGIN_METADATA(IID "IgnGazebo/1.0") + Q_PLUGIN_METADATA(IID "GzGazebo/1.0") /// \brief Overrided function that registers C++ class as a QML type /// \param[in] _uri Plugin uri. diff --git a/src/gui/plugins/modules/EntityContextMenu.qml b/src/gui/plugins/modules/EntityContextMenu.qml index bce3fc56c8e..fc7c4f17ef1 100644 --- a/src/gui/plugins/modules/EntityContextMenu.qml +++ b/src/gui/plugins/modules/EntityContextMenu.qml @@ -16,7 +16,7 @@ */ import QtQuick 2.0 import QtQuick.Controls 2.0 -import IgnGazebo 1.0 as IgnGazebo +import GzGazebo 1.0 as GzGazebo Item { Menu { @@ -187,7 +187,7 @@ Item { menu.open() } - IgnGazebo.EntityContextMenuItem { + GzGazebo.EntityContextMenuItem { id: context property string entity property string type diff --git a/src/gui/plugins/modules/EntityContextMenu.qrc b/src/gui/plugins/modules/EntityContextMenu.qrc index 9afa7448a46..4810a1af50e 100644 --- a/src/gui/plugins/modules/EntityContextMenu.qrc +++ b/src/gui/plugins/modules/EntityContextMenu.qrc @@ -1,5 +1,5 @@ - + EntityContextMenu.qml TypeIcon.qml diff --git a/src/gui/plugins/modules/qmldir b/src/gui/plugins/modules/qmldir index e75c49f6322..8aa4fa2c3e1 100644 --- a/src/gui/plugins/modules/qmldir +++ b/src/gui/plugins/modules/qmldir @@ -1,6 +1,6 @@ -module IgnGazebo +module GzGazebo plugin EntityContextMenu -EntityContextMenu 1.0 qrc:/IgnGazebo/EntityContextMenu.qml -TypeIcon 1.0 qrc:/IgnGazebo/TypeIcon.qml +EntityContextMenu 1.0 qrc:/GzGazebo/EntityContextMenu.qml +TypeIcon 1.0 qrc:/GzGazebo/TypeIcon.qml diff --git a/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc b/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc index 2935caaf1cb..be0d5d4414a 100644 --- a/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc +++ b/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc @@ -36,8 +36,8 @@ #include #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/components/LogPlaybackStatistics.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/components/LogPlaybackStatistics.hh" namespace ignition::gazebo { diff --git a/src/gui/plugins/playback_scrubber/PlaybackScrubber.hh b/src/gui/plugins/playback_scrubber/PlaybackScrubber.hh index 3d2031aa82f..131cd91c8a1 100644 --- a/src/gui/plugins/playback_scrubber/PlaybackScrubber.hh +++ b/src/gui/plugins/playback_scrubber/PlaybackScrubber.hh @@ -21,7 +21,7 @@ #include #include -#include +#include #include namespace ignition diff --git a/src/gui/plugins/plot_3d/Plot3D.cc b/src/gui/plugins/plot_3d/Plot3D.cc index 45565bbc75b..ed6fba2650c 100644 --- a/src/gui/plugins/plot_3d/Plot3D.cc +++ b/src/gui/plugins/plot_3d/Plot3D.cc @@ -31,11 +31,11 @@ #include #include -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/gui/GuiEvents.hh" +#include "gz/sim/Util.hh" #include "Plot3D.hh" diff --git a/src/gui/plugins/plot_3d/Plot3D.hh b/src/gui/plugins/plot_3d/Plot3D.hh index faf4466024f..33c9a68be62 100644 --- a/src/gui/plugins/plot_3d/Plot3D.hh +++ b/src/gui/plugins/plot_3d/Plot3D.hh @@ -20,7 +20,7 @@ #include -#include +#include #include "ignition/gui/qt.h" diff --git a/src/gui/plugins/plot_3d/Plot3D_TEST.cc b/src/gui/plugins/plot_3d/Plot3D_TEST.cc index f728472e58d..b87782fbd1d 100644 --- a/src/gui/plugins/plot_3d/Plot3D_TEST.cc +++ b/src/gui/plugins/plot_3d/Plot3D_TEST.cc @@ -31,15 +31,15 @@ #include #include -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/JointType.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/JointType.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/test_config.hh" #include "../../../../test/helpers/EnvTestFixture.hh" #include "../../GuiRunner.hh" diff --git a/src/gui/plugins/plotting/Plotting.cc b/src/gui/plugins/plotting/Plotting.cc index a6f5228ae59..02d0360b5b9 100644 --- a/src/gui/plugins/plotting/Plotting.cc +++ b/src/gui/plugins/plotting/Plotting.cc @@ -19,25 +19,25 @@ #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 "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 9e85c62264c..c3f6ba544a2 100644 --- a/src/gui/plugins/plotting/Plotting.hh +++ b/src/gui/plugins/plotting/Plotting.hh @@ -20,7 +20,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/gui/plugins/resource_spawner/ResourceSpawner.cc b/src/gui/plugins/resource_spawner/ResourceSpawner.cc index 9320e88be44..2ede866f597 100644 --- a/src/gui/plugins/resource_spawner/ResourceSpawner.cc +++ b/src/gui/plugins/resource_spawner/ResourceSpawner.cc @@ -39,7 +39,7 @@ #include #include -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/EntityComponentManager.hh" namespace ignition::gazebo { diff --git a/src/gui/plugins/scene3d/GzScene3D.qml b/src/gui/plugins/scene3d/GzScene3D.qml index 6dea55f64e2..059e7940bdb 100644 --- a/src/gui/plugins/scene3d/GzScene3D.qml +++ b/src/gui/plugins/scene3d/GzScene3D.qml @@ -14,7 +14,7 @@ * limitations under the License. * */ -import IgnGazebo 1.0 as IgnGazebo +import GzGazebo 1.0 as GzGazebo import QtGraphicalEffects 1.0 import QtQuick 2.9 import QtQuick.Controls 2.2 @@ -86,7 +86,7 @@ Rectangle { height = Qt.binding(function() {return parent.parent.height}) } - IgnGazebo.EntityContextMenu { + GzGazebo.EntityContextMenu { id: entityContextMenu anchors.fill: parent } diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index b5bef6d49d5..8463b89e917 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -64,12 +64,12 @@ #include #include -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/RenderEngineGuiPlugin.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/Name.hh" +#include "gz/sim/components/RenderEngineGuiPlugin.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/gui/GuiEvents.hh" +#include "gz/sim/rendering/RenderUtil.hh" /// \brief condition variable for lockstepping video recording /// todo(anyone) avoid using a global condition variable when we support diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index c21367c37f3..2b288353fc1 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -40,7 +40,7 @@ #include -#include +#include #include "ignition/gui/qt.h" diff --git a/src/gui/plugins/scene_manager/GzSceneManager.cc b/src/gui/plugins/scene_manager/GzSceneManager.cc index 68d8a666c0d..cdc5933643f 100644 --- a/src/gui/plugins/scene_manager/GzSceneManager.cc +++ b/src/gui/plugins/scene_manager/GzSceneManager.cc @@ -34,12 +34,12 @@ #include #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/components/Name.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 "gz/sim/EntityComponentManager.hh" +#include "gz/sim/components/Name.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 34208e0b33f..c84f33322ec 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 396360b34a5..93aa41730b9 100644 --- a/src/gui/plugins/select_entities/SelectEntities.cc +++ b/src/gui/plugins/select_entities/SelectEntities.cc @@ -33,10 +33,10 @@ #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 "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/shapes/Shapes.cc b/src/gui/plugins/shapes/Shapes.cc index 2cd01082377..dcfe2e40f67 100644 --- a/src/gui/plugins/shapes/Shapes.cc +++ b/src/gui/plugins/shapes/Shapes.cc @@ -32,7 +32,7 @@ #include #include -#include +#include namespace ignition::gazebo { diff --git a/src/gui/plugins/spawn/Spawn.cc b/src/gui/plugins/spawn/Spawn.cc index be60287e528..7d3a8828114 100644 --- a/src/gui/plugins/spawn/Spawn.cc +++ b/src/gui/plugins/spawn/Spawn.cc @@ -54,8 +54,8 @@ #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/transform_control/TransformControl.cc b/src/gui/plugins/transform_control/TransformControl.cc index 732aafe500c..7cde6bfca3f 100644 --- a/src/gui/plugins/transform_control/TransformControl.cc +++ b/src/gui/plugins/transform_control/TransformControl.cc @@ -45,7 +45,7 @@ #include #include -#include "ignition/gazebo/gui/GuiEvents.hh" +#include "gz/sim/gui/GuiEvents.hh" namespace ignition::gazebo { diff --git a/src/gui/plugins/video_recorder/VideoRecorder.hh b/src/gui/plugins/video_recorder/VideoRecorder.hh index a551dab782c..bd7cb90aef7 100644 --- a/src/gui/plugins/video_recorder/VideoRecorder.hh +++ b/src/gui/plugins/video_recorder/VideoRecorder.hh @@ -20,7 +20,7 @@ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/view_angle/ViewAngle.cc b/src/gui/plugins/view_angle/ViewAngle.cc index e561ac6677d..a6fbcf4c90b 100644 --- a/src/gui/plugins/view_angle/ViewAngle.cc +++ b/src/gui/plugins/view_angle/ViewAngle.cc @@ -35,8 +35,8 @@ #include #include -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/gui/GuiEvents.hh" namespace ignition::gazebo { diff --git a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc index b9dd2f133c0..58ab1461f34 100644 --- a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc +++ b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc @@ -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 99a400f7eba..9d9d646448c 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 4420d90d056..59b74605790 100644 --- a/src/gui/plugins/visualize_contacts/VisualizeContacts.cc +++ b/src/gui/plugins/visualize_contacts/VisualizeContacts.cc @@ -37,14 +37,14 @@ #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 f1c62110847..51908a7ec11 100644 --- a/src/gui/plugins/visualize_contacts/VisualizeContacts.hh +++ b/src/gui/plugins/visualize_contacts/VisualizeContacts.hh @@ -20,7 +20,7 @@ #include -#include +#include #include "ignition/gui/qt.h" diff --git a/src/gui/plugins/visualize_lidar/VisualizeLidar.cc b/src/gui/plugins/visualize_lidar/VisualizeLidar.cc index ab306bdd8ba..5b812929057 100644 --- a/src/gui/plugins/visualize_lidar/VisualizeLidar.cc +++ b/src/gui/plugins/visualize_lidar/VisualizeLidar.cc @@ -39,11 +39,11 @@ #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" @@ -51,12 +51,12 @@ #include "ignition/rendering/Scene.hh" #include "ignition/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" diff --git a/src/gui/plugins/visualize_lidar/VisualizeLidar.hh b/src/gui/plugins/visualize_lidar/VisualizeLidar.hh index 7eebe699772..19c891ed78c 100644 --- a/src/gui/plugins/visualize_lidar/VisualizeLidar.hh +++ b/src/gui/plugins/visualize_lidar/VisualizeLidar.hh @@ -21,7 +21,7 @@ #include #include "ignition/msgs/laserscan.pb.h" -#include "ignition/gazebo/gui/GuiSystem.hh" +#include "gz/sim/gui/GuiSystem.hh" #include "ignition/gui/qt.h" namespace ignition diff --git a/src/ign.cc b/src/ign.cc index 9a384281d81..1d856324241 100644 --- a/src/ign.cc +++ b/src/ign.cc @@ -28,11 +28,11 @@ #include #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/ServerConfig.hh" +#include "gz/sim/config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/ServerConfig.hh" -#include "ignition/gazebo/gui/Gui.hh" +#include "gz/sim/gui/Gui.hh" ////////////////////////////////////////////////// extern "C" char *ignitionGazeboVersion() diff --git a/src/ign.hh b/src/ign.hh index 28e5c26b97f..0cfffc51556 100644 --- a/src/ign.hh +++ b/src/ign.hh @@ -17,7 +17,7 @@ #ifndef IGNITION_GAZEBO_IGN_HH_ #define IGNITION_GAZEBO_IGN_HH_ -#include "ignition/gazebo/Export.hh" +#include "gz/sim/Export.hh" /// \brief External hook to read the library version. /// \return C-string representing the version. Ex.: 0.1.2 diff --git a/src/ign_TEST.cc b/src/ign_TEST.cc index 4eb5af17853..ab1b9147f1b 100644 --- a/src/ign_TEST.cc +++ b/src/ign_TEST.cc @@ -23,7 +23,7 @@ #include #include -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/test_config.hh" // NOLINT(build/include) static const std::string kBinPath(PROJECT_BINARY_PATH); diff --git a/src/network/NetworkConfig.hh b/src/network/NetworkConfig.hh index 0bd1dfdfc49..85727bb2bdb 100644 --- a/src/network/NetworkConfig.hh +++ b/src/network/NetworkConfig.hh @@ -20,8 +20,8 @@ #include #include -#include -#include +#include +#include #include "NetworkRole.hh" @@ -31,7 +31,7 @@ namespace ignition { // Inline bracket to help doxygen filtering. inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - /// \class NetworkConfig NetworkConfig.hh ignition/gazebo/NetworkConfig.hh + /// \class NetworkConfig NetworkConfig.hh gz/sim/NetworkConfig.hh /// \brief Configuration parameters for a distributed simulation instance /// /// NetworkConfig can either be created programatically, or populated from diff --git a/src/network/NetworkManager.cc b/src/network/NetworkManager.cc index 6bbc0bbd577..62f34fac477 100644 --- a/src/network/NetworkManager.cc +++ b/src/network/NetworkManager.cc @@ -21,7 +21,7 @@ #include "ignition/common/Console.hh" #include "ignition/common/Util.hh" -#include "ignition/gazebo/Events.hh" +#include "gz/sim/Events.hh" #include "NetworkManager.hh" #include "NetworkManagerPrivate.hh" diff --git a/src/network/NetworkManager.hh b/src/network/NetworkManager.hh index c26c2bf058a..281ec61abce 100644 --- a/src/network/NetworkManager.hh +++ b/src/network/NetworkManager.hh @@ -23,9 +23,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include "NetworkConfig.hh" @@ -39,7 +39,7 @@ namespace ignition class NetworkManagerPrivate; /// \class NetworkManager NetworkManager.hh - /// ignition/gazebo/NetworkManager.hh + /// gz/sim/NetworkManager.hh /// \brief The NetworkManager provides a common interface to derived /// objects that control the flow of information in the distributed /// simulation environment. diff --git a/src/network/NetworkManagerPrimary.cc b/src/network/NetworkManagerPrimary.cc index e9759eb7359..8f3a5abc41a 100644 --- a/src/network/NetworkManagerPrimary.cc +++ b/src/network/NetworkManagerPrimary.cc @@ -30,12 +30,12 @@ #include "msgs/peer_control.pb.h" #include "msgs/simulation_step.pb.h" -#include "ignition/gazebo/components/PerformerAffinity.hh" -#include "ignition/gazebo/components/PerformerLevels.hh" -#include "ignition/gazebo/Conversions.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Events.hh" +#include "gz/sim/components/PerformerAffinity.hh" +#include "gz/sim/components/PerformerLevels.hh" +#include "gz/sim/Conversions.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Events.hh" #include "NetworkManagerPrivate.hh" #include "PeerTracker.hh" diff --git a/src/network/NetworkManagerPrimary.hh b/src/network/NetworkManagerPrimary.hh index c95fe25e482..b2e756e4652 100644 --- a/src/network/NetworkManagerPrimary.hh +++ b/src/network/NetworkManagerPrimary.hh @@ -24,9 +24,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include #include "msgs/simulation_step.pb.h" @@ -55,7 +55,7 @@ namespace ignition }; /// \class NetworkManagerPrimary NetworkManagerPrimary.hh - /// ignition/gazebo/network/NetworkManagerPrimary.hh + /// gz/sim/network/NetworkManagerPrimary.hh /// \brief Simulation primary specific behaviors class IGNITION_GAZEBO_VISIBLE NetworkManagerPrimary: public NetworkManager diff --git a/src/network/NetworkManagerPrivate.hh b/src/network/NetworkManagerPrivate.hh index 16e91c1d5c8..581eb72bd21 100644 --- a/src/network/NetworkManagerPrivate.hh +++ b/src/network/NetworkManagerPrivate.hh @@ -20,8 +20,8 @@ #include #include -#include -#include +#include +#include #include "NetworkConfig.hh" #include "PeerInfo.hh" @@ -34,7 +34,7 @@ namespace ignition // Inline bracket to help doxygen filtering. inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \class NetworkManagerPrivate NetworkManagerPrivate.hh - /// ignition/gazebo/NetworkManagerPrivate.hh + /// gz/sim/NetworkManagerPrivate.hh class IGNITION_GAZEBO_VISIBLE NetworkManagerPrivate { /// \brief Network Configuration diff --git a/src/network/NetworkManagerSecondary.cc b/src/network/NetworkManagerSecondary.cc index f3b79d90c75..1e60ce13605 100644 --- a/src/network/NetworkManagerSecondary.cc +++ b/src/network/NetworkManagerSecondary.cc @@ -24,11 +24,11 @@ #include "msgs/peer_control.pb.h" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/Conversions.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Events.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/Conversions.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Events.hh" #include "NetworkManagerPrivate.hh" #include "NetworkManagerSecondary.hh" diff --git a/src/network/NetworkManagerSecondary.hh b/src/network/NetworkManagerSecondary.hh index a4f7b3343de..7ac9bdc3d39 100644 --- a/src/network/NetworkManagerSecondary.hh +++ b/src/network/NetworkManagerSecondary.hh @@ -22,8 +22,8 @@ #include #include -#include -#include +#include +#include #include #include "msgs/simulation_step.pb.h" @@ -38,7 +38,7 @@ namespace ignition // Inline bracket to help doxygen filtering. inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \class NetworkManagerSecondary NetworkManagerSecondary.hh - /// ignition/gazebo/network/NetworkManagerSecondary.hh + /// gz/sim/network/NetworkManagerSecondary.hh /// \brief Secondary specific behaviors class IGNITION_GAZEBO_VISIBLE NetworkManagerSecondary: public NetworkManager diff --git a/src/network/NetworkManager_TEST.cc b/src/network/NetworkManager_TEST.cc index ec4e0408d87..5d722af69a6 100644 --- a/src/network/NetworkManager_TEST.cc +++ b/src/network/NetworkManager_TEST.cc @@ -20,7 +20,7 @@ #include #include -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/EntityComponentManager.hh" #include "NetworkManager.hh" #include "NetworkManagerPrimary.hh" #include "NetworkManagerSecondary.hh" diff --git a/src/network/NetworkRole.hh b/src/network/NetworkRole.hh index 4861cf27891..bfee9c7fd01 100644 --- a/src/network/NetworkRole.hh +++ b/src/network/NetworkRole.hh @@ -17,8 +17,8 @@ #ifndef IGNITION_GAZEBO_NETWORK_NETWORKROLE_HH_ #define IGNITION_GAZEBO_NETWORK_NETWORKROLE_HH_ -#include -#include +#include +#include namespace ignition { diff --git a/src/network/PeerInfo.hh b/src/network/PeerInfo.hh index c44e461f563..e9d277e4a6f 100644 --- a/src/network/PeerInfo.hh +++ b/src/network/PeerInfo.hh @@ -19,8 +19,8 @@ #include -#include -#include +#include +#include #include "NetworkRole.hh" #include "msgs/peer_info.pb.h" diff --git a/src/network/PeerTracker.hh b/src/network/PeerTracker.hh index 1b7515bd6c8..62a3f1206c7 100644 --- a/src/network/PeerTracker.hh +++ b/src/network/PeerTracker.hh @@ -22,9 +22,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include #include diff --git a/src/network/PeerTracker_TEST.cc b/src/network/PeerTracker_TEST.cc index fa12da149f3..92377d5c4fd 100644 --- a/src/network/PeerTracker_TEST.cc +++ b/src/network/PeerTracker_TEST.cc @@ -23,7 +23,7 @@ #include #include "PeerTracker.hh" -#include "ignition/gazebo/EventManager.hh" +#include "gz/sim/EventManager.hh" using namespace ignition::gazebo; diff --git a/src/rendering/MarkerManager.cc b/src/rendering/MarkerManager.cc index 736815b45b6..148d6f1e6e8 100644 --- a/src/rendering/MarkerManager.cc +++ b/src/rendering/MarkerManager.cc @@ -24,14 +24,14 @@ #include #include -#include "ignition/gazebo/Events.hh" -#include "ignition/gazebo/Conversions.hh" +#include "gz/sim/Events.hh" +#include "gz/sim/Conversions.hh" #include "ignition/common/Console.hh" #include "ignition/rendering/Marker.hh" #include "ignition/rendering/RenderingIface.hh" #include "ignition/rendering/Scene.hh" -#include "ignition/gazebo/rendering/MarkerManager.hh" +#include "gz/sim/rendering/MarkerManager.hh" using namespace ignition; using namespace gazebo; diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 9c5aef2de14..3a6e16c6d7a 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -51,51 +51,51 @@ #include #include -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/Camera.hh" -#include "ignition/gazebo/components/CastShadows.hh" -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/DepthCamera.hh" -#include "ignition/gazebo/components/GpuLidar.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/LaserRetro.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/LightCmd.hh" -#include "ignition/gazebo/components/Link.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/ParticleEmitter.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/RgbdCamera.hh" -#include "ignition/gazebo/components/Scene.hh" -#include "ignition/gazebo/components/SegmentationCamera.hh" -#include "ignition/gazebo/components/SemanticLabel.hh" -#include "ignition/gazebo/components/SourceFilePath.hh" -#include "ignition/gazebo/components/Temperature.hh" -#include "ignition/gazebo/components/TemperatureRange.hh" -#include "ignition/gazebo/components/ThermalCamera.hh" -#include "ignition/gazebo/components/Transparency.hh" -#include "ignition/gazebo/components/Visibility.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/VisualCmd.hh" -#include "ignition/gazebo/components/WideAngleCamera.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/EntityComponentManager.hh" - -#include "ignition/gazebo/rendering/Events.hh" -#include "ignition/gazebo/rendering/RenderUtil.hh" -#include "ignition/gazebo/rendering/SceneManager.hh" -#include "ignition/gazebo/rendering/MarkerManager.hh" - -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/Camera.hh" +#include "gz/sim/components/CastShadows.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/DepthCamera.hh" +#include "gz/sim/components/GpuLidar.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/LaserRetro.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/LightCmd.hh" +#include "gz/sim/components/Link.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/ParticleEmitter.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/RgbdCamera.hh" +#include "gz/sim/components/Scene.hh" +#include "gz/sim/components/SegmentationCamera.hh" +#include "gz/sim/components/SemanticLabel.hh" +#include "gz/sim/components/SourceFilePath.hh" +#include "gz/sim/components/Temperature.hh" +#include "gz/sim/components/TemperatureRange.hh" +#include "gz/sim/components/ThermalCamera.hh" +#include "gz/sim/components/Transparency.hh" +#include "gz/sim/components/Visibility.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/VisualCmd.hh" +#include "gz/sim/components/WideAngleCamera.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/EntityComponentManager.hh" + +#include "gz/sim/rendering/Events.hh" +#include "gz/sim/rendering/RenderUtil.hh" +#include "gz/sim/rendering/SceneManager.hh" +#include "gz/sim/rendering/MarkerManager.hh" + +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index 43270415d5a..d664ec8878c 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -59,9 +59,9 @@ #include #include -#include "ignition/gazebo/Conversions.hh" -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/rendering/SceneManager.hh" +#include "gz/sim/Conversions.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/rendering/SceneManager.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/ackermann_steering/AckermannSteering.cc b/src/systems/ackermann_steering/AckermannSteering.cc index 530c3e3289d..c2c514956f4 100644 --- a/src/systems/ackermann_steering/AckermannSteering.cc +++ b/src/systems/ackermann_steering/AckermannSteering.cc @@ -31,12 +31,12 @@ #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 "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/ackermann_steering/AckermannSteering.hh b/src/systems/ackermann_steering/AckermannSteering.hh index b501bcfde8d..3cf34460fce 100644 --- a/src/systems/ackermann_steering/AckermannSteering.hh +++ b/src/systems/ackermann_steering/AckermannSteering.hh @@ -19,7 +19,7 @@ #include -#include +#include namespace ignition { diff --git a/src/systems/ackermann_steering/SpeedLimiter.hh b/src/systems/ackermann_steering/SpeedLimiter.hh index 34286bc3ae9..add505f5d07 100644 --- a/src/systems/ackermann_steering/SpeedLimiter.hh +++ b/src/systems/ackermann_steering/SpeedLimiter.hh @@ -42,7 +42,7 @@ #include -#include +#include namespace ignition { diff --git a/src/systems/air_pressure/AirPressure.cc b/src/systems/air_pressure/AirPressure.cc index 6b8db56ba5d..ed0d1e9bac7 100644 --- a/src/systems/air_pressure/AirPressure.cc +++ b/src/systems/air_pressure/AirPressure.cc @@ -35,13 +35,13 @@ #include #include -#include "ignition/gazebo/components/AirPressureSensor.hh" -#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 "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/AirPressureSensor.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 "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/air_pressure/AirPressure.hh b/src/systems/air_pressure/AirPressure.hh index 93cbb5fd4ac..237244492cb 100644 --- a/src/systems/air_pressure/AirPressure.hh +++ b/src/systems/air_pressure/AirPressure.hh @@ -18,8 +18,8 @@ #define IGNITION_GAZEBO_SYSTEMS_AIRPRESSURE_HH_ #include -#include -#include +#include +#include namespace ignition { @@ -32,7 +32,7 @@ namespace systems // Forward declarations. class AirPressurePrivate; - /// \class AirPressure AirPressure.hh ignition/gazebo/systems/AirPressure.hh + /// \class AirPressure AirPressure.hh gz/sim/systems/AirPressure.hh /// \brief An air pressure sensor that reports vertical position and velocity /// readings over ign transport class AirPressure: diff --git a/src/systems/altimeter/Altimeter.cc b/src/systems/altimeter/Altimeter.cc index 36f97663bdd..947bb5c047c 100644 --- a/src/systems/altimeter/Altimeter.cc +++ b/src/systems/altimeter/Altimeter.cc @@ -35,15 +35,15 @@ #include #include -#include "ignition/gazebo/components/Altimeter.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#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 "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/Altimeter.hh" +#include "gz/sim/components/LinearVelocity.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 "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/altimeter/Altimeter.hh b/src/systems/altimeter/Altimeter.hh index e044e9b8644..cef06a13ebe 100644 --- a/src/systems/altimeter/Altimeter.hh +++ b/src/systems/altimeter/Altimeter.hh @@ -18,8 +18,8 @@ #define IGNITION_GAZEBO_SYSTEMS_ALTIMETER_HH_ #include -#include -#include +#include +#include namespace ignition { @@ -32,7 +32,7 @@ namespace systems // Forward declarations. class AltimeterPrivate; - /// \class Altimeter Altimeter.hh ignition/gazebo/systems/Altimeter.hh + /// \class Altimeter Altimeter.hh gz/sim/systems/Altimeter.hh /// \brief An altimeter sensor that reports vertical position and velocity /// readings over ign transport class Altimeter: diff --git a/src/systems/apply_joint_force/ApplyJointForce.cc b/src/systems/apply_joint_force/ApplyJointForce.cc index 042f585565b..f2b8ea7124a 100644 --- a/src/systems/apply_joint_force/ApplyJointForce.cc +++ b/src/systems/apply_joint_force/ApplyJointForce.cc @@ -23,9 +23,9 @@ #include #include -#include "ignition/gazebo/components/JointForceCmd.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/JointForceCmd.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/apply_joint_force/ApplyJointForce.hh b/src/systems/apply_joint_force/ApplyJointForce.hh index 10dfabf1965..42b69da9bf9 100644 --- a/src/systems/apply_joint_force/ApplyJointForce.hh +++ b/src/systems/apply_joint_force/ApplyJointForce.hh @@ -17,7 +17,7 @@ #ifndef IGNITION_GAZEBO_SYSTEMS_APPLYJOINTFORCE_HH_ #define IGNITION_GAZEBO_SYSTEMS_APPLYJOINTFORCE_HH_ -#include +#include #include namespace ignition diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.cc b/src/systems/battery_plugin/LinearBatteryPlugin.cc index 1b484783cfc..995c6a51fe8 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.cc +++ b/src/systems/battery_plugin/LinearBatteryPlugin.cc @@ -39,14 +39,14 @@ #include #include -#include "ignition/gazebo/components/BatterySoC.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointForceCmd.hh" -#include "ignition/gazebo/components/JointVelocityCmd.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Model.hh" +#include "gz/sim/components/BatterySoC.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointForceCmd.hh" +#include "gz/sim/components/JointVelocityCmd.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Model.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.hh b/src/systems/battery_plugin/LinearBatteryPlugin.hh index e98460a15be..d5dab81c752 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.hh +++ b/src/systems/battery_plugin/LinearBatteryPlugin.hh @@ -24,7 +24,7 @@ #include -#include "ignition/gazebo/System.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/breadcrumbs/Breadcrumbs.cc b/src/systems/breadcrumbs/Breadcrumbs.cc index c6484e55510..31d5c5844f8 100644 --- a/src/systems/breadcrumbs/Breadcrumbs.cc +++ b/src/systems/breadcrumbs/Breadcrumbs.cc @@ -32,17 +32,17 @@ #include #include -#include "ignition/gazebo/components/CanonicalLink.hh" -#include "ignition/gazebo/components/DetachableJoint.hh" -#include "ignition/gazebo/components/Geometry.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/Performer.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/CanonicalLink.hh" +#include "gz/sim/components/DetachableJoint.hh" +#include "gz/sim/components/Geometry.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/Performer.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/breadcrumbs/Breadcrumbs.hh b/src/systems/breadcrumbs/Breadcrumbs.hh index 6d6270b58d1..2cb50184088 100644 --- a/src/systems/breadcrumbs/Breadcrumbs.hh +++ b/src/systems/breadcrumbs/Breadcrumbs.hh @@ -31,9 +31,9 @@ #include #include -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/SdfEntityCreator.hh" -#include "ignition/gazebo/System.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/SdfEntityCreator.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/buoyancy/Buoyancy.cc b/src/systems/buoyancy/Buoyancy.cc index eaa50b1aa72..a417780d791 100644 --- a/src/systems/buoyancy/Buoyancy.cc +++ b/src/systems/buoyancy/Buoyancy.cc @@ -37,18 +37,18 @@ #include -#include "ignition/gazebo/components/CenterOfVolume.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/Gravity.hh" -#include "ignition/gazebo/components/Inertial.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Volume.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/CenterOfVolume.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/Gravity.hh" +#include "gz/sim/components/Inertial.hh" +#include "gz/sim/components/Link.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" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" #include "Buoyancy.hh" diff --git a/src/systems/buoyancy/Buoyancy.hh b/src/systems/buoyancy/Buoyancy.hh index 73aedb205e3..aaad03dac31 100644 --- a/src/systems/buoyancy/Buoyancy.hh +++ b/src/systems/buoyancy/Buoyancy.hh @@ -17,7 +17,7 @@ #ifndef IGNITION_GAZEBO_SYSTEMS_BUOYANCY_HH_ #define IGNITION_GAZEBO_SYSTEMS_BUOYANCY_HH_ -#include +#include #include namespace ignition diff --git a/src/systems/buoyancy_engine/BuoyancyEngine.cc b/src/systems/buoyancy_engine/BuoyancyEngine.cc index d128de45811..822cd6cd35b 100644 --- a/src/systems/buoyancy_engine/BuoyancyEngine.cc +++ b/src/systems/buoyancy_engine/BuoyancyEngine.cc @@ -21,10 +21,10 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include diff --git a/src/systems/buoyancy_engine/BuoyancyEngine.hh b/src/systems/buoyancy_engine/BuoyancyEngine.hh index 1e6f6747b59..faa0536c377 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/camera_video_recorder/CameraVideoRecorder.cc b/src/systems/camera_video_recorder/CameraVideoRecorder.cc index 69180362995..25ef5c99b83 100644 --- a/src/systems/camera_video_recorder/CameraVideoRecorder.cc +++ b/src/systems/camera_video_recorder/CameraVideoRecorder.cc @@ -30,19 +30,19 @@ #include #include -#include "ignition/gazebo/rendering/RenderUtil.hh" -#include "ignition/gazebo/rendering/Events.hh" -#include "ignition/gazebo/rendering/MarkerManager.hh" - -#include "ignition/gazebo/components/Camera.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Conversions.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Events.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/rendering/RenderUtil.hh" +#include "gz/sim/rendering/Events.hh" +#include "gz/sim/rendering/MarkerManager.hh" + +#include "gz/sim/components/Camera.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Conversions.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Events.hh" +#include "gz/sim/Util.hh" #include "CameraVideoRecorder.hh" diff --git a/src/systems/camera_video_recorder/CameraVideoRecorder.hh b/src/systems/camera_video_recorder/CameraVideoRecorder.hh index f5f3dc02c1c..f9a3118176a 100644 --- a/src/systems/camera_video_recorder/CameraVideoRecorder.hh +++ b/src/systems/camera_video_recorder/CameraVideoRecorder.hh @@ -18,8 +18,8 @@ #define IGNITION_GAZEBO_CAMERAVIDEORECORDER_SYSTEM_HH_ #include -#include -#include +#include +#include namespace ignition { @@ -32,7 +32,7 @@ namespace systems class CameraVideoRecorderPrivate; /** \class CameraVideoRecorder CameraVideoRecorder.hh \ - * ignition/gazebo/systems/CameraVideoRecorder.hh + * gz/sim/systems/CameraVideoRecorder.hh **/ /// \brief Record video from a camera sensor /// The system takes in the following parameter: diff --git a/src/systems/collada_world_exporter/ColladaWorldExporter.cc b/src/systems/collada_world_exporter/ColladaWorldExporter.cc index 463b91be0a8..10ec69381fc 100644 --- a/src/systems/collada_world_exporter/ColladaWorldExporter.cc +++ b/src/systems/collada_world_exporter/ColladaWorldExporter.cc @@ -20,19 +20,19 @@ #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/collada_world_exporter/ColladaWorldExporter.hh b/src/systems/collada_world_exporter/ColladaWorldExporter.hh index e2243ff9136..0db2e7fae28 100644 --- a/src/systems/collada_world_exporter/ColladaWorldExporter.hh +++ b/src/systems/collada_world_exporter/ColladaWorldExporter.hh @@ -19,7 +19,7 @@ #define IGNITION_GAZEBO_SYSTEMS_COLLADAWORLDEXPORTER_HH_ #include -#include +#include namespace ignition { diff --git a/src/systems/comms_endpoint/CommsEndpoint.cc b/src/systems/comms_endpoint/CommsEndpoint.cc index 98c4522bacb..6a41f511a31 100644 --- a/src/systems/comms_endpoint/CommsEndpoint.cc +++ b/src/systems/comms_endpoint/CommsEndpoint.cc @@ -26,8 +26,8 @@ #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 a21e9b30899..c007cbc7426 100644 --- a/src/systems/comms_endpoint/CommsEndpoint.hh +++ b/src/systems/comms_endpoint/CommsEndpoint.hh @@ -21,7 +21,7 @@ #include #include -#include "ignition/gazebo/System.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/contact/Contact.cc b/src/systems/contact/Contact.cc index afd1122245d..73956c2e2b8 100644 --- a/src/systems/contact/Contact.cc +++ b/src/systems/contact/Contact.cc @@ -32,15 +32,15 @@ #include -#include "ignition/gazebo/Conversions.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/ContactSensor.hh" -#include "ignition/gazebo/components/ContactSensorData.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" +#include "gz/sim/Conversions.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/ContactSensor.hh" +#include "gz/sim/components/ContactSensorData.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/contact/Contact.hh b/src/systems/contact/Contact.hh index cd42afc0d38..6e6b76dadf3 100644 --- a/src/systems/contact/Contact.hh +++ b/src/systems/contact/Contact.hh @@ -18,7 +18,7 @@ #define IGNITION_GAZEBO_SYSTEMS_CONTACT_HH_ #include -#include +#include namespace ignition { @@ -32,7 +32,7 @@ namespace systems class ContactPrivate; /** \class Contact Contact.hh \ - * ignition/gazebo/systems/Contact/Contact.hh + * gz/sim/systems/Contact/Contact.hh **/ /// \brief Contact sensor system which manages all contact sensors in /// simulation diff --git a/src/systems/detachable_joint/DetachableJoint.cc b/src/systems/detachable_joint/DetachableJoint.cc index 0946aa9505b..09a7f6da14d 100644 --- a/src/systems/detachable_joint/DetachableJoint.cc +++ b/src/systems/detachable_joint/DetachableJoint.cc @@ -24,14 +24,14 @@ #include -#include "ignition/gazebo/components/DetachableJoint.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/Pose.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/DetachableJoint.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/Pose.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" #include "DetachableJoint.hh" diff --git a/src/systems/detachable_joint/DetachableJoint.hh b/src/systems/detachable_joint/DetachableJoint.hh index f52dc9d24a9..5de2d566355 100644 --- a/src/systems/detachable_joint/DetachableJoint.hh +++ b/src/systems/detachable_joint/DetachableJoint.hh @@ -24,8 +24,8 @@ #include #include -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/System.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/diff_drive/DiffDrive.cc b/src/systems/diff_drive/DiffDrive.cc index ec8e5a46d27..a9f2c6ee516 100644 --- a/src/systems/diff_drive/DiffDrive.cc +++ b/src/systems/diff_drive/DiffDrive.cc @@ -32,12 +32,12 @@ #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 "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/diff_drive/DiffDrive.hh b/src/systems/diff_drive/DiffDrive.hh index c9d45e66173..9ef73091e6c 100644 --- a/src/systems/diff_drive/DiffDrive.hh +++ b/src/systems/diff_drive/DiffDrive.hh @@ -19,7 +19,7 @@ #include -#include +#include namespace ignition { diff --git a/src/systems/elevator/Elevator.cc b/src/systems/elevator/Elevator.cc index d78bd26bb4e..a03b6f8dec3 100644 --- a/src/systems/elevator/Elevator.cc +++ b/src/systems/elevator/Elevator.cc @@ -41,14 +41,14 @@ #include #include -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/JointVelocity.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/JointVelocity.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" namespace ignition { diff --git a/src/systems/elevator/Elevator.hh b/src/systems/elevator/Elevator.hh index cbb44da5b76..e18cc76d11e 100644 --- a/src/systems/elevator/Elevator.hh +++ b/src/systems/elevator/Elevator.hh @@ -25,7 +25,7 @@ #include -#include +#include namespace ignition { diff --git a/src/systems/elevator/ElevatorStateMachine.hh b/src/systems/elevator/ElevatorStateMachine.hh index 6dfa7811f30..ad75000b172 100644 --- a/src/systems/elevator/ElevatorStateMachine.hh +++ b/src/systems/elevator/ElevatorStateMachine.hh @@ -25,7 +25,7 @@ #include -#include +#include #include #include "afsm/fsm.hpp" diff --git a/src/systems/elevator/utils/DoorTimer.hh b/src/systems/elevator/utils/DoorTimer.hh index bcfeb18a2f8..352889760d8 100644 --- a/src/systems/elevator/utils/DoorTimer.hh +++ b/src/systems/elevator/utils/DoorTimer.hh @@ -27,7 +27,7 @@ #include #include -#include +#include namespace ignition { diff --git a/src/systems/elevator/utils/JointMonitor.cc b/src/systems/elevator/utils/JointMonitor.cc index f2aa68a9a1d..d55c270664d 100644 --- a/src/systems/elevator/utils/JointMonitor.cc +++ b/src/systems/elevator/utils/JointMonitor.cc @@ -24,8 +24,8 @@ #include "JointMonitor.hh" -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/elevator/utils/JointMonitor.hh b/src/systems/elevator/utils/JointMonitor.hh index a42046b4abf..3f4b602a699 100644 --- a/src/systems/elevator/utils/JointMonitor.hh +++ b/src/systems/elevator/utils/JointMonitor.hh @@ -26,7 +26,7 @@ #include #include -#include +#include namespace ignition { diff --git a/src/systems/follow_actor/FollowActor.cc b/src/systems/follow_actor/FollowActor.cc index f55c65c8ce2..f72c84e9a13 100644 --- a/src/systems/follow_actor/FollowActor.cc +++ b/src/systems/follow_actor/FollowActor.cc @@ -21,11 +21,11 @@ #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 6c6023d836b..1443d12fb3d 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 { @@ -32,7 +32,7 @@ namespace systems // Forward declarations. class FollowActorPrivate; - /// \class FollowActor FollowActor.hh ignition/gazebo/systems/FollowActor.hh + /// \class FollowActor FollowActor.hh gz/sim/systems/FollowActor.hh /// \brief Make an actor follow a target entity in the world. /// /// ## SDF parameters diff --git a/src/systems/force_torque/ForceTorque.cc b/src/systems/force_torque/ForceTorque.cc index aed58c4664f..bed525ce2cd 100644 --- a/src/systems/force_torque/ForceTorque.cc +++ b/src/systems/force_torque/ForceTorque.cc @@ -32,19 +32,19 @@ #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 "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 5df5652fb0d..25b13aebfeb 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 { @@ -32,7 +32,7 @@ namespace systems // Forward declarations. class ForceTorquePrivate; - /// \class ForceTorque ForceTorque.hh ignition/gazebo/systems/ForceTorque.hh + /// \class ForceTorque ForceTorque.hh gz/sim/systems/ForceTorque.hh /// \brief This system manages all Force-Torque sensors in simulation. /// Each FT sensor reports readings over Ignition Transport. /// \note Regardless of the setting of //sensor/force_torque/frame the point diff --git a/src/systems/hydrodynamics/Hydrodynamics.cc b/src/systems/hydrodynamics/Hydrodynamics.cc index 767a7e036da..259e2f6d3cb 100644 --- a/src/systems/hydrodynamics/Hydrodynamics.cc +++ b/src/systems/hydrodynamics/Hydrodynamics.cc @@ -22,14 +22,14 @@ #include "ignition/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" diff --git a/src/systems/hydrodynamics/Hydrodynamics.hh b/src/systems/hydrodynamics/Hydrodynamics.hh index a06b37be7cb..efac6031519 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/imu/Imu.cc b/src/systems/imu/Imu.cc index bc1d504ebc5..9a7becb3b9b 100644 --- a/src/systems/imu/Imu.cc +++ b/src/systems/imu/Imu.cc @@ -31,18 +31,18 @@ #include #include -#include "ignition/gazebo/World.hh" -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/Imu.hh" -#include "ignition/gazebo/components/Gravity.hh" -#include "ignition/gazebo/components/LinearAcceleration.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/World.hh" +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/Imu.hh" +#include "gz/sim/components/Gravity.hh" +#include "gz/sim/components/LinearAcceleration.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/ParentEntity.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/imu/Imu.hh b/src/systems/imu/Imu.hh index 6194c4ec99e..0dc1c505558 100644 --- a/src/systems/imu/Imu.hh +++ b/src/systems/imu/Imu.hh @@ -18,8 +18,8 @@ #define IGNITION_GAZEBO_SYSTEMS_IMU_HH_ #include -#include -#include +#include +#include namespace ignition { @@ -32,7 +32,7 @@ namespace systems // Forward declarations. class ImuPrivate; - /// \class Imu Imu.hh ignition/gazebo/systems/Imu.hh + /// \class Imu Imu.hh gz/sim/systems/Imu.hh /// \brief This system manages all IMU sensors in simulation. /// Each IMU sensor eports vertical position, angular velocity /// and lienar acceleration readings over Ignition Transport. diff --git a/src/systems/joint_controller/JointController.cc b/src/systems/joint_controller/JointController.cc index 3f5a1cdfd11..a50fda4b9b1 100644 --- a/src/systems/joint_controller/JointController.cc +++ b/src/systems/joint_controller/JointController.cc @@ -26,10 +26,10 @@ #include #include -#include "ignition/gazebo/components/JointForceCmd.hh" -#include "ignition/gazebo/components/JointVelocity.hh" -#include "ignition/gazebo/components/JointVelocityCmd.hh" -#include "ignition/gazebo/Model.hh" +#include "gz/sim/components/JointForceCmd.hh" +#include "gz/sim/components/JointVelocity.hh" +#include "gz/sim/components/JointVelocityCmd.hh" +#include "gz/sim/Model.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/joint_controller/JointController.hh b/src/systems/joint_controller/JointController.hh index d3a1fb65876..f2fbf9e9686 100644 --- a/src/systems/joint_controller/JointController.hh +++ b/src/systems/joint_controller/JointController.hh @@ -17,7 +17,7 @@ #ifndef IGNITION_GAZEBO_SYSTEMS_JOINTCONTROLLER_HH_ #define IGNITION_GAZEBO_SYSTEMS_JOINTCONTROLLER_HH_ -#include +#include #include namespace ignition diff --git a/src/systems/joint_position_controller/JointPositionController.cc b/src/systems/joint_position_controller/JointPositionController.cc index 5f7ca8a8a8a..447d0e0e0ea 100644 --- a/src/systems/joint_position_controller/JointPositionController.cc +++ b/src/systems/joint_position_controller/JointPositionController.cc @@ -27,10 +27,10 @@ #include #include -#include "ignition/gazebo/components/JointForceCmd.hh" -#include "ignition/gazebo/components/JointVelocityCmd.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/Model.hh" +#include "gz/sim/components/JointForceCmd.hh" +#include "gz/sim/components/JointVelocityCmd.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/Model.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/joint_position_controller/JointPositionController.hh b/src/systems/joint_position_controller/JointPositionController.hh index 3dcaeac3f7a..eb508c4f84d 100644 --- a/src/systems/joint_position_controller/JointPositionController.hh +++ b/src/systems/joint_position_controller/JointPositionController.hh @@ -18,7 +18,7 @@ #define IGNITION_GAZEBO_SYSTEMS_JOINTPOSITIONCONTROLLER_HH_ #include -#include +#include namespace ignition { diff --git a/src/systems/joint_state_publisher/JointStatePublisher.cc b/src/systems/joint_state_publisher/JointStatePublisher.cc index 5a995b9dfde..2f4078bfadf 100644 --- a/src/systems/joint_state_publisher/JointStatePublisher.cc +++ b/src/systems/joint_state_publisher/JointStatePublisher.cc @@ -24,17 +24,17 @@ #include -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/JointForce.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/JointVelocity.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/ParentLinkName.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/JointForce.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/JointVelocity.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/ParentLinkName.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/joint_state_publisher/JointStatePublisher.hh b/src/systems/joint_state_publisher/JointStatePublisher.hh index 75c13f15a74..0f0aaa1884b 100644 --- a/src/systems/joint_state_publisher/JointStatePublisher.hh +++ b/src/systems/joint_state_publisher/JointStatePublisher.hh @@ -21,9 +21,9 @@ #include #include #include -#include +#include #include -#include +#include namespace ignition { diff --git a/src/systems/joint_traj_control/JointTrajectoryController.cc b/src/systems/joint_traj_control/JointTrajectoryController.cc index d7cb345e603..21bd99ef686 100644 --- a/src/systems/joint_traj_control/JointTrajectoryController.cc +++ b/src/systems/joint_traj_control/JointTrajectoryController.cc @@ -18,14 +18,14 @@ #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 fb60279d1d7..0caa15181ab 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/kinetic_energy_monitor/KineticEnergyMonitor.cc b/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.cc index 00978cc26f0..ef5ad3c9774 100644 --- a/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.cc +++ b/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.cc @@ -20,17 +20,17 @@ #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/kinetic_energy_monitor/KineticEnergyMonitor.hh b/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.hh index 2b5429d1176..fa68062a00c 100644 --- a/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.hh +++ b/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.hh @@ -19,9 +19,9 @@ #define IGNITION_GAZEBO_SYSTEMS_KINETIC_ENERGY_MONITOR_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/src/systems/label/Label.cc b/src/systems/label/Label.cc index 09986de1048..dc5c5934062 100644 --- a/src/systems/label/Label.cc +++ b/src/systems/label/Label.cc @@ -21,12 +21,12 @@ #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 a0d6fffde6e..4f09d886de2 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/lift_drag/LiftDrag.cc b/src/systems/lift_drag/LiftDrag.cc index d809f2292c6..4be74fcea29 100644 --- a/src/systems/lift_drag/LiftDrag.cc +++ b/src/systems/lift_drag/LiftDrag.cc @@ -27,19 +27,19 @@ #include -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" - -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/Inertial.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ExternalWorldWrenchCmd.hh" -#include "ignition/gazebo/components/Pose.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" + +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/Inertial.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ExternalWorldWrenchCmd.hh" +#include "gz/sim/components/Pose.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/lift_drag/LiftDrag.hh b/src/systems/lift_drag/LiftDrag.hh index b79e55616df..943da2d398f 100644 --- a/src/systems/lift_drag/LiftDrag.hh +++ b/src/systems/lift_drag/LiftDrag.hh @@ -19,7 +19,7 @@ #define IGNITION_GAZEBO_SYSTEMS_LIFT_DRAG_HH_ #include -#include +#include namespace ignition { diff --git a/src/systems/log/LogPlayback.cc b/src/systems/log/LogPlayback.cc index 3ee2b21bbff..deb51586bf8 100644 --- a/src/systems/log/LogPlayback.cc +++ b/src/systems/log/LogPlayback.cc @@ -37,15 +37,15 @@ #include #include -#include "ignition/gazebo/Conversions.hh" -#include "ignition/gazebo/Events.hh" -#include "ignition/gazebo/SdfEntityCreator.hh" -#include "ignition/gazebo/components/Geometry.hh" -#include "ignition/gazebo/components/LogPlaybackStatistics.hh" -#include "ignition/gazebo/components/Material.hh" -#include "ignition/gazebo/components/ParticleEmitter.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/World.hh" +#include "gz/sim/Conversions.hh" +#include "gz/sim/Events.hh" +#include "gz/sim/SdfEntityCreator.hh" +#include "gz/sim/components/Geometry.hh" +#include "gz/sim/components/LogPlaybackStatistics.hh" +#include "gz/sim/components/Material.hh" +#include "gz/sim/components/ParticleEmitter.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/World.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/log/LogPlayback.hh b/src/systems/log/LogPlayback.hh index 07086f63c9c..737884c3a78 100644 --- a/src/systems/log/LogPlayback.hh +++ b/src/systems/log/LogPlayback.hh @@ -19,8 +19,8 @@ #include -#include -#include +#include +#include namespace ignition { @@ -34,7 +34,7 @@ namespace systems class LogPlaybackPrivate; /// \class LogPlayback LogPlayback.hh - /// ignition/gazebo/systems/log/LogPlayback.hh + /// gz/sim/systems/log/LogPlayback.hh /// \brief Log state playback class LogPlayback: public System, diff --git a/src/systems/log/LogRecord.cc b/src/systems/log/LogRecord.cc index 87995ca0d08..d41262cafde 100644 --- a/src/systems/log/LogRecord.cc +++ b/src/systems/log/LogRecord.cc @@ -48,17 +48,17 @@ #include #include -#include "ignition/gazebo/components/Geometry.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Material.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/SourceFilePath.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/World.hh" - -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/Geometry.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Material.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/SourceFilePath.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.hh" + +#include "gz/sim/Util.hh" using namespace ignition; using namespace ignition::gazebo; diff --git a/src/systems/log/LogRecord.hh b/src/systems/log/LogRecord.hh index f03edd4e35f..ed40cee2935 100644 --- a/src/systems/log/LogRecord.hh +++ b/src/systems/log/LogRecord.hh @@ -19,8 +19,8 @@ #include -#include -#include +#include +#include namespace ignition { @@ -33,7 +33,7 @@ namespace systems // Forward declarations. class LogRecordPrivate; - /// \class LogRecord LogRecord.hh ignition/gazebo/systems/log/LogRecord.hh + /// \class LogRecord LogRecord.hh gz/sim/systems/log/LogRecord.hh /// \brief Log state recorder class LogRecord: public System, diff --git a/src/systems/log_video_recorder/LogVideoRecorder.cc b/src/systems/log_video_recorder/LogVideoRecorder.cc index 29416a3a0e4..9cd1dd92d7b 100644 --- a/src/systems/log_video_recorder/LogVideoRecorder.cc +++ b/src/systems/log_video_recorder/LogVideoRecorder.cc @@ -29,14 +29,14 @@ #include #include -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Static.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Conversions.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Events.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Static.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Conversions.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Events.hh" using namespace std::chrono_literals; diff --git a/src/systems/log_video_recorder/LogVideoRecorder.hh b/src/systems/log_video_recorder/LogVideoRecorder.hh index de4b565440c..7168d81a954 100644 --- a/src/systems/log_video_recorder/LogVideoRecorder.hh +++ b/src/systems/log_video_recorder/LogVideoRecorder.hh @@ -19,8 +19,8 @@ #include #include -#include -#include +#include +#include namespace ignition { @@ -33,7 +33,7 @@ namespace systems class LogVideoRecorderPrivate; /** \class LogVideoRecorder LogVideoRecorder.hh \ - * ignition/gazebo/systems/LogVideoRecorder.hh + * gz/sim/systems/LogVideoRecorder.hh **/ /// \brief System which recordings videos from log playback /// There are two ways to specify what entities in the log playback to follow diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudio.hh b/src/systems/logical_audio_sensor_plugin/LogicalAudio.hh index 8eb7feb3727..7453e86993a 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudio.hh +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudio.hh @@ -19,9 +19,9 @@ #include -#include -#include -#include +#include +#include +#include #include namespace ignition diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc index 78ab1b7d659..b5f96eec399 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc @@ -25,17 +25,17 @@ #include #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include #include #include -#include -#include +#include +#include #include #include "LogicalAudio.hh" diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh index 3dcaeb67a22..ee0bfe72758 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh @@ -19,7 +19,7 @@ #include -#include +#include namespace ignition { diff --git a/src/systems/logical_camera/LogicalCamera.cc b/src/systems/logical_camera/LogicalCamera.cc index 9a051f41143..d8596d606e6 100644 --- a/src/systems/logical_camera/LogicalCamera.cc +++ b/src/systems/logical_camera/LogicalCamera.cc @@ -36,15 +36,15 @@ #include #include -#include "ignition/gazebo/components/LogicalCamera.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/ParentEntity.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 "gz/sim/components/LogicalCamera.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/ParentEntity.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/logical_camera/LogicalCamera.hh b/src/systems/logical_camera/LogicalCamera.hh index 8d2ab28e38b..8670bb800e5 100644 --- a/src/systems/logical_camera/LogicalCamera.hh +++ b/src/systems/logical_camera/LogicalCamera.hh @@ -18,8 +18,8 @@ #define IGNITION_GAZEBO_SYSTEMS_LOGICALCAMERA_HH_ #include -#include -#include +#include +#include namespace ignition { @@ -33,7 +33,7 @@ namespace systems class LogicalCameraPrivate; /** \class LogicalCamera LogicalCamera.hh \ - * ignition/gazebo/systems/LogicalCamera.hh + * gz/sim/systems/LogicalCamera.hh **/ /// \brief A logical camera sensor that reports objects detected within its /// frustum readings over ign transport diff --git a/src/systems/magnetometer/Magnetometer.cc b/src/systems/magnetometer/Magnetometer.cc index fd2963e35a2..8818cba8c95 100644 --- a/src/systems/magnetometer/Magnetometer.cc +++ b/src/systems/magnetometer/Magnetometer.cc @@ -33,15 +33,15 @@ #include #include -#include "ignition/gazebo/components/MagneticField.hh" -#include "ignition/gazebo/components/Magnetometer.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/MagneticField.hh" +#include "gz/sim/components/Magnetometer.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/ParentEntity.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/magnetometer/Magnetometer.hh b/src/systems/magnetometer/Magnetometer.hh index 5294fe96ee0..8feda59e5e2 100644 --- a/src/systems/magnetometer/Magnetometer.hh +++ b/src/systems/magnetometer/Magnetometer.hh @@ -18,8 +18,8 @@ #define IGNITION_GAZEBO_SYSTEMS_MAGNETOMETER_HH_ #include -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/mecanum_drive/MecanumDrive.cc b/src/systems/mecanum_drive/MecanumDrive.cc index 59dd7016759..d0b7f1b5935 100644 --- a/src/systems/mecanum_drive/MecanumDrive.cc +++ b/src/systems/mecanum_drive/MecanumDrive.cc @@ -32,12 +32,12 @@ #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 "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 e9db61c2c9b..38b7e342fe2 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 25b1bded900..a3757743cbb 100644 --- a/src/systems/model_photo_shoot/ModelPhotoShoot.cc +++ b/src/systems/model_photo_shoot/ModelPhotoShoot.cc @@ -27,16 +27,16 @@ #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 "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 b059f2486e2..9a14609c6a9 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_control/Common.cc b/src/systems/multicopter_control/Common.cc index 137f70dbd48..177f3ced816 100644 --- a/src/systems/multicopter_control/Common.cc +++ b/src/systems/multicopter_control/Common.cc @@ -22,15 +22,15 @@ #include #include -#include -#include -#include -#include -#include -#include -#include -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/AngularVelocity.hh" +#include +#include +#include +#include +#include +#include +#include +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/AngularVelocity.hh" namespace ignition { diff --git a/src/systems/multicopter_control/Common.hh b/src/systems/multicopter_control/Common.hh index d0e41f7689f..ca39eb2b466 100644 --- a/src/systems/multicopter_control/Common.hh +++ b/src/systems/multicopter_control/Common.hh @@ -24,9 +24,9 @@ #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Model.hh" +#include "gz/sim/config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Model.hh" #include "Parameters.hh" diff --git a/src/systems/multicopter_control/LeeVelocityController.hh b/src/systems/multicopter_control/LeeVelocityController.hh index d0d48ea4b73..e871894a0ec 100644 --- a/src/systems/multicopter_control/LeeVelocityController.hh +++ b/src/systems/multicopter_control/LeeVelocityController.hh @@ -20,7 +20,7 @@ #include #include -#include "ignition/gazebo/config.hh" +#include "gz/sim/config.hh" #include "Common.hh" #include "LeeVelocityController.hh" diff --git a/src/systems/multicopter_control/MulticopterVelocityControl.cc b/src/systems/multicopter_control/MulticopterVelocityControl.cc index 9eb4b248b43..7539e010558 100644 --- a/src/systems/multicopter_control/MulticopterVelocityControl.cc +++ b/src/systems/multicopter_control/MulticopterVelocityControl.cc @@ -32,14 +32,14 @@ #include -#include "ignition/gazebo/components/Actuators.hh" -#include "ignition/gazebo/components/Gravity.hh" -#include "ignition/gazebo/components/Inertial.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" +#include "gz/sim/components/Actuators.hh" +#include "gz/sim/components/Gravity.hh" +#include "gz/sim/components/Inertial.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" #include "MulticopterVelocityControl.hh" diff --git a/src/systems/multicopter_control/MulticopterVelocityControl.hh b/src/systems/multicopter_control/MulticopterVelocityControl.hh index 0fe9d7ece67..3424bb8a505 100644 --- a/src/systems/multicopter_control/MulticopterVelocityControl.hh +++ b/src/systems/multicopter_control/MulticopterVelocityControl.hh @@ -23,9 +23,9 @@ #include -#include -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" +#include +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" #include "Common.hh" #include "LeeVelocityController.hh" diff --git a/src/systems/multicopter_control/Parameters.hh b/src/systems/multicopter_control/Parameters.hh index 149ab9d7cab..3d174c8a8ce 100644 --- a/src/systems/multicopter_control/Parameters.hh +++ b/src/systems/multicopter_control/Parameters.hh @@ -21,7 +21,7 @@ #include #include -#include "ignition/gazebo/config.hh" +#include "gz/sim/config.hh" namespace ignition { diff --git a/src/systems/multicopter_motor_model/MulticopterMotorModel.cc b/src/systems/multicopter_motor_model/MulticopterMotorModel.cc index dbb5102d00c..6e1e85621f6 100644 --- a/src/systems/multicopter_motor_model/MulticopterMotorModel.cc +++ b/src/systems/multicopter_motor_model/MulticopterMotorModel.cc @@ -38,17 +38,17 @@ #include -#include "ignition/gazebo/components/Actuators.hh" -#include "ignition/gazebo/components/ExternalWorldWrenchCmd.hh" -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/JointVelocity.hh" -#include "ignition/gazebo/components/JointVelocityCmd.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/ParentLinkName.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Wind.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" +#include "gz/sim/components/Actuators.hh" +#include "gz/sim/components/ExternalWorldWrenchCmd.hh" +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/JointVelocity.hh" +#include "gz/sim/components/JointVelocityCmd.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/ParentLinkName.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Wind.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" // from rotors_gazebo_plugins/include/rotors_gazebo_plugins/common.h /// \brief This class can be used to apply a first order filter on a signal. diff --git a/src/systems/multicopter_motor_model/MulticopterMotorModel.hh b/src/systems/multicopter_motor_model/MulticopterMotorModel.hh index 1c736bf505d..19ed209491c 100644 --- a/src/systems/multicopter_motor_model/MulticopterMotorModel.hh +++ b/src/systems/multicopter_motor_model/MulticopterMotorModel.hh @@ -17,7 +17,7 @@ #ifndef IGNITION_GAZEBO_SYSTEMS_MULTICOPTERMOTORMODEL_HH_ #define IGNITION_GAZEBO_SYSTEMS_MULTICOPTERMOTORMODEL_HH_ -#include +#include #include namespace ignition diff --git a/src/systems/navsat/NavSat.cc b/src/systems/navsat/NavSat.cc index faa8f4f38f2..935b8de03f2 100644 --- a/src/systems/navsat/NavSat.cc +++ b/src/systems/navsat/NavSat.cc @@ -36,13 +36,13 @@ #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 e4ce4f34d66..1b990a910a1 100644 --- a/src/systems/navsat/NavSat.hh +++ b/src/systems/navsat/NavSat.hh @@ -19,8 +19,8 @@ #include -#include -#include +#include +#include namespace ignition { @@ -30,7 +30,7 @@ namespace gazebo inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { namespace systems { - /// \class NavSat NavSat.hh ignition/gazebo/systems/NavSat.hh + /// \class NavSat NavSat.hh gz/sim/systems/NavSat.hh /// \brief System that handles navigation satellite sensors, such as GPS, /// that reports position and velocity in spherical coordinates (latitude / /// longitude) over Ignition Transport. diff --git a/src/systems/odometry_publisher/OdometryPublisher.cc b/src/systems/odometry_publisher/OdometryPublisher.cc index 8bdd6f215b6..76c99045df9 100644 --- a/src/systems/odometry_publisher/OdometryPublisher.cc +++ b/src/systems/odometry_publisher/OdometryPublisher.cc @@ -34,10 +34,10 @@ #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 "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 7fdab8253ba..b69cc68f7b0 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 ea898e4d511..35b2bf51090 100644 --- a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc +++ b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc @@ -27,19 +27,19 @@ #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 687246b6a85..2ab466778d6 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.hh b/src/systems/optical_tactile_plugin/Visualization.hh index 978b3e5acac..571f9baad30 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 "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 fe71f14f0fb..cd07e953eae 100644 --- a/src/systems/particle_emitter/ParticleEmitter.cc +++ b/src/systems/particle_emitter/ParticleEmitter.cc @@ -28,11 +28,11 @@ #include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include "ParticleEmitter.hh" using namespace std::chrono_literals; diff --git a/src/systems/particle_emitter/ParticleEmitter.hh b/src/systems/particle_emitter/ParticleEmitter.hh index ed144dab4d0..06fb0ae9886 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 1478ccf5f59..683e72b3c62 100644 --- a/src/systems/particle_emitter2/ParticleEmitter2.cc +++ b/src/systems/particle_emitter2/ParticleEmitter2.cc @@ -28,11 +28,11 @@ #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 e9dd359d004..81b00f30822 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 08f24cc033c..c238af9a0ed 100644 --- a/src/systems/perfect_comms/PerfectComms.cc +++ b/src/systems/perfect_comms/PerfectComms.cc @@ -19,9 +19,9 @@ #include #include -#include "ignition/gazebo/comms/Broker.hh" -#include "ignition/gazebo/comms/MsgManager.hh" -#include "ignition/gazebo/Util.hh" +#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 9ac93f07a78..20bfdb8dcc7 100644 --- a/src/systems/perfect_comms/PerfectComms.hh +++ b/src/systems/perfect_comms/PerfectComms.hh @@ -21,8 +21,8 @@ #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/performer_detector/PerformerDetector.cc b/src/systems/performer_detector/PerformerDetector.cc index 7da45abd733..7cb072889a0 100644 --- a/src/systems/performer_detector/PerformerDetector.cc +++ b/src/systems/performer_detector/PerformerDetector.cc @@ -26,14 +26,14 @@ #include #include -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/components/Geometry.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Performer.hh" -#include "ignition/gazebo/components/Pose.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/components/Geometry.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Performer.hh" +#include "gz/sim/components/Pose.hh" #include "PerformerDetector.hh" diff --git a/src/systems/performer_detector/PerformerDetector.hh b/src/systems/performer_detector/PerformerDetector.hh index 72d651b1215..190be783a25 100644 --- a/src/systems/performer_detector/PerformerDetector.hh +++ b/src/systems/performer_detector/PerformerDetector.hh @@ -25,8 +25,8 @@ #include -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/System.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/physics/CanonicalLinkModelTracker.hh b/src/systems/physics/CanonicalLinkModelTracker.hh index 4f6f01443e5..44e6f99e025 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/physics/EntityFeatureMap.hh b/src/systems/physics/EntityFeatureMap.hh index 933accc9faa..7f64a24b1a7 100644 --- a/src/systems/physics/EntityFeatureMap.hh +++ b/src/systems/physics/EntityFeatureMap.hh @@ -27,7 +27,7 @@ #include #include -#include "ignition/gazebo/Entity.hh" +#include "gz/sim/Entity.hh" namespace ignition::gazebo { diff --git a/src/systems/physics/EntityFeatureMap_TEST.cc b/src/systems/physics/EntityFeatureMap_TEST.cc index 8f0547918a3..1b5a18aaaed 100644 --- a/src/systems/physics/EntityFeatureMap_TEST.cc +++ b/src/systems/physics/EntityFeatureMap_TEST.cc @@ -32,7 +32,7 @@ #include #include "../../../test/helpers/EnvTestFixture.hh" -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/EntityComponentManager.hh" using namespace ignition; using namespace ignition::gazebo::systems::physics_system; diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 094fafa3f14..e532bb578da 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -85,61 +85,61 @@ #include #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" // Components -#include "ignition/gazebo/components/AngularAcceleration.hh" -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/AngularVelocityCmd.hh" -#include "ignition/gazebo/components/AxisAlignedBox.hh" -#include "ignition/gazebo/components/BatterySoC.hh" -#include "ignition/gazebo/components/CanonicalLink.hh" -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/ContactSensorData.hh" -#include "ignition/gazebo/components/Geometry.hh" -#include "ignition/gazebo/components/Gravity.hh" -#include "ignition/gazebo/components/Inertial.hh" -#include "ignition/gazebo/components/DetachableJoint.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/JointEffortLimitsCmd.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/JointPositionLimitsCmd.hh" -#include "ignition/gazebo/components/JointPositionReset.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/LinearAcceleration.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/LinearVelocityCmd.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/ExternalWorldWrenchCmd.hh" -#include "ignition/gazebo/components/JointTransmittedWrench.hh" -#include "ignition/gazebo/components/JointForceCmd.hh" -#include "ignition/gazebo/components/Physics.hh" -#include "ignition/gazebo/components/PhysicsEnginePlugin.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/PoseCmd.hh" -#include "ignition/gazebo/components/Recreate.hh" -#include "ignition/gazebo/components/SelfCollide.hh" -#include "ignition/gazebo/components/SlipComplianceCmd.hh" -#include "ignition/gazebo/components/Static.hh" -#include "ignition/gazebo/components/ThreadPitch.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/components/HaltMotion.hh" +#include "gz/sim/components/AngularAcceleration.hh" +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/AngularVelocityCmd.hh" +#include "gz/sim/components/AxisAlignedBox.hh" +#include "gz/sim/components/BatterySoC.hh" +#include "gz/sim/components/CanonicalLink.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/ContactSensorData.hh" +#include "gz/sim/components/Geometry.hh" +#include "gz/sim/components/Gravity.hh" +#include "gz/sim/components/Inertial.hh" +#include "gz/sim/components/DetachableJoint.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/JointEffortLimitsCmd.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/JointPositionLimitsCmd.hh" +#include "gz/sim/components/JointPositionReset.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/LinearAcceleration.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/LinearVelocityCmd.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/ExternalWorldWrenchCmd.hh" +#include "gz/sim/components/JointTransmittedWrench.hh" +#include "gz/sim/components/JointForceCmd.hh" +#include "gz/sim/components/Physics.hh" +#include "gz/sim/components/PhysicsEnginePlugin.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/PoseCmd.hh" +#include "gz/sim/components/Recreate.hh" +#include "gz/sim/components/SelfCollide.hh" +#include "gz/sim/components/SlipComplianceCmd.hh" +#include "gz/sim/components/Static.hh" +#include "gz/sim/components/ThreadPitch.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/components/HaltMotion.hh" #include "CanonicalLinkModelTracker.hh" // Events -#include "ignition/gazebo/physics/Events.hh" +#include "gz/sim/physics/Events.hh" #include "EntityFeatureMap.hh" diff --git a/src/systems/physics/Physics.hh b/src/systems/physics/Physics.hh index 98ebde22d51..854247010b6 100644 --- a/src/systems/physics/Physics.hh +++ b/src/systems/physics/Physics.hh @@ -48,8 +48,8 @@ #include #include -#include -#include +#include +#include namespace ignition { @@ -62,7 +62,7 @@ namespace systems // Forward declarations. class PhysicsPrivate; - /// \class Physics Physics.hh ignition/gazebo/systems/Physics.hh + /// \class Physics Physics.hh gz/sim/systems/Physics.hh /// \brief Base class for a System. /// Includes optional parameter : . When set /// to false, the name of colliding entities is not populated in diff --git a/src/systems/pose_publisher/PosePublisher.cc b/src/systems/pose_publisher/PosePublisher.cc index 010c88b10bf..e82eb71fd5c 100644 --- a/src/systems/pose_publisher/PosePublisher.cc +++ b/src/systems/pose_publisher/PosePublisher.cc @@ -33,22 +33,22 @@ #include #include -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/components/CanonicalLink.hh" -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/Joint.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/Sensor.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/Conversions.hh" -#include "ignition/gazebo/Model.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/components/CanonicalLink.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/Joint.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/Sensor.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/Conversions.hh" +#include "gz/sim/Model.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/pose_publisher/PosePublisher.hh b/src/systems/pose_publisher/PosePublisher.hh index e3797b0bf62..8dda7e336d1 100644 --- a/src/systems/pose_publisher/PosePublisher.hh +++ b/src/systems/pose_publisher/PosePublisher.hh @@ -18,8 +18,8 @@ #define IGNITION_GAZEBO_SYSTEMS_POSEPUBLISHER_HH_ #include -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/rf_comms/RFComms.cc b/src/systems/rf_comms/RFComms.cc index 199d6f55ced..e11314c14e5 100644 --- a/src/systems/rf_comms/RFComms.cc +++ b/src/systems/rf_comms/RFComms.cc @@ -28,11 +28,11 @@ #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 "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 c36696b62ae..e5368320eda 100644 --- a/src/systems/rf_comms/RFComms.hh +++ b/src/systems/rf_comms/RFComms.hh @@ -21,8 +21,8 @@ #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/scene_broadcaster/SceneBroadcaster.cc b/src/systems/scene_broadcaster/SceneBroadcaster.cc index ad168d2811b..0f2f949fb1e 100644 --- a/src/systems/scene_broadcaster/SceneBroadcaster.cc +++ b/src/systems/scene_broadcaster/SceneBroadcaster.cc @@ -31,33 +31,33 @@ #include #include -#include "ignition/gazebo/components/AirPressureSensor.hh" -#include "ignition/gazebo/components/Altimeter.hh" -#include "ignition/gazebo/components/Camera.hh" -#include "ignition/gazebo/components/CastShadows.hh" -#include "ignition/gazebo/components/ContactSensor.hh" -#include "ignition/gazebo/components/DepthCamera.hh" -#include "ignition/gazebo/components/Geometry.hh" -#include "ignition/gazebo/components/GpuLidar.hh" -#include "ignition/gazebo/components/Imu.hh" -#include "ignition/gazebo/components/LaserRetro.hh" -#include "ignition/gazebo/components/Lidar.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/LogicalCamera.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/Pose.hh" -#include "ignition/gazebo/components/RgbdCamera.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/Static.hh" -#include "ignition/gazebo/components/ThermalCamera.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Conversions.hh" -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/components/AirPressureSensor.hh" +#include "gz/sim/components/Altimeter.hh" +#include "gz/sim/components/Camera.hh" +#include "gz/sim/components/CastShadows.hh" +#include "gz/sim/components/ContactSensor.hh" +#include "gz/sim/components/DepthCamera.hh" +#include "gz/sim/components/Geometry.hh" +#include "gz/sim/components/GpuLidar.hh" +#include "gz/sim/components/Imu.hh" +#include "gz/sim/components/LaserRetro.hh" +#include "gz/sim/components/Lidar.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/LogicalCamera.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/Pose.hh" +#include "gz/sim/components/RgbdCamera.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/Static.hh" +#include "gz/sim/components/ThermalCamera.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Conversions.hh" +#include "gz/sim/EntityComponentManager.hh" #include #include diff --git a/src/systems/scene_broadcaster/SceneBroadcaster.hh b/src/systems/scene_broadcaster/SceneBroadcaster.hh index faeedd0b447..4b3a1b8a348 100644 --- a/src/systems/scene_broadcaster/SceneBroadcaster.hh +++ b/src/systems/scene_broadcaster/SceneBroadcaster.hh @@ -19,8 +19,8 @@ #include #include -#include -#include +#include +#include namespace ignition { @@ -33,7 +33,7 @@ namespace systems class SceneBroadcasterPrivate; /** \class SceneBroadcaster SceneBroadcaster.hh \ - * ignition/gazebo/systems/SceneBroadcaster.hh + * gz/sim/systems/SceneBroadcaster.hh **/ /// \brief System which periodically publishes an ignition::msgs::Scene /// message with updated information. diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc index 265fc49aa97..d9b9c8db30d 100644 --- a/src/systems/sensors/Sensors.cc +++ b/src/systems/sensors/Sensors.cc @@ -41,24 +41,24 @@ #include #include -#include "ignition/gazebo/components/Atmosphere.hh" -#include "ignition/gazebo/components/BatterySoC.hh" -#include "ignition/gazebo/components/Camera.hh" -#include "ignition/gazebo/components/DepthCamera.hh" -#include "ignition/gazebo/components/GpuLidar.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/RenderEngineServerHeadless.hh" -#include "ignition/gazebo/components/RenderEngineServerPlugin.hh" -#include "ignition/gazebo/components/RgbdCamera.hh" -#include "ignition/gazebo/components/SegmentationCamera.hh" -#include "ignition/gazebo/components/ThermalCamera.hh" -#include "ignition/gazebo/components/WideAngleCamera.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Events.hh" -#include "ignition/gazebo/EntityComponentManager.hh" - -#include "ignition/gazebo/rendering/Events.hh" -#include "ignition/gazebo/rendering/RenderUtil.hh" +#include "gz/sim/components/Atmosphere.hh" +#include "gz/sim/components/BatterySoC.hh" +#include "gz/sim/components/Camera.hh" +#include "gz/sim/components/DepthCamera.hh" +#include "gz/sim/components/GpuLidar.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/RenderEngineServerHeadless.hh" +#include "gz/sim/components/RenderEngineServerPlugin.hh" +#include "gz/sim/components/RgbdCamera.hh" +#include "gz/sim/components/SegmentationCamera.hh" +#include "gz/sim/components/ThermalCamera.hh" +#include "gz/sim/components/WideAngleCamera.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Events.hh" +#include "gz/sim/EntityComponentManager.hh" + +#include "gz/sim/rendering/Events.hh" +#include "gz/sim/rendering/RenderUtil.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/sensors/Sensors.hh b/src/systems/sensors/Sensors.hh index 87e317bc6c7..0c0b05b663a 100644 --- a/src/systems/sensors/Sensors.hh +++ b/src/systems/sensors/Sensors.hh @@ -20,8 +20,8 @@ #include #include -#include -#include +#include +#include #include namespace ignition @@ -35,7 +35,7 @@ namespace systems // Forward declarations. class SensorsPrivate; - /// \class Sensors Sensors.hh ignition/gazebo/systems/Sensors.hh + /// \class Sensors Sensors.hh gz/sim/systems/Sensors.hh /// \brief A system that manages sensors. /// /// ## System Parameters diff --git a/src/systems/shader_param/ShaderParam.cc b/src/systems/shader_param/ShaderParam.cc index eeabde451f2..592c2c6b45c 100644 --- a/src/systems/shader_param/ShaderParam.cc +++ b/src/systems/shader_param/ShaderParam.cc @@ -34,11 +34,11 @@ #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 7b6135dd79b..98c3fb2e6e3 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/Thermal.cc b/src/systems/thermal/Thermal.cc index 28bd118931e..e1c6769f947 100644 --- a/src/systems/thermal/Thermal.cc +++ b/src/systems/thermal/Thermal.cc @@ -24,13 +24,13 @@ #include #include -#include "ignition/gazebo/components/Atmosphere.hh" -#include "ignition/gazebo/components/SourceFilePath.hh" -#include "ignition/gazebo/components/Temperature.hh" -#include "ignition/gazebo/components/TemperatureRange.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/Atmosphere.hh" +#include "gz/sim/components/SourceFilePath.hh" +#include "gz/sim/components/Temperature.hh" +#include "gz/sim/components/TemperatureRange.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/thermal/Thermal.hh b/src/systems/thermal/Thermal.hh index 9210a06a0fe..0da1c2c32c5 100644 --- a/src/systems/thermal/Thermal.hh +++ b/src/systems/thermal/Thermal.hh @@ -18,8 +18,8 @@ #define IGNITION_GAZEBO_SYSTEMS_THERMAL_HH_ #include -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/thermal/ThermalSensor.cc b/src/systems/thermal/ThermalSensor.cc index 72e5f60a459..28d9e2e44b4 100644 --- a/src/systems/thermal/ThermalSensor.cc +++ b/src/systems/thermal/ThermalSensor.cc @@ -23,11 +23,11 @@ #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 c0a27306d35..dae7094bb37 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 ec4130f027b..5582265f981 100644 --- a/src/systems/thruster/Thruster.cc +++ b/src/systems/thruster/Thruster.cc @@ -26,16 +26,16 @@ #include -#include "ignition/gazebo/components/AngularVelocity.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/Pose.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/AngularVelocity.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/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 ac123080c28..45a3c30dd04 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/touch_plugin/TouchPlugin.cc b/src/systems/touch_plugin/TouchPlugin.cc index ccd177bb90f..eb707da8bc4 100644 --- a/src/systems/touch_plugin/TouchPlugin.cc +++ b/src/systems/touch_plugin/TouchPlugin.cc @@ -28,15 +28,15 @@ #include -#include "ignition/gazebo/components/ContactSensor.hh" -#include "ignition/gazebo/components/ContactSensorData.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Sensor.hh" - -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/ContactSensor.hh" +#include "gz/sim/components/ContactSensorData.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Sensor.hh" + +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/touch_plugin/TouchPlugin.hh b/src/systems/touch_plugin/TouchPlugin.hh index 251fc2e8bfa..978e67cdbae 100644 --- a/src/systems/touch_plugin/TouchPlugin.hh +++ b/src/systems/touch_plugin/TouchPlugin.hh @@ -19,7 +19,7 @@ #define IGNITION_GAZEBO_SYSTEMS_TOUCH_PLUGIN_HH_ #include -#include +#include namespace ignition { diff --git a/src/systems/track_controller/TrackController.cc b/src/systems/track_controller/TrackController.cc index 5e1d4b27301..6d436617a4d 100644 --- a/src/systems/track_controller/TrackController.cc +++ b/src/systems/track_controller/TrackController.cc @@ -33,12 +33,12 @@ #include #include -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/track_controller/TrackController.hh b/src/systems/track_controller/TrackController.hh index f9d54a32044..a6e00f8eaf5 100644 --- a/src/systems/track_controller/TrackController.hh +++ b/src/systems/track_controller/TrackController.hh @@ -18,8 +18,8 @@ #define IGNITION_GAZEBO_SYSTEMS_TRACKCONTROLLER_HH_ #include -#include -#include "ignition/gazebo/physics/Events.hh" +#include +#include "gz/sim/physics/Events.hh" namespace ignition { diff --git a/src/systems/tracked_vehicle/TrackedVehicle.cc b/src/systems/tracked_vehicle/TrackedVehicle.cc index e175d44329c..b75c219c68c 100644 --- a/src/systems/tracked_vehicle/TrackedVehicle.cc +++ b/src/systems/tracked_vehicle/TrackedVehicle.cc @@ -34,11 +34,11 @@ #include #include -#include "ignition/gazebo/components/CanonicalLink.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/CanonicalLink.hh" +#include "gz/sim/components/JointPosition.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/tracked_vehicle/TrackedVehicle.hh b/src/systems/tracked_vehicle/TrackedVehicle.hh index 878c5defc9d..d0313a08b61 100644 --- a/src/systems/tracked_vehicle/TrackedVehicle.hh +++ b/src/systems/tracked_vehicle/TrackedVehicle.hh @@ -19,7 +19,7 @@ #include -#include +#include namespace ignition { diff --git a/src/systems/trajectory_follower/TrajectoryFollower.cc b/src/systems/trajectory_follower/TrajectoryFollower.cc index 3b1ea70dda4..5f8b6117616 100644 --- a/src/systems/trajectory_follower/TrajectoryFollower.cc +++ b/src/systems/trajectory_follower/TrajectoryFollower.cc @@ -32,11 +32,11 @@ #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 57fbfcaae92..9d8adf77a0a 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/src/systems/triggered_publisher/TriggeredPublisher.hh b/src/systems/triggered_publisher/TriggeredPublisher.hh index f524b119abb..fe9f711c94b 100644 --- a/src/systems/triggered_publisher/TriggeredPublisher.hh +++ b/src/systems/triggered_publisher/TriggeredPublisher.hh @@ -22,7 +22,7 @@ #include #include -#include "ignition/gazebo/System.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index df8dd1dfb95..a6dc661bdb2 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -45,31 +45,31 @@ #include "ignition/common/Profiler.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/LightCmd.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/Pose.hh" -#include "ignition/gazebo/components/PoseCmd.hh" -#include "ignition/gazebo/components/PhysicsCmd.hh" -#include "ignition/gazebo/components/SphericalCoordinates.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Conversions.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/SdfEntityCreator.hh" -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/World.hh" -#include "ignition/gazebo/components/ContactSensorData.hh" -#include "ignition/gazebo/components/ContactSensor.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/VisualCmd.hh" -#include "ignition/gazebo/components/WheelSlipCmd.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/LightCmd.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/Pose.hh" +#include "gz/sim/components/PoseCmd.hh" +#include "gz/sim/components/PhysicsCmd.hh" +#include "gz/sim/components/SphericalCoordinates.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Conversions.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/SdfEntityCreator.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/World.hh" +#include "gz/sim/components/ContactSensorData.hh" +#include "gz/sim/components/ContactSensor.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/VisualCmd.hh" +#include "gz/sim/components/WheelSlipCmd.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/user_commands/UserCommands.hh b/src/systems/user_commands/UserCommands.hh index ea162bd0781..b4c458219bf 100644 --- a/src/systems/user_commands/UserCommands.hh +++ b/src/systems/user_commands/UserCommands.hh @@ -18,8 +18,8 @@ #define IGNITION_GAZEBO_SYSTEMS_USERCOMMANDS_HH_ #include -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/velocity_control/VelocityControl.cc b/src/systems/velocity_control/VelocityControl.cc index 8082c397162..c72554a034b 100644 --- a/src/systems/velocity_control/VelocityControl.cc +++ b/src/systems/velocity_control/VelocityControl.cc @@ -26,10 +26,10 @@ #include #include -#include "ignition/gazebo/components/AngularVelocityCmd.hh" -#include "ignition/gazebo/components/LinearVelocityCmd.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/AngularVelocityCmd.hh" +#include "gz/sim/components/LinearVelocityCmd.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" #include "VelocityControl.hh" diff --git a/src/systems/velocity_control/VelocityControl.hh b/src/systems/velocity_control/VelocityControl.hh index 08ac7cd569c..ffa6b3622a3 100644 --- a/src/systems/velocity_control/VelocityControl.hh +++ b/src/systems/velocity_control/VelocityControl.hh @@ -20,7 +20,7 @@ #include #include -#include +#include namespace ignition { diff --git a/src/systems/wheel_slip/WheelSlip.cc b/src/systems/wheel_slip/WheelSlip.cc index 78385295de4..8a2680b4be2 100644 --- a/src/systems/wheel_slip/WheelSlip.cc +++ b/src/systems/wheel_slip/WheelSlip.cc @@ -25,15 +25,15 @@ #include #include -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointVelocity.hh" -#include "ignition/gazebo/components/SlipComplianceCmd.hh" -#include "ignition/gazebo/components/WheelSlipCmd.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointVelocity.hh" +#include "gz/sim/components/SlipComplianceCmd.hh" +#include "gz/sim/components/WheelSlipCmd.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/wheel_slip/WheelSlip.hh b/src/systems/wheel_slip/WheelSlip.hh index 0400da23dc3..ccd8ebf5a2b 100644 --- a/src/systems/wheel_slip/WheelSlip.hh +++ b/src/systems/wheel_slip/WheelSlip.hh @@ -18,7 +18,7 @@ #ifndef IGNITION_GAZEBO_SYSTEMS_WHEELSLIP_HH_ #define IGNITION_GAZEBO_SYSTEMS_WHEELSLIP_HH_ -#include +#include #include namespace ignition diff --git a/src/systems/wind_effects/WindEffects.cc b/src/systems/wind_effects/WindEffects.cc index 931ca629ecc..0cdd941f5e8 100644 --- a/src/systems/wind_effects/WindEffects.cc +++ b/src/systems/wind_effects/WindEffects.cc @@ -40,21 +40,21 @@ #include #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/SdfEntityCreator.hh" - -#include "ignition/gazebo/components/Inertial.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/LinearVelocitySeed.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Wind.hh" -#include "ignition/gazebo/components/WindMode.hh" - -#include "ignition/gazebo/Link.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/SdfEntityCreator.hh" + +#include "gz/sim/components/Inertial.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/LinearVelocitySeed.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Wind.hh" +#include "gz/sim/components/WindMode.hh" + +#include "gz/sim/Link.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/wind_effects/WindEffects.hh b/src/systems/wind_effects/WindEffects.hh index 1502895e1ef..09088af95a9 100644 --- a/src/systems/wind_effects/WindEffects.hh +++ b/src/systems/wind_effects/WindEffects.hh @@ -18,8 +18,8 @@ #define IGNITION_GAZEBO_SYSTEMS_WINDEFFECTS_HH_ #include -#include -#include +#include +#include namespace ignition { diff --git a/test/helpers/EnvTestFixture.hh b/test/helpers/EnvTestFixture.hh index e73636f6ac5..b7e77706634 100644 --- a/test/helpers/EnvTestFixture.hh +++ b/test/helpers/EnvTestFixture.hh @@ -22,7 +22,7 @@ #include #include #include -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" using namespace ignition; diff --git a/test/helpers/Relay.hh b/test/helpers/Relay.hh index f30323e4e65..504d07ed243 100644 --- a/test/helpers/Relay.hh +++ b/test/helpers/Relay.hh @@ -17,7 +17,7 @@ #ifndef IGNITION_GAZEBO_TEST_HELPERS_RELAY_HH_ #define IGNITION_GAZEBO_TEST_HELPERS_RELAY_HH_ -#include +#include #include "../plugins/MockSystem.hh" diff --git a/test/helpers/UniqueTestDirectoryEnv.hh b/test/helpers/UniqueTestDirectoryEnv.hh index c544ac3b8f3..e4ab5048ea6 100644 --- a/test/helpers/UniqueTestDirectoryEnv.hh +++ b/test/helpers/UniqueTestDirectoryEnv.hh @@ -21,7 +21,7 @@ #include #include -#include +#include namespace ignition { diff --git a/test/integration/ModelPhotoShootTest.hh b/test/integration/ModelPhotoShootTest.hh index 68e0923646d..af9bfb2a503 100644 --- a/test/integration/ModelPhotoShootTest.hh +++ b/test/integration/ModelPhotoShootTest.hh @@ -34,7 +34,7 @@ #include "ignition/gazebo/components/JointPosition.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "ignition/gazebo/TestFixture.hh" #include "ignition/gazebo/rendering/Events.hh" #include "ignition/gazebo/Model.hh" diff --git a/test/integration/ackermann_steering_system.cc b/test/integration/ackermann_steering_system.cc index 2358e50d81a..3d89cd10ca2 100644 --- a/test/integration/ackermann_steering_system.cc +++ b/test/integration/ackermann_steering_system.cc @@ -27,7 +27,7 @@ #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/air_pressure_system.cc b/test/integration/air_pressure_system.cc index 77e5a7431ed..53401d620b2 100644 --- a/test/integration/air_pressure_system.cc +++ b/test/integration/air_pressure_system.cc @@ -28,7 +28,7 @@ #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/Sensor.hh" #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/altimeter_system.cc b/test/integration/altimeter_system.cc index 611b733a1bf..48144b0b0cc 100644 --- a/test/integration/altimeter_system.cc +++ b/test/integration/altimeter_system.cc @@ -34,7 +34,7 @@ #include "ignition/gazebo/components/Sensor.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/apply_joint_force_system.cc b/test/integration/apply_joint_force_system.cc index 0c3a43169f9..0a74a1a8172 100644 --- a/test/integration/apply_joint_force_system.cc +++ b/test/integration/apply_joint_force_system.cc @@ -30,7 +30,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/battery_plugin.cc b/test/integration/battery_plugin.cc index 2b58f219a11..fc7a994cb97 100644 --- a/test/integration/battery_plugin.cc +++ b/test/integration/battery_plugin.cc @@ -33,7 +33,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/ServerConfig.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "ignition/gazebo/Entity.hh" #include "ignition/gazebo/components/BatterySoC.hh" #include "ignition/gazebo/components/Link.hh" diff --git a/test/integration/breadcrumbs.cc b/test/integration/breadcrumbs.cc index b78149dd4ab..e674bbdc999 100644 --- a/test/integration/breadcrumbs.cc +++ b/test/integration/breadcrumbs.cc @@ -37,7 +37,7 @@ #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 "gz/sim/test_config.hh" #include "helpers/Relay.hh" #include "helpers/UniqueTestDirectoryEnv.hh" diff --git a/test/integration/buoyancy.cc b/test/integration/buoyancy.cc index ac8acb358dc..8b5a0d9abf6 100644 --- a/test/integration/buoyancy.cc +++ b/test/integration/buoyancy.cc @@ -33,7 +33,7 @@ #include "ignition/gazebo/components/Model.hh" #include "ignition/gazebo/components/Volume.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/buoyancy_engine.cc b/test/integration/buoyancy_engine.cc index 31cae77cbf0..d8c9c6b5c27 100644 --- a/test/integration/buoyancy_engine.cc +++ b/test/integration/buoyancy_engine.cc @@ -29,7 +29,7 @@ #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/camera_sensor_background.cc b/test/integration/camera_sensor_background.cc index ace16d4dbda..55e8b70df88 100644 --- a/test/integration/camera_sensor_background.cc +++ b/test/integration/camera_sensor_background.cc @@ -24,7 +24,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/camera_video_record_system.cc b/test/integration/camera_video_record_system.cc index 76dad450d81..c820d739671 100644 --- a/test/integration/camera_video_record_system.cc +++ b/test/integration/camera_video_record_system.cc @@ -23,7 +23,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/collada_world_exporter.cc b/test/integration/collada_world_exporter.cc index 8b791287445..4c19aeaba40 100644 --- a/test/integration/collada_world_exporter.cc +++ b/test/integration/collada_world_exporter.cc @@ -25,7 +25,7 @@ #include #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "helpers/UniqueTestDirectoryEnv.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/components.cc b/test/integration/components.cc index 93a507e83e7..a8dc090f33d 100644 --- a/test/integration/components.cc +++ b/test/integration/components.cc @@ -85,7 +85,7 @@ #include "ignition/gazebo/components/ThreadPitch.hh" #include "ignition/gazebo/components/Visual.hh" #include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/test/integration/contact_system.cc b/test/integration/contact_system.cc index 63ec59d0b97..ef8693b74fe 100644 --- a/test/integration/contact_system.cc +++ b/test/integration/contact_system.cc @@ -28,7 +28,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/depth_camera.cc b/test/integration/depth_camera.cc index 552f3f12952..789b1534216 100644 --- a/test/integration/depth_camera.cc +++ b/test/integration/depth_camera.cc @@ -26,7 +26,7 @@ #include #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/detachable_joint.cc b/test/integration/detachable_joint.cc index 4ea68e9bde5..0096f7d3e2c 100644 --- a/test/integration/detachable_joint.cc +++ b/test/integration/detachable_joint.cc @@ -25,7 +25,7 @@ #include "ignition/gazebo/Link.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "ignition/gazebo/components/LinearAcceleration.hh" #include "ignition/gazebo/components/LinearVelocity.hh" diff --git a/test/integration/diff_drive_system.cc b/test/integration/diff_drive_system.cc index acda11da518..a51f774b808 100644 --- a/test/integration/diff_drive_system.cc +++ b/test/integration/diff_drive_system.cc @@ -27,7 +27,7 @@ #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/distortion_camera.cc b/test/integration/distortion_camera.cc index 4633c877e84..b1dc5987a9a 100644 --- a/test/integration/distortion_camera.cc +++ b/test/integration/distortion_camera.cc @@ -26,7 +26,7 @@ #endif #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include #include #include diff --git a/test/integration/each_new_removed.cc b/test/integration/each_new_removed.cc index 1821f576a4f..9b2700dbaac 100644 --- a/test/integration/each_new_removed.cc +++ b/test/integration/each_new_removed.cc @@ -28,7 +28,7 @@ #include "ignition/gazebo/components/Factory.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/elevator_system.cc b/test/integration/elevator_system.cc index ab5aa803046..9d766f46dbd 100644 --- a/test/integration/elevator_system.cc +++ b/test/integration/elevator_system.cc @@ -28,7 +28,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" using namespace ignition; using namespace gazebo; diff --git a/test/integration/entity_erase.cc b/test/integration/entity_erase.cc index 08b8cc273f5..4024859157c 100644 --- a/test/integration/entity_erase.cc +++ b/test/integration/entity_erase.cc @@ -22,7 +22,7 @@ #include #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/test/integration/events.cc b/test/integration/events.cc index 596790afa73..35154f92933 100644 --- a/test/integration/events.cc +++ b/test/integration/events.cc @@ -22,7 +22,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "plugins/EventTriggerSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/examples_build.cc b/test/integration/examples_build.cc index 2319d8a905b..0122dca524a 100644 --- a/test/integration/examples_build.cc +++ b/test/integration/examples_build.cc @@ -24,7 +24,7 @@ #include #include -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" // File copied from diff --git a/test/integration/follow_actor_system.cc b/test/integration/follow_actor_system.cc index 24f0273fa64..14d3bdbd20e 100644 --- a/test/integration/follow_actor_system.cc +++ b/test/integration/follow_actor_system.cc @@ -26,7 +26,7 @@ #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.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 cdac9e273ce..922e9696b2b 100644 --- a/test/integration/force_torque_system.cc +++ b/test/integration/force_torque_system.cc @@ -28,7 +28,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "helpers/Relay.hh" #include "helpers/EnvTestFixture.hh" diff --git a/test/integration/gpu_lidar.cc b/test/integration/gpu_lidar.cc index 350f7ca5212..f3391c26dff 100644 --- a/test/integration/gpu_lidar.cc +++ b/test/integration/gpu_lidar.cc @@ -25,7 +25,7 @@ #include #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/halt_motion.cc b/test/integration/halt_motion.cc index f7a2baf6b26..4455400a011 100644 --- a/test/integration/halt_motion.cc +++ b/test/integration/halt_motion.cc @@ -28,7 +28,7 @@ #include "ignition/gazebo/components/HaltMotion.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/imu_system.cc b/test/integration/imu_system.cc index 6094bf76bba..af26d070013 100644 --- a/test/integration/imu_system.cc +++ b/test/integration/imu_system.cc @@ -35,7 +35,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/joint_controller_system.cc b/test/integration/joint_controller_system.cc index 6bf785a1dac..61d9706a079 100644 --- a/test/integration/joint_controller_system.cc +++ b/test/integration/joint_controller_system.cc @@ -30,7 +30,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/joint_position_controller_system.cc b/test/integration/joint_position_controller_system.cc index 1a17a958e31..ac87f261e2f 100644 --- a/test/integration/joint_position_controller_system.cc +++ b/test/integration/joint_position_controller_system.cc @@ -30,7 +30,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/joint_state_publisher_system.cc b/test/integration/joint_state_publisher_system.cc index 1c560f8172e..659ff20b29f 100644 --- a/test/integration/joint_state_publisher_system.cc +++ b/test/integration/joint_state_publisher_system.cc @@ -22,7 +22,7 @@ #include #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/test/integration/joint_trajectory_controller_system.cc b/test/integration/joint_trajectory_controller_system.cc index 670727f7460..908df86a553 100644 --- a/test/integration/joint_trajectory_controller_system.cc +++ b/test/integration/joint_trajectory_controller_system.cc @@ -34,7 +34,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/kinetic_energy_monitor_system.cc b/test/integration/kinetic_energy_monitor_system.cc index e884362afc0..42f34c92c17 100644 --- a/test/integration/kinetic_energy_monitor_system.cc +++ b/test/integration/kinetic_energy_monitor_system.cc @@ -28,7 +28,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/test/integration/level_manager.cc b/test/integration/level_manager.cc index 4b845442ac1..81c2e66a577 100644 --- a/test/integration/level_manager.cc +++ b/test/integration/level_manager.cc @@ -34,7 +34,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "ignition/gazebo/components/Level.hh" #include "ignition/gazebo/components/LevelBuffer.hh" diff --git a/test/integration/level_manager_runtime_performers.cc b/test/integration/level_manager_runtime_performers.cc index 4f82aca4acb..9f0f00758df 100644 --- a/test/integration/level_manager_runtime_performers.cc +++ b/test/integration/level_manager_runtime_performers.cc @@ -30,7 +30,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "ignition/gazebo/components/Level.hh" #include "ignition/gazebo/components/LevelBuffer.hh" diff --git a/test/integration/lift_drag_system.cc b/test/integration/lift_drag_system.cc index f7d620f3bd3..4a81f0008ed 100644 --- a/test/integration/lift_drag_system.cc +++ b/test/integration/lift_drag_system.cc @@ -39,7 +39,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" #include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/log_system.cc b/test/integration/log_system.cc index 26b75d0fdda..f1475932dd6 100644 --- a/test/integration/log_system.cc +++ b/test/integration/log_system.cc @@ -49,7 +49,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/ServerConfig.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/logical_audio_sensor_plugin.cc b/test/integration/logical_audio_sensor_plugin.cc index ca216e2f09c..93a1a556a2a 100644 --- a/test/integration/logical_audio_sensor_plugin.cc +++ b/test/integration/logical_audio_sensor_plugin.cc @@ -32,7 +32,7 @@ #include "ignition/gazebo/components/LogicalAudio.hh" #include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "ignition/gazebo/Entity.hh" #include "ignition/gazebo/EntityComponentManager.hh" #include "ignition/gazebo/Server.hh" diff --git a/test/integration/logical_camera_system.cc b/test/integration/logical_camera_system.cc index 994d9b11a2f..e08def62f16 100644 --- a/test/integration/logical_camera_system.cc +++ b/test/integration/logical_camera_system.cc @@ -31,7 +31,7 @@ #include "ignition/gazebo/components/Sensor.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/magnetometer_system.cc b/test/integration/magnetometer_system.cc index b8c9d90610f..a49979e2eff 100644 --- a/test/integration/magnetometer_system.cc +++ b/test/integration/magnetometer_system.cc @@ -33,7 +33,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/multicopter.cc b/test/integration/multicopter.cc index 06f0f5d7968..f0b2710ac00 100644 --- a/test/integration/multicopter.cc +++ b/test/integration/multicopter.cc @@ -38,7 +38,7 @@ #include "ignition/gazebo/Model.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/navsat_system.cc b/test/integration/navsat_system.cc index aade7f115f6..f52572b3f51 100644 --- a/test/integration/navsat_system.cc +++ b/test/integration/navsat_system.cc @@ -34,7 +34,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" #include "ignition/gazebo/TestFixture.hh" -#include "ignition/gazebo/test_config.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 96631ab320f..bc3e4ec14fb 100644 --- a/test/integration/nested_model_physics.cc +++ b/test/integration/nested_model_physics.cc @@ -28,7 +28,7 @@ #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/network_handshake.cc b/test/integration/network_handshake.cc index af2fdf7bc51..9e0a58ff516 100644 --- a/test/integration/network_handshake.cc +++ b/test/integration/network_handshake.cc @@ -25,7 +25,7 @@ #include "ignition/msgs/world_stats.pb.h" #include "ignition/transport/Node.hh" #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/odometry_publisher.cc b/test/integration/odometry_publisher.cc index fa158d5a610..72cff4ed368 100644 --- a/test/integration/odometry_publisher.cc +++ b/test/integration/odometry_publisher.cc @@ -31,7 +31,7 @@ #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.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 6ad0de66045..f0f525e106b 100644 --- a/test/integration/optical_tactile_plugin.cc +++ b/test/integration/optical_tactile_plugin.cc @@ -29,7 +29,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.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 c42b001aa43..6f8620bb4cb 100644 --- a/test/integration/particle_emitter.cc +++ b/test/integration/particle_emitter.cc @@ -30,7 +30,7 @@ #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 "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 36a107b8cf9..ded22d90990 100644 --- a/test/integration/perfect_comms.cc +++ b/test/integration/perfect_comms.cc @@ -25,7 +25,7 @@ #include #include #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/test/integration/performer_detector.cc b/test/integration/performer_detector.cc index 34e7484d713..22f88379d60 100644 --- a/test/integration/performer_detector.cc +++ b/test/integration/performer_detector.cc @@ -27,7 +27,7 @@ #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/components/PoseCmd.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "helpers/Relay.hh" #include "helpers/EnvTestFixture.hh" diff --git a/test/integration/physics_system.cc b/test/integration/physics_system.cc index 380cd0c174f..def47abffd7 100644 --- a/test/integration/physics_system.cc +++ b/test/integration/physics_system.cc @@ -41,7 +41,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" #include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "ignition/gazebo/components/AxisAlignedBox.hh" #include "ignition/gazebo/components/CanonicalLink.hh" diff --git a/test/integration/play_pause.cc b/test/integration/play_pause.cc index 92a9e6d3989..1495f763fae 100644 --- a/test/integration/play_pause.cc +++ b/test/integration/play_pause.cc @@ -22,7 +22,7 @@ #include "ignition/msgs.hh" #include "ignition/transport.hh" #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/pose_publisher_system.cc b/test/integration/pose_publisher_system.cc index 0350efd1b7c..519b4064a56 100644 --- a/test/integration/pose_publisher_system.cc +++ b/test/integration/pose_publisher_system.cc @@ -31,7 +31,7 @@ #include "ignition/gazebo/Model.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/recreate_entities.cc b/test/integration/recreate_entities.cc index 8c18ba76c3d..2ffec7a5470 100644 --- a/test/integration/recreate_entities.cc +++ b/test/integration/recreate_entities.cc @@ -37,7 +37,7 @@ #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/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 aba7b050926..526119f101b 100644 --- a/test/integration/rf_comms.cc +++ b/test/integration/rf_comms.cc @@ -26,7 +26,7 @@ #include #include "ignition/gazebo/Model.hh" #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/test/integration/rgbd_camera.cc b/test/integration/rgbd_camera.cc index 343b576da21..2267580b835 100644 --- a/test/integration/rgbd_camera.cc +++ b/test/integration/rgbd_camera.cc @@ -26,7 +26,7 @@ #include #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/save_world.cc b/test/integration/save_world.cc index 82d67f650f3..bd03d4180ba 100644 --- a/test/integration/save_world.cc +++ b/test/integration/save_world.cc @@ -47,7 +47,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "helpers/UniqueTestDirectoryEnv.hh" #include "plugins/MockSystem.hh" diff --git a/test/integration/scene_broadcaster_system.cc b/test/integration/scene_broadcaster_system.cc index 8fe13b08482..3e966bb457c 100644 --- a/test/integration/scene_broadcaster_system.cc +++ b/test/integration/scene_broadcaster_system.cc @@ -29,7 +29,7 @@ #include #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/sdf_frame_semantics.cc b/test/integration/sdf_frame_semantics.cc index 1685ac33593..ee0bb9565f5 100644 --- a/test/integration/sdf_frame_semantics.cc +++ b/test/integration/sdf_frame_semantics.cc @@ -32,7 +32,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" #include "ignition/gazebo/Types.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "ignition/gazebo/components/Collision.hh" #include "ignition/gazebo/components/Link.hh" diff --git a/test/integration/sdf_include.cc b/test/integration/sdf_include.cc index d6dc6e7c714..99c0c955885 100644 --- a/test/integration/sdf_include.cc +++ b/test/integration/sdf_include.cc @@ -21,7 +21,7 @@ #include #include #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/sensors_system.cc b/test/integration/sensors_system.cc index 8c0387ea0f1..d618912e56f 100644 --- a/test/integration/sensors_system.cc +++ b/test/integration/sensors_system.cc @@ -39,7 +39,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" #include "ignition/gazebo/Types.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "ignition/gazebo/components/Model.hh" #include "ignition/gazebo/components/Name.hh" diff --git a/test/integration/sensors_system_battery.cc b/test/integration/sensors_system_battery.cc index ba78ed2c6df..5920d4e7cdd 100644 --- a/test/integration/sensors_system_battery.cc +++ b/test/integration/sensors_system_battery.cc @@ -28,7 +28,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" #include "ignition/gazebo/Types.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "ignition/gazebo/components/BatterySoC.hh" #include "ignition/gazebo/components/Name.hh" diff --git a/test/integration/shader_param_system.cc b/test/integration/shader_param_system.cc index 79683703f4c..1d250d96073 100644 --- a/test/integration/shader_param_system.cc +++ b/test/integration/shader_param_system.cc @@ -25,7 +25,7 @@ #include #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.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 1f8548fef2c..6ab2e789882 100644 --- a/test/integration/spherical_coordinates.cc +++ b/test/integration/spherical_coordinates.cc @@ -30,7 +30,7 @@ #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 "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 4d159c770ba..db241556948 100644 --- a/test/integration/thermal_sensor_system.cc +++ b/test/integration/thermal_sensor_system.cc @@ -33,7 +33,7 @@ #include "ignition/gazebo/components/Visual.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/thermal_system.cc b/test/integration/thermal_system.cc index ccdc66c284c..74af01642ae 100644 --- a/test/integration/thermal_system.cc +++ b/test/integration/thermal_system.cc @@ -35,7 +35,7 @@ #include "ignition/gazebo/components/Visual.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/thruster.cc b/test/integration/thruster.cc index 2ae8148b6d1..f96fd0d9de6 100644 --- a/test/integration/thruster.cc +++ b/test/integration/thruster.cc @@ -32,7 +32,7 @@ #include "ignition/gazebo/Util.hh" #include "ignition/gazebo/World.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/test/integration/touch_plugin.cc b/test/integration/touch_plugin.cc index 539671128c8..17a8b71d89e 100644 --- a/test/integration/touch_plugin.cc +++ b/test/integration/touch_plugin.cc @@ -22,7 +22,7 @@ #include #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/tracked_vehicle_system.cc b/test/integration/tracked_vehicle_system.cc index 39b8cc88d13..d528842927d 100644 --- a/test/integration/tracked_vehicle_system.cc +++ b/test/integration/tracked_vehicle_system.cc @@ -36,7 +36,7 @@ #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/triggered_publisher.cc b/test/integration/triggered_publisher.cc index a4a8017d034..89ff41977ac 100644 --- a/test/integration/triggered_publisher.cc +++ b/test/integration/triggered_publisher.cc @@ -34,7 +34,7 @@ #include "ignition/gazebo/components/Model.hh" #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index 9414bac429c..b1b326b2e26 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -38,7 +38,7 @@ #include "ignition/gazebo/Model.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/velocity_control_system.cc b/test/integration/velocity_control_system.cc index 4b1cd4d2901..afe82d82f25 100644 --- a/test/integration/velocity_control_system.cc +++ b/test/integration/velocity_control_system.cc @@ -28,7 +28,7 @@ #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/wheel_slip.cc b/test/integration/wheel_slip.cc index 2e2e51a24c2..850d4720049 100644 --- a/test/integration/wheel_slip.cc +++ b/test/integration/wheel_slip.cc @@ -46,7 +46,7 @@ #include "ignition/gazebo/components/World.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/wide_angle_camera.cc b/test/integration/wide_angle_camera.cc index f4d4d1d1b9a..644d93b3f5a 100644 --- a/test/integration/wide_angle_camera.cc +++ b/test/integration/wide_angle_camera.cc @@ -26,7 +26,7 @@ #include #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/wind_effects.cc b/test/integration/wind_effects.cc index 319f6038ada..b47b0502aad 100644 --- a/test/integration/wind_effects.cc +++ b/test/integration/wind_effects.cc @@ -25,7 +25,7 @@ #include "ignition/gazebo/Link.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "ignition/gazebo/components/LinearAcceleration.hh" #include "ignition/gazebo/components/LinearVelocity.hh" diff --git a/test/integration/world_control_state.cc b/test/integration/world_control_state.cc index 4c2d1295ec4..8d1a352ce02 100644 --- a/test/integration/world_control_state.cc +++ b/test/integration/world_control_state.cc @@ -25,7 +25,7 @@ #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/performance/level_manager.cc b/test/performance/level_manager.cc index 64b2116d950..128043e8353 100644 --- a/test/performance/level_manager.cc +++ b/test/performance/level_manager.cc @@ -26,7 +26,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/test_config.hh" // NOLINT(build/include) using namespace ignition; using namespace gazebo; diff --git a/test/performance/sdf_runner.cc b/test/performance/sdf_runner.cc index b2fdfe1818c..b7bb999d18d 100644 --- a/test/performance/sdf_runner.cc +++ b/test/performance/sdf_runner.cc @@ -25,7 +25,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/test_config.hh" // NOLINT(build/include) using namespace ignition; using namespace gazebo;