From 2673c015f444de2f591666eef0cdc7ff3eee9562 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Thu, 13 Apr 2023 20:32:09 +0000 Subject: [PATCH 01/31] ign -> gz Migrate Ignition Headers : gz-sim (#1646) * Migrate headers Signed-off-by: methylDragon * Add redirection headers Signed-off-by: methylDragon * Migrate include statements Signed-off-by: methylDragon * Leave ignition as primary in headers to fix ABI Signed-off-by: methylDragon * Generate MOC files from gz headers Signed-off-by: Louise Poubel * Migrate msgs include usage Signed-off-by: methylDragon * Add plugin aliases Signed-off-by: methylDragon * Fix tests and code check Signed-off-by: Nate Koenig * Added fuel.gazebosim.org test dir Signed-off-by: Nate Koenig * Fix SdfGenerator_TEST Signed-off-by: Nate Koenig * require rendering 3.7 Signed-off-by: Nate Koenig * Fix namespaces Signed-off-by: Nate Koenig * Clarify messages Signed-off-by: Nate Koenig * More debugging Signed-off-by: Nate Koenig * Fix linter Signed-off-by: Nate Koenig * More testing Signed-off-by: Nate Koenig * More debug Signed-off-by: Nate Koenig * fix build Signed-off-by: Nate Koenig * More debug Signed-off-by: Nate Koenig * linter Signed-off-by: Nate Koenig * Fix build Signed-off-by: Nate Koenig * Fix build Signed-off-by: Nate Koenig * More debug Signed-off-by: Nate Koenig * More testing Signed-off-by: Nate Koenig * More tests Signed-off-by: Nate Koenig * Fix gui.config Signed-off-by: Nate Koenig * Remove debugging Signed-off-by: Nate Koenig --------- Signed-off-by: methylDragon Signed-off-by: Louise Poubel Signed-off-by: Nate Koenig Signed-off-by: Nate Koenig Co-authored-by: Louise Poubel Co-authored-by: Nate Koenig Co-authored-by: Nate Koenig --- CMakeLists.txt | 7 +- Changelog.md | 10 +- api.md.in | 8 +- .../custom_component/CustomComponentPlugin.cc | 4 +- .../custom_component/CustomComponentPlugin.hh | 22 +- .../gui_system_plugin/GuiSystemPlugin.cc | 26 +- .../gui_system_plugin/GuiSystemPlugin.hh | 14 +- examples/plugin/gui_system_plugin/README.md | 2 +- examples/plugin/hello_world/HelloWorld.cc | 10 +- examples/plugin/hello_world/HelloWorld.hh | 10 +- .../rendering_plugins/RenderingGuiPlugin.cc | 34 +- .../rendering_plugins/RenderingGuiPlugin.hh | 10 +- .../RenderingServerPlugin.cc | 36 +- .../RenderingServerPlugin.hh | 24 +- .../rendering_plugins/rendering_plugins.sdf | 4 +- examples/plugin/system_plugin/SampleSystem.cc | 8 +- examples/plugin/system_plugin/SampleSystem.hh | 30 +- .../plugin/system_plugin/SampleSystem2.cc | 16 +- examples/scripts/distributed/primary.sdf | 4 +- examples/scripts/distributed/secondary.sdf | 4 +- examples/scripts/distributed/standalone.sdf | 6 +- .../distributed_levels.sdf.erb | 6 +- .../scripts/distributed_levels/primary.sdf | 4 +- .../scripts/distributed_levels/secondary.sdf | 4 +- .../scripts/distributed_levels/standalone.sdf | 6 +- .../log_video_recorder/log_video_recorder.sdf | 6 +- .../standalone/custom_server/custom_server.cc | 10 +- examples/standalone/each_performance/each.cc | 14 +- .../standalone/external_ecm/external_ecm.cc | 26 +- examples/standalone/gtest_setup/command.sdf | 4 +- .../standalone/gtest_setup/command_TEST.cc | 54 +- examples/standalone/gtest_setup/gravity.sdf | 2 +- .../standalone/gtest_setup/gravity_TEST.cc | 36 +- examples/standalone/joy_to_twist/README.md | 4 +- .../standalone/joy_to_twist/joy_to_twist.cc | 44 +- examples/standalone/joystick/README.md | 2 +- examples/standalone/joystick/joystick.cc | 18 +- examples/standalone/keyboard/keyboard.cc | 34 +- examples/standalone/marker/marker.cc | 264 +++--- .../scene_requester/scene_requester.cc | 10 +- examples/worlds/3k_shapes.sdf | 6 +- examples/worlds/ackermann_steering.sdf | 8 +- examples/worlds/actor.sdf | 8 +- examples/worlds/actors_population.sdf.erb | 6 +- examples/worlds/apply_joint_force.sdf | 6 +- examples/worlds/apply_link_wrench.sdf | 6 +- examples/worlds/breadcrumbs.sdf | 12 +- examples/worlds/buoyancy.sdf | 18 +- examples/worlds/camera_sensor.sdf | 8 +- .../camera_video_record_dbl_pendulum.sdf | 10 +- examples/worlds/collada_world_exporter.sdf | 2 +- examples/worlds/contact_sensor.sdf | 8 +- examples/worlds/conveyor.sdf | 14 +- examples/worlds/debug_shapes.sdf | 6 +- examples/worlds/depth_camera_sensor.sdf | 6 +- examples/worlds/detachable_joint.sdf | 14 +- examples/worlds/diff_drive.sdf | 10 +- examples/worlds/diff_drive_skid.sdf | 8 +- examples/worlds/elevator.sdf | 6 +- examples/worlds/empty.sdf | 8 +- examples/worlds/fuel.sdf | 6 +- examples/worlds/fuel_textured_mesh.sdf | 8 +- .../worlds/gpu_lidar_retro_values_sensor.sdf | 6 +- examples/worlds/gpu_lidar_sensor.sdf | 6 +- examples/worlds/grid.sdf | 8 +- examples/worlds/import_mesh.sdf | 6 +- examples/worlds/joint_controller.sdf | 8 +- examples/worlds/joint_position_controller.sdf | 6 +- examples/worlds/kinetic_energy_monitor.sdf | 8 +- examples/worlds/levels.sdf | 12 +- examples/worlds/levels_no_performers.sdf | 12 +- examples/worlds/lift_drag.sdf | 14 +- examples/worlds/lift_drag_battery.sdf | 16 +- examples/worlds/lights.sdf | 6 +- examples/worlds/linear_battery_demo.sdf | 12 +- examples/worlds/log_playback.sdf | 4 +- examples/worlds/log_record_dbl_pendulum.sdf | 8 +- examples/worlds/log_record_keyboard.sdf | 10 +- examples/worlds/log_record_resources.sdf | 6 +- examples/worlds/log_record_shapes.sdf | 8 +- .../worlds/logical_audio_sensor_plugin.sdf | 14 +- examples/worlds/logical_camera_sensor.sdf | 8 +- .../worlds/multicopter_velocity_control.sdf | 32 +- examples/worlds/nested_model.sdf | 6 +- examples/worlds/pendulum_links.sdf | 8 +- examples/worlds/performer_detector.sdf | 14 +- examples/worlds/plane_propeller_demo.sdf | 22 +- examples/worlds/pose_publisher.sdf | 8 +- examples/worlds/quadcopter.sdf | 16 +- examples/worlds/rolling_shapes.sdf | 6 +- examples/worlds/sensors.sdf | 14 +- examples/worlds/sensors_demo.sdf | 6 +- examples/worlds/shapes_bitmask.sdf | 6 +- examples/worlds/shapes_population.sdf.erb | 6 +- examples/worlds/thermal_camera.sdf | 14 +- examples/worlds/touch_plugin.sdf | 8 +- examples/worlds/track_drive.sdf | 12 +- examples/worlds/tracked_vehicle_simple.sdf | 38 +- examples/worlds/triggered_publisher.sdf | 24 +- .../worlds/trisphere_cycle_wheel_slip.sdf | 10 +- examples/worlds/tunnel.sdf | 8 +- examples/worlds/velocity_control.sdf | 10 +- examples/worlds/video_record_dbl_pendulum.sdf | 6 +- examples/worlds/wind.sdf | 8 +- examples/worlds/world_joint.sdf | 6 +- include/CMakeLists.txt | 3 +- include/gz/CMakeLists.txt | 1 + .../gazebo => gz/sim}/CMakeLists.txt | 0 include/gz/sim/Conversions.hh | 665 +++++++++++++++ include/gz/sim/Entity.hh | 66 ++ include/gz/sim/EntityComponentManager.hh | 778 ++++++++++++++++++ include/gz/sim/EventManager.hh | 148 ++++ include/gz/sim/Events.hh | 66 ++ include/gz/sim/Link.hh | 282 +++++++ include/gz/sim/Model.hh | 184 +++++ include/gz/sim/SdfEntityCreator.hh | 176 ++++ include/gz/sim/Server.hh | 295 +++++++ include/gz/sim/ServerConfig.hh | 436 ++++++++++ include/gz/sim/System.hh | 126 +++ include/gz/sim/SystemLoader.hh | 81 ++ include/gz/sim/SystemPluginPtr.hh | 37 + include/gz/sim/TestFixture.hh | 113 +++ include/gz/sim/Types.hh | 105 +++ include/gz/sim/Util.hh | 258 ++++++ include/gz/sim/World.hh | 189 +++++ include/gz/sim/components/Actor.hh | 55 ++ include/gz/sim/components/Actuators.hh | 46 ++ .../gz/sim/components/AirPressureSensor.hh | 46 ++ include/gz/sim/components/Altimeter.hh | 45 + .../gz/sim/components/AngularAcceleration.hh | 54 ++ include/gz/sim/components/AngularVelocity.hh | 53 ++ .../gz/sim/components/AngularVelocityCmd.hh | 53 ++ include/gz/sim/components/Atmosphere.hh | 52 ++ include/gz/sim/components/AxisAlignedBox.hh | 55 ++ include/gz/sim/components/BatterySoC.hh | 41 + .../sim}/components/CMakeLists.txt | 2 +- include/gz/sim/components/Camera.hh | 45 + include/gz/sim/components/CanonicalLink.hh | 41 + include/gz/sim/components/CastShadows.hh | 42 + include/gz/sim/components/CenterOfVolume.hh | 45 + include/gz/sim/components/ChildLinkName.hh | 43 + include/gz/sim/components/Collision.hh | 68 ++ include/gz/sim/components/Component.hh | 542 ++++++++++++ include/gz/sim/components/ContactSensor.hh | 43 + .../gz/sim/components/ContactSensorData.hh | 46 ++ include/gz/sim/components/DepthCamera.hh | 45 + include/gz/sim/components/DetachableJoint.hh | 105 +++ .../sim/components/ExternalWorldWrenchCmd.hh | 52 ++ include/gz/sim/components/Factory.hh | 352 ++++++++ include/gz/sim/components/Geometry.hh | 55 ++ include/gz/sim/components/GpuLidar.hh | 43 + include/gz/sim/components/Gravity.hh | 43 + include/gz/sim/components/Imu.hh | 46 ++ include/gz/sim/components/Inertial.hh | 51 ++ include/gz/sim/components/Joint.hh | 40 + include/gz/sim/components/JointAxis.hh | 58 ++ .../gz/sim/components/JointEffortLimitsCmd.hh | 60 ++ include/gz/sim/components/JointForce.hh | 46 ++ include/gz/sim/components/JointForceCmd.hh | 46 ++ include/gz/sim/components/JointPosition.hh | 47 ++ .../sim/components/JointPositionLimitsCmd.hh | 58 ++ .../gz/sim/components/JointPositionReset.hh | 49 ++ include/gz/sim/components/JointType.hh | 74 ++ include/gz/sim/components/JointVelocity.hh | 46 ++ include/gz/sim/components/JointVelocityCmd.hh | 48 ++ .../sim/components/JointVelocityLimitsCmd.hh | 58 ++ .../gz/sim/components/JointVelocityReset.hh | 50 ++ include/gz/sim/components/LaserRetro.hh | 41 + include/gz/sim/components/Level.hh | 46 ++ include/gz/sim/components/LevelBuffer.hh | 43 + include/gz/sim/components/LevelEntityNames.hh | 89 ++ include/gz/sim/components/Lidar.hh | 43 + include/gz/sim/components/Light.hh | 55 ++ .../gz/sim/components/LinearAcceleration.hh | 53 ++ include/gz/sim/components/LinearVelocity.hh | 50 ++ .../gz/sim/components/LinearVelocityCmd.hh | 55 ++ .../gz/sim/components/LinearVelocitySeed.hh | 55 ++ include/gz/sim/components/Link.hh | 40 + .../sim/components/LogPlaybackStatistics.hh | 48 ++ include/gz/sim/components/LogicalAudio.hh | 325 ++++++++ include/gz/sim/components/LogicalCamera.hh | 43 + include/gz/sim/components/MagneticField.hh | 44 + include/gz/sim/components/Magnetometer.hh | 48 ++ include/gz/sim/components/Material.hh | 51 ++ include/gz/sim/components/Model.hh | 46 ++ include/gz/sim/components/Name.hh | 42 + include/gz/sim/components/ParentEntity.hh | 49 ++ include/gz/sim/components/ParentLinkName.hh | 42 + include/gz/sim/components/Performer.hh | 41 + .../gz/sim/components/PerformerAffinity.hh | 47 ++ include/gz/sim/components/PerformerLevels.hh | 85 ++ include/gz/sim/components/Physics.hh | 56 ++ include/gz/sim/components/PhysicsCmd.hh | 46 ++ .../gz/sim/components/PhysicsEnginePlugin.hh | 43 + include/gz/sim/components/Pose.hh | 48 ++ include/gz/sim/components/PoseCmd.hh | 45 + .../sim/components/RenderEngineGuiPlugin.hh | 44 + .../components/RenderEngineServerPlugin.hh | 45 + include/gz/sim/components/RgbdCamera.hh | 44 + include/gz/sim/components/Scene.hh | 53 ++ include/gz/sim/components/SelfCollide.hh | 42 + include/gz/sim/components/Sensor.hh | 51 ++ include/gz/sim/components/Serialization.hh | 225 +++++ .../gz/sim/components/SlipComplianceCmd.hh | 49 ++ include/gz/sim/components/SourceFilePath.hh | 45 + include/gz/sim/components/Static.hh | 41 + include/gz/sim/components/Temperature.hh | 43 + include/gz/sim/components/ThermalCamera.hh | 45 + include/gz/sim/components/ThreadPitch.hh | 41 + include/gz/sim/components/Transparency.hh | 43 + include/gz/sim/components/Visual.hh | 40 + include/gz/sim/components/Volume.hh | 41 + include/gz/sim/components/Wind.hh | 40 + include/gz/sim/components/WindMode.hh | 40 + include/gz/sim/components/World.hh | 46 ++ .../sim}/components/components.hh.in | 4 +- .../{ignition/gazebo => gz/sim}/config.hh.in | 20 +- .../sim}/detail/ComponentStorageBase.hh | 10 +- .../sim}/detail/EntityComponentManager.hh | 10 +- .../gazebo => gz/sim}/detail/View.hh | 12 +- include/gz/sim/gui/Gui.hh | 114 +++ include/gz/sim/gui/GuiEvents.hh | 219 +++++ include/gz/sim/gui/GuiRunner.hh | 91 ++ include/gz/sim/gui/GuiSystem.hh | 65 ++ include/gz/sim/gui/TmpIface.hh | 83 ++ include/gz/sim/physics/Events.hh | 65 ++ .../gazebo => gz/sim}/playback_server.config | 4 +- include/gz/sim/rendering/Events.hh | 61 ++ include/gz/sim/rendering/MarkerManager.hh | 77 ++ include/gz/sim/rendering/RenderUtil.hh | 167 ++++ include/gz/sim/rendering/SceneManager.hh | 212 +++++ .../{ignition/gazebo => gz/sim}/server.config | 6 +- include/ignition/CMakeLists.txt | 1 - include/ignition/gazebo.hh | 19 + include/ignition/gazebo/Conversions.hh | 654 +-------------- include/ignition/gazebo/Entity.hh | 52 +- .../ignition/gazebo/EntityComponentManager.hh | 767 +---------------- include/ignition/gazebo/EventManager.hh | 135 +-- include/ignition/gazebo/Events.hh | 55 +- include/ignition/gazebo/Export.hh | 19 + include/ignition/gazebo/Link.hh | 266 +----- include/ignition/gazebo/Model.hh | 171 +--- include/ignition/gazebo/SdfEntityCreator.hh | 165 +--- include/ignition/gazebo/Server.hh | 282 +------ include/ignition/gazebo/ServerConfig.hh | 423 +--------- include/ignition/gazebo/System.hh | 113 +-- include/ignition/gazebo/SystemLoader.hh | 70 +- include/ignition/gazebo/SystemPluginPtr.hh | 26 +- include/ignition/gazebo/TestFixture.hh | 102 +-- include/ignition/gazebo/Types.hh | 94 +-- include/ignition/gazebo/Util.hh | 247 +----- include/ignition/gazebo/World.hh | 178 +--- .../ackermann-steering-system/Export.hh | 19 + .../gazebo/air-pressure-system/Export.hh | 19 + .../gazebo/altimeter-system/Export.hh | 19 + .../gazebo/apply-joint-force-system/Export.hh | 19 + .../gazebo/apply-link-wrench-system/Export.hh | 19 + .../gazebo/breadcrumbs-system/Export.hh | 19 + .../ignition/gazebo/buoyancy-system/Export.hh | 19 + .../camera-video-recorder-system/Export.hh | 19 + .../collada-world-exporter-system/Export.hh | 19 + include/ignition/gazebo/components.hh | 19 + include/ignition/gazebo/components/Actor.hh | 42 +- .../ignition/gazebo/components/Actuators.hh | 31 +- .../gazebo/components/AirPressureSensor.hh | 33 +- .../ignition/gazebo/components/Altimeter.hh | 32 +- .../gazebo/components/AngularAcceleration.hh | 39 +- .../gazebo/components/AngularVelocity.hh | 38 +- .../gazebo/components/AngularVelocityCmd.hh | 38 +- .../ignition/gazebo/components/Atmosphere.hh | 39 +- .../gazebo/components/AxisAlignedBox.hh | 42 +- .../ignition/gazebo/components/BatterySoC.hh | 28 +- include/ignition/gazebo/components/Camera.hh | 32 +- .../gazebo/components/CanonicalLink.hh | 28 +- .../ignition/gazebo/components/CastShadows.hh | 27 +- .../gazebo/components/CenterOfVolume.hh | 32 +- .../gazebo/components/ChildLinkName.hh | 28 +- .../ignition/gazebo/components/Collision.hh | 55 +- .../ignition/gazebo/components/Component.hh | 527 +----------- .../gazebo/components/ContactSensor.hh | 28 +- .../gazebo/components/ContactSensorData.hh | 31 +- .../ignition/gazebo/components/DepthCamera.hh | 32 +- .../gazebo/components/DetachableJoint.hh | 90 +- .../components/ExternalWorldWrenchCmd.hh | 37 +- include/ignition/gazebo/components/Factory.hh | 339 +------- .../ignition/gazebo/components/Geometry.hh | 42 +- .../ignition/gazebo/components/GpuLidar.hh | 30 +- include/ignition/gazebo/components/Gravity.hh | 30 +- include/ignition/gazebo/components/Imu.hh | 33 +- .../ignition/gazebo/components/Inertial.hh | 38 +- include/ignition/gazebo/components/Joint.hh | 27 +- .../ignition/gazebo/components/JointAxis.hh | 43 +- .../gazebo/components/JointEffortLimitsCmd.hh | 45 +- .../ignition/gazebo/components/JointForce.hh | 31 +- .../gazebo/components/JointForceCmd.hh | 31 +- .../gazebo/components/JointPosition.hh | 32 +- .../components/JointPositionLimitsCmd.hh | 43 +- .../gazebo/components/JointPositionReset.hh | 34 +- .../ignition/gazebo/components/JointType.hh | 59 +- .../gazebo/components/JointVelocity.hh | 31 +- .../gazebo/components/JointVelocityCmd.hh | 33 +- .../components/JointVelocityLimitsCmd.hh | 43 +- .../gazebo/components/JointVelocityReset.hh | 35 +- .../ignition/gazebo/components/LaserRetro.hh | 26 +- include/ignition/gazebo/components/Level.hh | 31 +- .../ignition/gazebo/components/LevelBuffer.hh | 28 +- .../gazebo/components/LevelEntityNames.hh | 74 +- include/ignition/gazebo/components/Lidar.hh | 30 +- include/ignition/gazebo/components/Light.hh | 42 +- .../gazebo/components/LinearAcceleration.hh | 38 +- .../gazebo/components/LinearVelocity.hh | 35 +- .../gazebo/components/LinearVelocityCmd.hh | 40 +- .../gazebo/components/LinearVelocitySeed.hh | 40 +- include/ignition/gazebo/components/Link.hh | 27 +- .../components/LogPlaybackStatistics.hh | 35 +- .../gazebo/components/LogicalAudio.hh | 312 +------ .../gazebo/components/LogicalCamera.hh | 30 +- .../gazebo/components/MagneticField.hh | 31 +- .../gazebo/components/Magnetometer.hh | 35 +- .../ignition/gazebo/components/Material.hh | 38 +- include/ignition/gazebo/components/Model.hh | 33 +- include/ignition/gazebo/components/Name.hh | 29 +- .../gazebo/components/ParentEntity.hh | 36 +- .../gazebo/components/ParentLinkName.hh | 27 +- .../ignition/gazebo/components/Performer.hh | 26 +- .../gazebo/components/PerformerAffinity.hh | 34 +- .../gazebo/components/PerformerLevels.hh | 70 +- include/ignition/gazebo/components/Physics.hh | 43 +- .../ignition/gazebo/components/PhysicsCmd.hh | 33 +- .../gazebo/components/PhysicsEnginePlugin.hh | 30 +- include/ignition/gazebo/components/Pose.hh | 35 +- include/ignition/gazebo/components/PoseCmd.hh | 30 +- .../components/RenderEngineGuiPlugin.hh | 31 +- .../components/RenderEngineServerPlugin.hh | 32 +- .../ignition/gazebo/components/RgbdCamera.hh | 31 +- include/ignition/gazebo/components/Scene.hh | 40 +- .../ignition/gazebo/components/SelfCollide.hh | 27 +- include/ignition/gazebo/components/Sensor.hh | 38 +- .../gazebo/components/Serialization.hh | 214 +---- .../gazebo/components/SlipComplianceCmd.hh | 34 +- .../gazebo/components/SourceFilePath.hh | 30 +- include/ignition/gazebo/components/Static.hh | 26 +- .../ignition/gazebo/components/Temperature.hh | 30 +- .../gazebo/components/ThermalCamera.hh | 32 +- .../ignition/gazebo/components/ThreadPitch.hh | 26 +- .../gazebo/components/Transparency.hh | 28 +- include/ignition/gazebo/components/Visual.hh | 27 +- include/ignition/gazebo/components/Volume.hh | 28 +- include/ignition/gazebo/components/Wind.hh | 25 +- .../ignition/gazebo/components/WindMode.hh | 25 +- include/ignition/gazebo/components/World.hh | 33 +- include/ignition/gazebo/config.hh | 65 ++ .../ignition/gazebo/contact-system/Export.hh | 19 + .../gazebo/detachable-joint-system/Export.hh | 19 + .../gazebo/diff-drive-system/Export.hh | 19 + .../ignition/gazebo/elevator-system/Export.hh | 19 + include/ignition/gazebo/gui/Export.hh | 19 + include/ignition/gazebo/gui/Gui.hh | 101 +-- include/ignition/gazebo/gui/GuiEvents.hh | 208 +---- include/ignition/gazebo/gui/GuiRunner.hh | 80 +- include/ignition/gazebo/gui/GuiSystem.hh | 52 +- include/ignition/gazebo/gui/TmpIface.hh | 72 +- include/ignition/gazebo/ign/gazebo/Export.hh | 19 + .../ignition/gazebo/ignition/gazebo/Export.hh | 19 + include/ignition/gazebo/imu-system/Export.hh | 19 + .../gazebo/joint-controller-system/Export.hh | 19 + .../Export.hh | 19 + .../joint-state-publisher-system/Export.hh | 19 + .../kinetic-energy-monitor-system/Export.hh | 19 + .../gazebo/lift-drag-system/Export.hh | 19 + .../linearbatteryplugin-system/Export.hh | 19 + include/ignition/gazebo/log-system/Export.hh | 19 + .../log-video-recorder-system/Export.hh | 19 + .../gazebo/logical-camera-system/Export.hh | 19 + .../logicalaudiosensorplugin-system/Export.hh | 19 + .../gazebo/magnetometer-system/Export.hh | 19 + .../multicopter-control-system/Export.hh | 19 + .../multicopter-motor-model-system/Export.hh | 19 + .../performer-detector-system/Export.hh | 19 + .../ignition/gazebo/physics-system/Export.hh | 19 + include/ignition/gazebo/physics/Events.hh | 54 +- .../gazebo/pose-publisher-system/Export.hh | 19 + include/ignition/gazebo/rendering/Events.hh | 50 +- include/ignition/gazebo/rendering/Export.hh | 19 + .../gazebo/rendering/MarkerManager.hh | 66 +- .../ignition/gazebo/rendering/RenderUtil.hh | 154 +--- .../ignition/gazebo/rendering/SceneManager.hh | 197 +---- .../gazebo/scene-broadcaster-system/Export.hh | 19 + .../ignition/gazebo/sensors-system/Export.hh | 19 + .../ignition/gazebo/thermal-system/Export.hh | 19 + .../gazebo/touchplugin-system/Export.hh | 19 + .../gazebo/track-controller-system/Export.hh | 19 + .../gazebo/tracked-vehicle-system/Export.hh | 19 + .../triggered-publisher-system/Export.hh | 19 + .../gazebo/user-commands-system/Export.hh | 19 + .../gazebo/velocity-control-system/Export.hh | 19 + .../gazebo/wheel-slip-system/Export.hh | 19 + .../gazebo/wind-effects-system/Export.hh | 19 + src/Barrier.cc | 2 +- src/Barrier.hh | 10 +- src/Barrier_TEST.cc | 14 +- src/CMakeLists.txt | 7 +- src/ComponentFactory_TEST.cc | 12 +- src/Component_TEST.cc | 18 +- src/Conversions.cc | 54 +- src/Conversions_TEST.cc | 8 +- src/EntityComponentManager.cc | 18 +- src/EntityComponentManager_TEST.cc | 20 +- src/EventManager.cc | 6 +- src/EventManager_TEST.cc | 16 +- src/LevelManager.cc | 66 +- src/LevelManager.hh | 20 +- src/Link.cc | 52 +- src/Link_TEST.cc | 34 +- src/Model.cc | 32 +- src/ModelCommandAPI_TEST.cc | 8 +- src/Model_TEST.cc | 34 +- src/SdfEntityCreator.cc | 116 +-- src/SdfEntityCreator_TEST.cc | 54 +- src/SdfGenerator.cc | 20 +- src/SdfGenerator.hh | 10 +- src/SdfGenerator_TEST.cc | 36 +- src/Server.cc | 16 +- src/ServerConfig.cc | 39 +- src/ServerConfig_TEST.cc | 42 +- src/ServerPrivate.cc | 18 +- src/ServerPrivate.hh | 36 +- src/Server_TEST.cc | 136 +-- src/SimulationRunner.cc | 28 +- src/SimulationRunner.hh | 62 +- src/SimulationRunner_TEST.cc | 60 +- src/System.cc | 4 +- src/SystemLoader.cc | 35 +- src/SystemLoader_TEST.cc | 16 +- src/System_TEST.cc | 4 +- src/TestFixture.cc | 12 +- src/TestFixture_TEST.cc | 16 +- src/Util.cc | 41 +- src/Util_TEST.cc | 72 +- src/View.cc | 8 +- src/World.cc | 35 +- src/World_TEST.cc | 34 +- src/cmd/ModelCommandAPI.cc | 44 +- src/cmd/ModelCommandAPI.hh | 2 +- src/cmd/gazebo.bash_completion.sh | 2 +- src/gui/AboutDialogHandler.cc | 12 +- src/gui/AboutDialogHandler.hh | 8 +- src/gui/CMakeLists.txt | 8 +- src/gui/Gui.cc | 72 +- src/gui/GuiFileHandler.cc | 14 +- src/gui/GuiFileHandler.hh | 12 +- src/gui/GuiRunner.cc | 24 +- src/gui/Gui_TEST.cc | 26 +- src/gui/PathManager.cc | 16 +- src/gui/PathManager.hh | 10 +- src/gui/QuickStartHandler.cc | 8 +- src/gui/QuickStartHandler.hh | 8 +- src/gui/TmpIface.cc | 4 +- src/gui/plugins/align_tool/AlignTool.cc | 52 +- src/gui/plugins/align_tool/AlignTool.hh | 10 +- .../component_inspector/ComponentInspector.cc | 114 +-- .../component_inspector/ComponentInspector.hh | 18 +- src/gui/plugins/component_inspector/Pose3d.cc | 6 +- src/gui/plugins/component_inspector/Pose3d.hh | 12 +- src/gui/plugins/component_inspector/Types.hh | 6 +- src/gui/plugins/entity_tree/EntityTree.cc | 60 +- src/gui/plugins/entity_tree/EntityTree.hh | 6 +- src/gui/plugins/grid_config/GridConfig.cc | 32 +- src/gui/plugins/grid_config/GridConfig.hh | 10 +- .../JointPositionController.cc | 48 +- .../JointPositionController.hh | 12 +- .../JointPositionController_TEST.cc | 74 +- src/gui/plugins/modules/EntityContextMenu.cc | 18 +- src/gui/plugins/modules/EntityContextMenu.hh | 6 +- .../playback_scrubber/PlaybackScrubber.cc | 32 +- .../playback_scrubber/PlaybackScrubber.hh | 8 +- src/gui/plugins/plot_3d/Plot3D.cc | 38 +- src/gui/plugins/plot_3d/Plot3D.hh | 8 +- src/gui/plugins/plot_3d/Plot3D_TEST.cc | 40 +- .../resource_spawner/ResourceSpawner.cc | 44 +- .../resource_spawner/ResourceSpawner.hh | 8 +- src/gui/plugins/scene3d/Scene3D.cc | 158 ++-- src/gui/plugins/scene3d/Scene3D.hh | 34 +- src/gui/plugins/shapes/Shapes.cc | 32 +- src/gui/plugins/shapes/Shapes.hh | 8 +- src/gui/plugins/tape_measure/TapeMeasure.cc | 72 +- src/gui/plugins/tape_measure/TapeMeasure.hh | 22 +- .../transform_control/TransformControl.cc | 48 +- .../transform_control/TransformControl.hh | 8 +- .../plugins/video_recorder/VideoRecorder.cc | 20 +- .../plugins/video_recorder/VideoRecorder.hh | 8 +- src/gui/plugins/view_angle/ViewAngle.cc | 16 +- src/gui/plugins/view_angle/ViewAngle.hh | 10 +- src/{ign.cc => gz.cc} | 34 +- src/{ign.hh => gz.hh} | 6 +- src/{ign_TEST.cc => gz_TEST.cc} | 14 +- src/network/NetworkConfig.cc | 8 +- src/network/NetworkConfig.hh | 10 +- src/network/NetworkConfig_TEST.cc | 8 +- src/network/NetworkManager.cc | 10 +- src/network/NetworkManager.hh | 16 +- src/network/NetworkManagerPrimary.cc | 22 +- src/network/NetworkManagerPrimary.hh | 18 +- src/network/NetworkManagerPrivate.hh | 19 +- src/network/NetworkManagerSecondary.cc | 20 +- src/network/NetworkManagerSecondary.hh | 16 +- src/network/NetworkManager_TEST.cc | 12 +- src/network/NetworkRole.hh | 10 +- src/network/PeerInfo.cc | 12 +- src/network/PeerInfo.hh | 10 +- src/network/PeerTracker.cc | 4 +- src/network/PeerTracker.hh | 24 +- src/network/PeerTracker_TEST.cc | 38 +- src/rendering/MarkerManager.cc | 22 +- src/rendering/RenderUtil.cc | 90 +- src/rendering/SceneManager.cc | 40 +- .../ackermann_steering/AckermannSteering.cc | 40 +- .../ackermann_steering/AckermannSteering.hh | 10 +- src/systems/air_pressure/AirPressure.cc | 35 +- src/systems/air_pressure/AirPressure.hh | 8 +- src/systems/altimeter/Altimeter.cc | 41 +- src/systems/altimeter/Altimeter.hh | 8 +- .../apply_joint_force/ApplyJointForce.cc | 20 +- .../apply_joint_force/ApplyJointForce.hh | 10 +- .../apply_link_wrench/ApplyLinkWrench.cc | 36 +- .../apply_link_wrench/ApplyLinkWrench.hh | 2 +- .../battery_plugin/LinearBatteryPlugin.cc | 42 +- .../battery_plugin/LinearBatteryPlugin.hh | 12 +- src/systems/breadcrumbs/Breadcrumbs.cc | 39 +- src/systems/breadcrumbs/Breadcrumbs.hh | 18 +- src/systems/buoyancy/Buoyancy.cc | 50 +- src/systems/buoyancy/Buoyancy.hh | 10 +- .../CameraVideoRecorder.cc | 56 +- .../CameraVideoRecorder.hh | 8 +- .../ColladaWorldExporter.cc | 52 +- .../ColladaWorldExporter.hh | 6 +- src/systems/contact/Contact.cc | 38 +- src/systems/contact/Contact.hh | 6 +- .../detachable_joint/DetachableJoint.cc | 28 +- .../detachable_joint/DetachableJoint.hh | 16 +- src/systems/diff_drive/DiffDrive.cc | 37 +- src/systems/diff_drive/DiffDrive.hh | 10 +- src/systems/elevator/Elevator.cc | 39 +- src/systems/elevator/Elevator.hh | 8 +- src/systems/elevator/ElevatorCommonPrivate.hh | 8 +- src/systems/elevator/ElevatorStateMachine.hh | 10 +- .../state_machine/ElevatorStateMachineImpl.hh | 2 +- .../elevator/state_machine/StatesImpl.hh | 2 +- src/systems/elevator/utils/DoorTimer.hh | 8 +- src/systems/elevator/utils/JointMonitor.cc | 4 +- src/systems/elevator/utils/JointMonitor.hh | 8 +- src/systems/imu/Imu.cc | 45 +- src/systems/imu/Imu.hh | 8 +- .../joint_controller/JointController.cc | 28 +- .../joint_controller/JointController.hh | 10 +- .../JointPositionController.cc | 26 +- .../JointPositionController.hh | 12 +- .../JointStatePublisher.cc | 36 +- .../JointStatePublisher.hh | 14 +- .../KineticEnergyMonitor.cc | 38 +- .../KineticEnergyMonitor.hh | 12 +- src/systems/lift_drag/LiftDrag.cc | 41 +- src/systems/lift_drag/LiftDrag.hh | 6 +- src/systems/log/LogPlayback.cc | 52 +- src/systems/log/LogPlayback.hh | 8 +- src/systems/log/LogRecord.cc | 56 +- src/systems/log/LogRecord.hh | 8 +- .../log_video_recorder/LogVideoRecorder.cc | 38 +- .../log_video_recorder/LogVideoRecorder.hh | 8 +- .../LogicalAudio.cc | 4 +- .../LogicalAudio.hh | 14 +- .../LogicalAudioSensorPlugin.cc | 30 +- .../LogicalAudioSensorPlugin.hh | 14 +- .../LogicalAudio_TEST.cc | 2 +- src/systems/logical_camera/LogicalCamera.cc | 42 +- src/systems/logical_camera/LogicalCamera.hh | 8 +- src/systems/magnetometer/Magnetometer.cc | 38 +- src/systems/magnetometer/Magnetometer.hh | 8 +- src/systems/multicopter_control/Common.cc | 24 +- src/systems/multicopter_control/Common.hh | 10 +- .../LeeVelocityController.hh | 6 +- .../MulticopterVelocityControl.cc | 41 +- .../MulticopterVelocityControl.hh | 18 +- src/systems/multicopter_control/Parameters.hh | 6 +- .../MulticopterMotorModel.cc | 44 +- .../MulticopterMotorModel.hh | 10 +- .../performer_detector/PerformerDetector.cc | 36 +- .../performer_detector/PerformerDetector.hh | 18 +- src/systems/physics/EntityFeatureMap.hh | 16 +- src/systems/physics/EntityFeatureMap_TEST.cc | 34 +- src/systems/physics/Physics.cc | 185 +++-- src/systems/physics/Physics.hh | 52 +- src/systems/pose_publisher/PosePublisher.cc | 58 +- src/systems/pose_publisher/PosePublisher.hh | 16 +- .../scene_broadcaster/SceneBroadcaster.cc | 76 +- .../scene_broadcaster/SceneBroadcaster.hh | 10 +- src/systems/sensors/Sensors.cc | 59 +- src/systems/sensors/Sensors.hh | 8 +- src/systems/thermal/Thermal.cc | 21 +- src/systems/thermal/Thermal.hh | 10 +- src/systems/touch_plugin/TouchPlugin.cc | 31 +- src/systems/touch_plugin/TouchPlugin.hh | 10 +- .../track_controller/TrackController.cc | 36 +- .../track_controller/TrackController.hh | 12 +- src/systems/tracked_vehicle/TrackedVehicle.cc | 38 +- src/systems/tracked_vehicle/TrackedVehicle.hh | 10 +- .../triggered_publisher/TriggeredPublisher.cc | 14 +- .../triggered_publisher/TriggeredPublisher.hh | 8 +- src/systems/user_commands/UserCommands.cc | 58 +- src/systems/user_commands/UserCommands.hh | 8 +- .../velocity_control/VelocityControl.cc | 24 +- .../velocity_control/VelocityControl.hh | 10 +- src/systems/wheel_slip/WheelSlip.cc | 36 +- src/systems/wheel_slip/WheelSlip.hh | 12 +- src/systems/wind_effects/WindEffects.cc | 61 +- src/systems/wind_effects/WindEffects.hh | 8 +- test/CMakeLists.txt | 1 + test/benchmark/each.cc | 22 +- test/benchmark/ecm_serialize.cc | 24 +- test/helpers/EnvTestFixture.hh | 12 +- test/helpers/Relay.hh | 10 +- test/helpers/UniqueTestDirectoryEnv.hh | 12 +- test/integration/ackermann_steering_system.cc | 24 +- test/integration/air_pressure_system.cc | 22 +- test/integration/altimeter_system.cc | 36 +- test/integration/apply_joint_force_system.cc | 24 +- test/integration/apply_link_wrench_system.cc | 30 +- test/integration/battery_plugin.cc | 32 +- test/integration/breadcrumbs.cc | 28 +- test/integration/buoyancy.cc | 36 +- test/integration/camera_sensor_background.cc | 16 +- .../integration/camera_video_record_system.cc | 18 +- test/integration/collada_world_exporter.cc | 12 +- test/integration/components.cc | 94 +-- test/integration/contact_system.cc | 18 +- test/integration/deprecated_TEST.cc | 26 + test/integration/depth_camera.cc | 20 +- test/integration/detachable_joint.cc | 38 +- test/integration/diff_drive_system.cc | 28 +- test/integration/each_new_removed.cc | 42 +- test/integration/elevator_system.cc | 14 +- test/integration/entity_erase.cc | 8 +- test/integration/events.cc | 14 +- test/integration/examples_build.cc | 14 +- test/integration/gpu_lidar.cc | 18 +- test/integration/imu_system.cc | 34 +- test/integration/joint_controller_system.cc | 24 +- .../joint_position_controller_system.cc | 24 +- .../joint_state_publisher_system.cc | 14 +- .../kinetic_energy_monitor_system.cc | 18 +- test/integration/level_manager.cc | 38 +- .../level_manager_runtime_performers.cc | 44 +- test/integration/lift_drag_system.cc | 44 +- test/integration/link.cc | 44 +- test/integration/log_system.cc | 84 +- .../logical_audio_sensor_plugin.cc | 32 +- test/integration/logical_camera_system.cc | 28 +- test/integration/magnetometer_system.cc | 30 +- test/integration/model.cc | 38 +- test/integration/multicopter.cc | 36 +- test/integration/network_handshake.cc | 20 +- test/integration/performer_detector.cc | 24 +- test/integration/physics_system.cc | 66 +- test/integration/play_pause.cc | 10 +- test/integration/pose_publisher_system.cc | 32 +- test/integration/rgbd_camera.cc | 20 +- test/integration/save_world.cc | 22 +- test/integration/scene_broadcaster_system.cc | 48 +- test/integration/sdf_frame_semantics.cc | 40 +- test/integration/sdf_include.cc | 12 +- test/integration/sensors_system.cc | 58 +- test/integration/thermal_system.cc | 24 +- test/integration/touch_plugin.cc | 18 +- test/integration/tracked_vehicle_system.cc | 44 +- test/integration/triggered_publisher.cc | 28 +- test/integration/user_commands.cc | 38 +- test/integration/velocity_control_system.cc | 30 +- test/integration/wheel_slip.cc | 52 +- test/integration/wind_effects.cc | 38 +- test/integration/world.cc | 44 +- test/performance/each.cc | 14 +- test/performance/level_manager.cc | 16 +- test/performance/sdf_runner.cc | 16 +- test/plugins/EventTriggerSystem.cc | 15 +- test/plugins/EventTriggerSystem.hh | 16 +- test/plugins/MockSystem.cc | 17 +- test/plugins/MockSystem.hh | 34 +- test/plugins/Null.cc | 7 +- test/plugins/Null.hh | 10 +- test/plugins/TestModelSystem.cc | 13 +- test/plugins/TestModelSystem.hh | 16 +- test/plugins/TestSensorSystem.cc | 13 +- test/plugins/TestSensorSystem.hh | 14 +- test/plugins/TestSystem.cc | 9 +- test/plugins/TestSystem.hh | 8 +- test/plugins/TestWorldSystem.cc | 15 +- test/plugins/TestWorldSystem.hh | 12 +- test/test_config.hh.in | 10 +- test/worlds/ackermann_steering.sdf | 4 +- .../ackermann_steering_custom_frame_id.sdf | 8 +- .../ackermann_steering_custom_topics.sdf | 8 +- .../ackermann_steering_limited_joints_pub.sdf | 10 +- test/worlds/ackermann_steering_slow_odom.sdf | 4 +- test/worlds/air_pressure.sdf | 2 +- test/worlds/altimeter.sdf | 6 +- test/worlds/altimeter_with_pose.sdf | 8 +- test/worlds/apply_joint_force.sdf | 4 +- test/worlds/apply_link_wrench.sdf | 4 +- test/worlds/battery.sdf | 6 +- test/worlds/benchmark.sdf.erb | 8 +- test/worlds/breadcrumbs.sdf | 24 +- test/worlds/breadcrumbs_levels.sdf | 10 +- test/worlds/buoyancy.sdf.in | 8 +- test/worlds/camera_sensor_empty_scene.sdf | 4 +- test/worlds/camera_video_record.sdf | 10 +- test/worlds/canonical.sdf | 4 +- test/worlds/center_of_volume.sdf | 4 +- test/worlds/collada_world_exporter.sdf | 2 +- test/worlds/contact.sdf | 4 +- test/worlds/conveyor.sdf | 8 +- test/worlds/demo_joint_types.sdf | 4 +- test/worlds/depth_camera_sensor.sdf | 4 +- test/worlds/detachable_joint.sdf | 6 +- test/worlds/diff_drive.sdf | 6 +- test/worlds/diff_drive_custom_frame_id.sdf | 6 +- test/worlds/diff_drive_custom_tf_topic.sdf | 6 +- test/worlds/diff_drive_custom_topics.sdf | 4 +- test/worlds/diff_drive_limited_joint_pub.sdf | 6 +- test/worlds/diff_drive_skid.sdf | 4 +- test/worlds/elevator.sdf | 14 +- test/worlds/empty.sdf | 8 +- test/worlds/event_trigger.sdf | 2 +- test/worlds/falling.sdf | 2 +- test/worlds/friction.sdf | 8 +- .../worlds/test%20world/2/test.sdf | 5 + .../worlds/test%20world/2/test.world | 5 + .../worlds/test%20world/2/thumbnails/1.png | Bin 0 -> 6279 bytes test/worlds/gpu_lidar_sensor.sdf | 4 +- test/worlds/imu.sdf | 4 +- test/worlds/joint_controller.sdf | 8 +- test/worlds/joint_position_controller.sdf | 6 +- test/worlds/level_performance.sdf | 6 +- test/worlds/levels.sdf | 4 +- test/worlds/levels_no_performers.sdf | 4 +- test/worlds/lift_drag.sdf | 6 +- test/worlds/lights.sdf | 4 +- test/worlds/log_playback.sdf | 4 +- test/worlds/log_record_dbl_pendulum.sdf | 8 +- test/worlds/log_record_resources.sdf | 6 +- test/worlds/logical_audio_sensor_plugin.sdf | 6 +- .../logical_audio_sensor_plugin_services.sdf | 4 +- test/worlds/logical_camera_sensor.sdf | 4 +- test/worlds/magnetometer.sdf | 4 +- test/worlds/mesh.sdf | 4 +- test/worlds/multiple_worlds.sdf | 10 +- test/worlds/nested_model.sdf | 6 +- test/worlds/nondefault_canonical.sdf | 4 +- test/worlds/performer_detector.sdf | 12 +- test/worlds/performers.sdf | 2 +- test/worlds/plugins.sdf | 6 +- test/worlds/pose_publisher.sdf | 12 +- test/worlds/quadcopter.sdf | 12 +- test/worlds/quadcopter_velocity_control.sdf | 14 +- test/worlds/resource_paths.sdf | 2 +- test/worlds/revolute_joint.sdf | 4 +- test/worlds/revolute_joint_equilibrium.sdf | 4 +- test/worlds/rgbd_camera_sensor.sdf | 4 +- test/worlds/save_world.sdf | 12 +- test/worlds/sensor.sdf | 4 +- test/worlds/server_invalid.config | 2 +- test/worlds/server_valid.config | 6 +- test/worlds/server_valid2.config | 4 +- test/worlds/static_diff_drive_vehicle.sdf | 6 +- test/worlds/thermal.sdf | 12 +- test/worlds/tire_drum.sdf | 2 +- test/worlds/touch_plugin.sdf | 10 +- test/worlds/tracked_vehicle_simple.sdf | 20 +- test/worlds/triball_drift.sdf | 8 +- test/worlds/triggered_publisher.sdf | 34 +- test/worlds/trisphere_cycle_wheel_slip.sdf | 10 +- test/worlds/velocity_control.sdf | 10 +- test/worlds/wind_effects.sdf | 6 +- tutorials/battery.md | 4 +- tutorials/collada_world_exporter.md | 2 +- tutorials/create_system_plugins.md | 10 +- tutorials/gui_config.md | 2 +- tutorials/levels.md | 8 +- tutorials/log.md | 10 +- tutorials/logical_audio_sensor.md | 4 +- tutorials/migrating_ardupilot_plugin.md | 156 ++-- tutorials/migration_link_api.md | 76 +- tutorials/migration_model_api.md | 62 +- tutorials/migration_plugins.md | 42 +- tutorials/migration_sdf.md | 2 +- tutorials/migration_world_api.md | 54 +- tutorials/physics.md | 14 +- tutorials/rendering_plugins.md | 26 +- tutorials/resources.md | 8 +- tutorials/server_config.md | 6 +- tutorials/terminology.md | 4 +- tutorials/test_fixture.md | 2 +- tutorials/triggered_publisher.md | 18 +- tutorials/video_recorder.md | 4 +- 803 files changed, 17437 insertions(+), 14005 deletions(-) create mode 100644 include/gz/CMakeLists.txt rename include/{ignition/gazebo => gz/sim}/CMakeLists.txt (100%) create mode 100644 include/gz/sim/Conversions.hh create mode 100644 include/gz/sim/Entity.hh create mode 100644 include/gz/sim/EntityComponentManager.hh create mode 100644 include/gz/sim/EventManager.hh create mode 100644 include/gz/sim/Events.hh create mode 100644 include/gz/sim/Link.hh create mode 100644 include/gz/sim/Model.hh create mode 100644 include/gz/sim/SdfEntityCreator.hh create mode 100644 include/gz/sim/Server.hh create mode 100644 include/gz/sim/ServerConfig.hh create mode 100644 include/gz/sim/System.hh create mode 100644 include/gz/sim/SystemLoader.hh create mode 100644 include/gz/sim/SystemPluginPtr.hh create mode 100644 include/gz/sim/TestFixture.hh create mode 100644 include/gz/sim/Types.hh create mode 100644 include/gz/sim/Util.hh create mode 100644 include/gz/sim/World.hh create mode 100644 include/gz/sim/components/Actor.hh create mode 100644 include/gz/sim/components/Actuators.hh create mode 100644 include/gz/sim/components/AirPressureSensor.hh create mode 100644 include/gz/sim/components/Altimeter.hh create mode 100644 include/gz/sim/components/AngularAcceleration.hh create mode 100644 include/gz/sim/components/AngularVelocity.hh create mode 100644 include/gz/sim/components/AngularVelocityCmd.hh create mode 100644 include/gz/sim/components/Atmosphere.hh create mode 100644 include/gz/sim/components/AxisAlignedBox.hh create mode 100644 include/gz/sim/components/BatterySoC.hh rename include/{ignition/gazebo => gz/sim}/components/CMakeLists.txt (80%) create mode 100644 include/gz/sim/components/Camera.hh create mode 100644 include/gz/sim/components/CanonicalLink.hh create mode 100644 include/gz/sim/components/CastShadows.hh create mode 100644 include/gz/sim/components/CenterOfVolume.hh create mode 100644 include/gz/sim/components/ChildLinkName.hh create mode 100644 include/gz/sim/components/Collision.hh create mode 100644 include/gz/sim/components/Component.hh create mode 100644 include/gz/sim/components/ContactSensor.hh create mode 100644 include/gz/sim/components/ContactSensorData.hh create mode 100644 include/gz/sim/components/DepthCamera.hh create mode 100644 include/gz/sim/components/DetachableJoint.hh create mode 100644 include/gz/sim/components/ExternalWorldWrenchCmd.hh create mode 100644 include/gz/sim/components/Factory.hh create mode 100644 include/gz/sim/components/Geometry.hh create mode 100644 include/gz/sim/components/GpuLidar.hh create mode 100644 include/gz/sim/components/Gravity.hh create mode 100644 include/gz/sim/components/Imu.hh create mode 100644 include/gz/sim/components/Inertial.hh create mode 100644 include/gz/sim/components/Joint.hh create mode 100644 include/gz/sim/components/JointAxis.hh create mode 100644 include/gz/sim/components/JointEffortLimitsCmd.hh create mode 100644 include/gz/sim/components/JointForce.hh create mode 100644 include/gz/sim/components/JointForceCmd.hh create mode 100644 include/gz/sim/components/JointPosition.hh create mode 100644 include/gz/sim/components/JointPositionLimitsCmd.hh create mode 100644 include/gz/sim/components/JointPositionReset.hh create mode 100644 include/gz/sim/components/JointType.hh create mode 100644 include/gz/sim/components/JointVelocity.hh create mode 100644 include/gz/sim/components/JointVelocityCmd.hh create mode 100644 include/gz/sim/components/JointVelocityLimitsCmd.hh create mode 100644 include/gz/sim/components/JointVelocityReset.hh create mode 100644 include/gz/sim/components/LaserRetro.hh create mode 100644 include/gz/sim/components/Level.hh create mode 100644 include/gz/sim/components/LevelBuffer.hh create mode 100644 include/gz/sim/components/LevelEntityNames.hh create mode 100644 include/gz/sim/components/Lidar.hh create mode 100644 include/gz/sim/components/Light.hh create mode 100644 include/gz/sim/components/LinearAcceleration.hh create mode 100644 include/gz/sim/components/LinearVelocity.hh create mode 100644 include/gz/sim/components/LinearVelocityCmd.hh create mode 100644 include/gz/sim/components/LinearVelocitySeed.hh create mode 100644 include/gz/sim/components/Link.hh create mode 100644 include/gz/sim/components/LogPlaybackStatistics.hh create mode 100644 include/gz/sim/components/LogicalAudio.hh create mode 100644 include/gz/sim/components/LogicalCamera.hh create mode 100644 include/gz/sim/components/MagneticField.hh create mode 100644 include/gz/sim/components/Magnetometer.hh create mode 100644 include/gz/sim/components/Material.hh create mode 100644 include/gz/sim/components/Model.hh create mode 100644 include/gz/sim/components/Name.hh create mode 100644 include/gz/sim/components/ParentEntity.hh create mode 100644 include/gz/sim/components/ParentLinkName.hh create mode 100644 include/gz/sim/components/Performer.hh create mode 100644 include/gz/sim/components/PerformerAffinity.hh create mode 100644 include/gz/sim/components/PerformerLevels.hh create mode 100644 include/gz/sim/components/Physics.hh create mode 100644 include/gz/sim/components/PhysicsCmd.hh create mode 100644 include/gz/sim/components/PhysicsEnginePlugin.hh create mode 100644 include/gz/sim/components/Pose.hh create mode 100644 include/gz/sim/components/PoseCmd.hh create mode 100644 include/gz/sim/components/RenderEngineGuiPlugin.hh create mode 100644 include/gz/sim/components/RenderEngineServerPlugin.hh create mode 100644 include/gz/sim/components/RgbdCamera.hh create mode 100644 include/gz/sim/components/Scene.hh create mode 100644 include/gz/sim/components/SelfCollide.hh create mode 100644 include/gz/sim/components/Sensor.hh create mode 100644 include/gz/sim/components/Serialization.hh create mode 100644 include/gz/sim/components/SlipComplianceCmd.hh create mode 100644 include/gz/sim/components/SourceFilePath.hh create mode 100644 include/gz/sim/components/Static.hh create mode 100644 include/gz/sim/components/Temperature.hh create mode 100644 include/gz/sim/components/ThermalCamera.hh create mode 100644 include/gz/sim/components/ThreadPitch.hh create mode 100644 include/gz/sim/components/Transparency.hh create mode 100644 include/gz/sim/components/Visual.hh create mode 100644 include/gz/sim/components/Volume.hh create mode 100644 include/gz/sim/components/Wind.hh create mode 100644 include/gz/sim/components/WindMode.hh create mode 100644 include/gz/sim/components/World.hh rename include/{ignition/gazebo => gz/sim}/components/components.hh.in (87%) rename include/{ignition/gazebo => gz/sim}/config.hh.in (79%) rename include/{ignition/gazebo => gz/sim}/detail/ComponentStorageBase.hh (96%) rename include/{ignition/gazebo => gz/sim}/detail/EntityComponentManager.hh (98%) rename include/{ignition/gazebo => gz/sim}/detail/View.hh (95%) create mode 100644 include/gz/sim/gui/Gui.hh create mode 100644 include/gz/sim/gui/GuiEvents.hh create mode 100644 include/gz/sim/gui/GuiRunner.hh create mode 100644 include/gz/sim/gui/GuiSystem.hh create mode 100644 include/gz/sim/gui/TmpIface.hh create mode 100644 include/gz/sim/physics/Events.hh rename include/{ignition/gazebo => gz/sim}/playback_server.config (72%) create mode 100644 include/gz/sim/rendering/Events.hh create mode 100644 include/gz/sim/rendering/MarkerManager.hh create mode 100644 include/gz/sim/rendering/RenderUtil.hh create mode 100644 include/gz/sim/rendering/SceneManager.hh rename include/{ignition/gazebo => gz/sim}/server.config (71%) delete mode 100644 include/ignition/CMakeLists.txt create mode 100644 include/ignition/gazebo.hh create mode 100644 include/ignition/gazebo/Export.hh create mode 100644 include/ignition/gazebo/ackermann-steering-system/Export.hh create mode 100644 include/ignition/gazebo/air-pressure-system/Export.hh create mode 100644 include/ignition/gazebo/altimeter-system/Export.hh create mode 100644 include/ignition/gazebo/apply-joint-force-system/Export.hh create mode 100644 include/ignition/gazebo/apply-link-wrench-system/Export.hh create mode 100644 include/ignition/gazebo/breadcrumbs-system/Export.hh create mode 100644 include/ignition/gazebo/buoyancy-system/Export.hh create mode 100644 include/ignition/gazebo/camera-video-recorder-system/Export.hh create mode 100644 include/ignition/gazebo/collada-world-exporter-system/Export.hh create mode 100644 include/ignition/gazebo/components.hh create mode 100644 include/ignition/gazebo/config.hh create mode 100644 include/ignition/gazebo/contact-system/Export.hh create mode 100644 include/ignition/gazebo/detachable-joint-system/Export.hh create mode 100644 include/ignition/gazebo/diff-drive-system/Export.hh create mode 100644 include/ignition/gazebo/elevator-system/Export.hh create mode 100644 include/ignition/gazebo/gui/Export.hh create mode 100644 include/ignition/gazebo/ign/gazebo/Export.hh create mode 100644 include/ignition/gazebo/ignition/gazebo/Export.hh create mode 100644 include/ignition/gazebo/imu-system/Export.hh create mode 100644 include/ignition/gazebo/joint-controller-system/Export.hh create mode 100644 include/ignition/gazebo/joint-position-controller-system/Export.hh create mode 100644 include/ignition/gazebo/joint-state-publisher-system/Export.hh create mode 100644 include/ignition/gazebo/kinetic-energy-monitor-system/Export.hh create mode 100644 include/ignition/gazebo/lift-drag-system/Export.hh create mode 100644 include/ignition/gazebo/linearbatteryplugin-system/Export.hh create mode 100644 include/ignition/gazebo/log-system/Export.hh create mode 100644 include/ignition/gazebo/log-video-recorder-system/Export.hh create mode 100644 include/ignition/gazebo/logical-camera-system/Export.hh create mode 100644 include/ignition/gazebo/logicalaudiosensorplugin-system/Export.hh create mode 100644 include/ignition/gazebo/magnetometer-system/Export.hh create mode 100644 include/ignition/gazebo/multicopter-control-system/Export.hh create mode 100644 include/ignition/gazebo/multicopter-motor-model-system/Export.hh create mode 100644 include/ignition/gazebo/performer-detector-system/Export.hh create mode 100644 include/ignition/gazebo/physics-system/Export.hh create mode 100644 include/ignition/gazebo/pose-publisher-system/Export.hh create mode 100644 include/ignition/gazebo/rendering/Export.hh create mode 100644 include/ignition/gazebo/scene-broadcaster-system/Export.hh create mode 100644 include/ignition/gazebo/sensors-system/Export.hh create mode 100644 include/ignition/gazebo/thermal-system/Export.hh create mode 100644 include/ignition/gazebo/touchplugin-system/Export.hh create mode 100644 include/ignition/gazebo/track-controller-system/Export.hh create mode 100644 include/ignition/gazebo/tracked-vehicle-system/Export.hh create mode 100644 include/ignition/gazebo/triggered-publisher-system/Export.hh create mode 100644 include/ignition/gazebo/user-commands-system/Export.hh create mode 100644 include/ignition/gazebo/velocity-control-system/Export.hh create mode 100644 include/ignition/gazebo/wheel-slip-system/Export.hh create mode 100644 include/ignition/gazebo/wind-effects-system/Export.hh rename src/{ign.cc => gz.cc} (95%) rename src/{ign.hh => gz.hh} (97%) rename src/{ign_TEST.cc => gz_TEST.cc} (94%) create mode 100644 test/integration/deprecated_TEST.cc create mode 100644 test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.sdf create mode 100644 test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.world create mode 100644 test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/thumbnails/1.png diff --git a/CMakeLists.txt b/CMakeLists.txt index 7cc0c040ae..5c5abddeba 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -15,7 +15,10 @@ find_package(ignition-cmake2 2.8.0 REQUIRED) #============================================================================ # Configure the project #============================================================================ -ign_configure_project(VERSION_SUFFIX) +ign_configure_project( + REPLACE_IGNITION_INCLUDE_PATH gz/sim + VERSION_SUFFIX +) #============================================================================ # Set project-specific options @@ -124,7 +127,7 @@ set(IGN_SENSORS_VER ${ignition-sensors3_VERSION_MAJOR}) #-------------------------------------- # Find ignition-rendering -ign_find_package(ignition-rendering3 REQUIRED VERSION 3.5) +ign_find_package(ignition-rendering3 REQUIRED VERSION 3.7) set(IGN_RENDERING_VER ${ignition-rendering3_VERSION_MAJOR}) #-------------------------------------- diff --git a/Changelog.md b/Changelog.md index 6cfe14816d..4873dea3d3 100644 --- a/Changelog.md +++ b/Changelog.md @@ -126,7 +126,7 @@ 1. Fix generation of systems library symlinks in build directory * [Pull request #1160](https://github.com/gazebosim/gz-sim/pull/1160) -1. Backport gazebo::Util::validTopic() from ign-gazebo4. +1. Backport sim::Util::validTopic() from ign-gazebo4. * [Pull request #1153](https://github.com/gazebosim/gz-sim/pull/1153) 1. Support setting the background color for sensors @@ -643,7 +643,7 @@ * [Pull Request 351](https://github.com/gazebosim/gz-sim/pull/351) * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) -1. Tests & Warnings: Qt 5.14, breadcrumbs, Gui, ign_TEST +1. Tests & Warnings: Qt 5.14, breadcrumbs, Gui, gz_TEST * [Pull Request 327](https://github.com/gazebosim/gz-sim/pull/327) 1. Added support for specifying topics to record. @@ -788,7 +788,7 @@ 1. Enhanced log playback performance. * [Pull Request 351](https://github.com/gazebosim/gz-sim/pull/351) -1. Tests & Warnings: Qt 5.14, breadcrumbs, Gui, ign_TEST +1. Tests & Warnings: Qt 5.14, breadcrumbs, Gui, gz_TEST * [Pull Request 327](https://github.com/gazebosim/gz-sim/pull/327) 1. Added support for specifying topics to record. @@ -902,7 +902,7 @@ ### Ignition Gazebo 2.18.0 (2020-05-20) -1. Added a `/world//create_multiple` service that parallels the current `/world//create` service. The `create_multiple` service can handle an `ignition::msgs::EntityFactory_V` message that may contain one or more entities to spawn. +1. Added a `/world//create_multiple` service that parallels the current `/world//create` service. The `create_multiple` service can handle an `gz::msgs::EntityFactory_V` message that may contain one or more entities to spawn. * [Pull Request 146](https://github.com/gazebosim/gz-sim/pull/146) 1. DetachableJoint system: Add option to suppress warning about missing child model @@ -1319,7 +1319,7 @@ 1. Update Camera and DepthCamera components to use sdf::Sensor object instead of an sdf::ElementPtr. * [BitBucket pull request 299](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/299) -1. Added system for ignition::sensors::AirPressureSensor. +1. Added system for gz::sensors::AirPressureSensor. * [BitBucket pull request 300](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/300) 1. Support conversion and serialization of Imu components. IMU sensors are diff --git a/api.md.in b/api.md.in index 0fc4704def..43eb2ebe20 100644 --- a/api.md.in +++ b/api.md.in @@ -5,10 +5,10 @@ designed to rapidly develop robot and simulation applications. **Useful links** -1. ignition::gazebo::components : List of built-in Component types. Components represent data, such as position information, that can be added to an Entity. -2. ignition::gazebo::systems : List of available Systems. A System operates on Entities that have a specific set of Components. -3. ignition::gazebo::events : List of simulation events. See the - ignition::gazebo::EventManager for details about events and how to use them. +1. gz::sim::components : List of built-in Component types. Components represent data, such as position information, that can be added to an Entity. +2. gz::sim::systems : List of available Systems. A System operates on Entities that have a specific set of Components. +3. gz::sim::events : List of simulation events. See the + gz::sim::EventManager for details about events and how to use them. ## License diff --git a/examples/plugin/custom_component/CustomComponentPlugin.cc b/examples/plugin/custom_component/CustomComponentPlugin.cc index 7896ea3088..f2fdc39aca 100644 --- a/examples/plugin/custom_component/CustomComponentPlugin.cc +++ b/examples/plugin/custom_component/CustomComponentPlugin.cc @@ -16,9 +16,9 @@ */ #include "CustomComponentPlugin.hh" -#include +#include IGNITION_ADD_PLUGIN(examples::CustomComponentPlugin, - ignition::gazebo::System, + gz::sim::System, examples::CustomComponentPlugin::ISystemConfigure) diff --git a/examples/plugin/custom_component/CustomComponentPlugin.hh b/examples/plugin/custom_component/CustomComponentPlugin.hh index 1ae04b2453..070269ec81 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 { @@ -32,22 +32,22 @@ namespace examples // of `components::Component` where the first argument is the type being wrapped // (i.e. int) and the second is a unique name tag. using CustomComponent = - ignition::gazebo::components::Component; + gz::sim::components::Component; // Use this macro to register a component. Give it a unique name across the // entire simulation. IGN_GAZEBO_REGISTER_COMPONENT("examples::CustomComponent", CustomComponent) class CustomComponentPlugin : - public ignition::gazebo::System, - public ignition::gazebo::ISystemConfigure + public gz::sim::System, + public gz::sim::ISystemConfigure { public: CustomComponentPlugin() = default; - public: void Configure(const ignition::gazebo::Entity &_entity, + public: void Configure(const gz::sim::Entity &_entity, const std::shared_ptr &, - ignition::gazebo::EntityComponentManager &_ecm, - ignition::gazebo::EventManager &) override + gz::sim::EntityComponentManager &_ecm, + gz::sim::EventManager &) override { // You can create the custom component as you would create any other igndbg << "Creating component" << std::endl; @@ -56,7 +56,7 @@ class CustomComponentPlugin : // You can use the ECM's API, such as Each, to query for the // component: _ecm.Each( - [&](const ignition::gazebo::Entity &_entityEach, + [&](const gz::sim::Entity &_entityEach, const CustomComponent *_comp) -> bool { igndbg << "Entity: " << _entityEach << std::endl; diff --git a/examples/plugin/gui_system_plugin/GuiSystemPlugin.cc b/examples/plugin/gui_system_plugin/GuiSystemPlugin.cc index e1abf119ce..c7d94f4cbe 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" @@ -39,16 +39,16 @@ void GuiSystemPlugin::LoadConfig(const tinyxml2::XMLElement * /*_pluginElem*/) } ////////////////////////////////////////////////// -void GuiSystemPlugin::Update(const ignition::gazebo::UpdateInfo & /*_info*/, - ignition::gazebo::EntityComponentManager &_ecm) +void GuiSystemPlugin::Update(const gz::sim::UpdateInfo & /*_info*/, + gz::sim::EntityComponentManager &_ecm) { // In the update loop, you can for example get the name of the world and set // it as a property that can be read from the QML. - _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::Name *_name, - const ignition::gazebo::components::World *)->bool + _ecm.Each( + [&](const gz::sim::Entity &_entity, + const gz::sim::components::Name *_name, + const gz::sim::components::World *)->bool { this->SetCustomProperty(QString::fromStdString(_name->Data())); return true; @@ -70,4 +70,4 @@ void GuiSystemPlugin::SetCustomProperty(const QString &_customProperty) // Register this plugin IGNITION_ADD_PLUGIN(GuiSystemPlugin, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/examples/plugin/gui_system_plugin/GuiSystemPlugin.hh b/examples/plugin/gui_system_plugin/GuiSystemPlugin.hh index c9ff0826f1..aebbee2771 100644 --- a/examples/plugin/gui_system_plugin/GuiSystemPlugin.hh +++ b/examples/plugin/gui_system_plugin/GuiSystemPlugin.hh @@ -15,13 +15,13 @@ * */ -#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 +class GuiSystemPlugin : public gz::sim::GuiSystem { Q_OBJECT @@ -40,7 +40,7 @@ class GuiSystemPlugin : public ignition::gazebo::GuiSystem /// \brief Destructor public: ~GuiSystemPlugin() override; - /// \brief `ignition::gui::Plugin`s can overload this function to + /// \brief `gz::gui::Plugin`s can overload this function to /// receive custom configuration from an XML file. Here, it comes from the /// SDF. /// @@ -59,8 +59,8 @@ class GuiSystemPlugin : public ignition::gazebo::GuiSystem /// \param[in] _info Simulation information such as time. /// \param[in] _ecm Entity component manager, which can be used to get the /// latest information about entities and components. - public: void Update(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + public: void Update(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; /// \brief Get the custom property as a string. /// \return Custom property diff --git a/examples/plugin/gui_system_plugin/README.md b/examples/plugin/gui_system_plugin/README.md index 83c9f1a26b..2cee41dcc6 100644 --- a/examples/plugin/gui_system_plugin/README.md +++ b/examples/plugin/gui_system_plugin/README.md @@ -3,7 +3,7 @@ This example shows how to create a GUI system plugin. Ignition Gazebo supports any kind of Ignition GUI plugin -(`ignition::gui::Plugin`). Gazebo GUI plugins are a special type of Ignition +(`gz::gui::Plugin`). Gazebo GUI plugins are a special type of Ignition GUI plugin which also have access to entity and component updates coming from the server. diff --git a/examples/plugin/hello_world/HelloWorld.cc b/examples/plugin/hello_world/HelloWorld.cc index d73ed28b6c..3e793a465f 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" @@ -31,15 +31,15 @@ // what's in the header. IGNITION_ADD_PLUGIN( hello_world::HelloWorld, - ignition::gazebo::System, + gz::sim::System, hello_world::HelloWorld::ISystemPostUpdate) using namespace hello_world; // Here we implement the PostUpdate function, which is called at every // iteration. -void HelloWorld::PostUpdate(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &/*_ecm*/) +void HelloWorld::PostUpdate(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &/*_ecm*/) { // This is a simple example of how to get information from UpdateInfo. std::string msg = "Hello, world! Simulation is "; diff --git a/examples/plugin/hello_world/HelloWorld.hh b/examples/plugin/hello_world/HelloWorld.hh index ff60e09392..12c11a7cc8 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 @@ -31,16 +31,16 @@ namespace hello_world // physics runs. The opposite of that, `ISystemPreUpdate`, would be used by // plugins that want to send commands. class HelloWorld: - public ignition::gazebo::System, - public ignition::gazebo::ISystemPostUpdate + public gz::sim::System, + public gz::sim::ISystemPostUpdate { // Plugins inheriting ISystemPostUpdate must implement the PostUpdate // callback. This is called at every simulation iteration after the physics // updates the world. The _info variable provides information such as time, // while the _ecm provides an interface to all entities and components in // simulation. - public: void PostUpdate(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) override; + public: void PostUpdate(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) override; }; } #endif diff --git a/examples/plugin/rendering_plugins/RenderingGuiPlugin.cc b/examples/plugin/rendering_plugins/RenderingGuiPlugin.cc index e0c629f09b..ee376fefdf 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" @@ -33,8 +33,8 @@ void RenderingGuiPlugin::LoadConfig(const tinyxml2::XMLElement * /*_pluginElem*/ { // This is necessary to receive the Render event on eventFilter //! [connectToGuiEvent] - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); //! [connectToGuiEvent] } @@ -48,7 +48,7 @@ void RenderingGuiPlugin::RandomColor() //! [eventFilter] bool RenderingGuiPlugin::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { // This event is called in the render thread, so it's safe to make // rendering calls here @@ -78,9 +78,9 @@ void RenderingGuiPlugin::PerformRenderingOperations() return; this->scene->SetAmbientLight({ - static_cast(ignition::math::Rand::DblUniform(0.0, 1.0)), - static_cast(ignition::math::Rand::DblUniform(0.0, 1.0)), - static_cast(ignition::math::Rand::DblUniform(0.0, 1.0)), + static_cast(gz::math::Rand::DblUniform(0.0, 1.0)), + static_cast(gz::math::Rand::DblUniform(0.0, 1.0)), + static_cast(gz::math::Rand::DblUniform(0.0, 1.0)), 1.0}); this->dirty = false; @@ -90,7 +90,7 @@ void RenderingGuiPlugin::PerformRenderingOperations() ///////////////////////////////////////////////// void RenderingGuiPlugin::FindScene() { - auto loadedEngNames = ignition::rendering::loadedEngines(); + auto loadedEngNames = gz::rendering::loadedEngines(); if (loadedEngNames.empty()) { igndbg << "No rendering engine is loaded yet" << std::endl; @@ -104,7 +104,7 @@ void RenderingGuiPlugin::FindScene() igndbg << "More than one engine is available. " << "Using engine [" << engineName << "]" << std::endl; } - auto engine = ignition::rendering::engine(engineName); + auto engine = gz::rendering::engine(engineName); if (!engine) { ignerr << "Internal error: failed to load engine [" << engineName @@ -142,4 +142,4 @@ void RenderingGuiPlugin::FindScene() // Register this plugin IGNITION_ADD_PLUGIN(RenderingGuiPlugin, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/examples/plugin/rendering_plugins/RenderingGuiPlugin.hh b/examples/plugin/rendering_plugins/RenderingGuiPlugin.hh index 7958c38b07..33316706da 100644 --- a/examples/plugin/rendering_plugins/RenderingGuiPlugin.hh +++ b/examples/plugin/rendering_plugins/RenderingGuiPlugin.hh @@ -18,14 +18,14 @@ #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 /// Scene3D. -class RenderingGuiPlugin : public ignition::gui::Plugin +class RenderingGuiPlugin : public gz::gui::Plugin { Q_OBJECT @@ -51,7 +51,7 @@ class RenderingGuiPlugin : public ignition::gui::Plugin private: bool dirty{false}; /// \brief Pointer to the rendering scene. - private: ignition::rendering::ScenePtr scene{nullptr}; + private: gz::rendering::ScenePtr scene{nullptr}; }; #endif diff --git a/examples/plugin/rendering_plugins/RenderingServerPlugin.cc b/examples/plugin/rendering_plugins/RenderingServerPlugin.cc index 2054975787..b284edb749 100644 --- a/examples/plugin/rendering_plugins/RenderingServerPlugin.cc +++ b/examples/plugin/rendering_plugins/RenderingServerPlugin.cc @@ -17,25 +17,25 @@ #include "RenderingServerPlugin.hh" //! [includeRenderingEvents] -#include +#include //! [includeRenderingEvents] -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include using namespace std::literals::chrono_literals; ////////////////////////////////////////////////// void RenderingServerPlugin::Configure( - const ignition::gazebo::Entity &/*_entity*/, + const gz::sim::Entity &/*_entity*/, const std::shared_ptr &/*_sdf*/, - ignition::gazebo::EntityComponentManager &/*_ecm*/, - ignition::gazebo::EventManager &_eventMgr) + gz::sim::EntityComponentManager &/*_ecm*/, + gz::sim::EventManager &_eventMgr) { //! [connectToServerEvent] - this->connection = _eventMgr.Connect( + this->connection = _eventMgr.Connect( std::bind(&RenderingServerPlugin::PerformRenderingOperations, this)); //! [connectToServerEvent] } @@ -56,9 +56,9 @@ void RenderingServerPlugin::PerformRenderingOperations() return; this->scene->SetAmbientLight({ - static_cast(ignition::math::Rand::DblUniform(0.0, 1.0)), - static_cast(ignition::math::Rand::DblUniform(0.0, 1.0)), - static_cast(ignition::math::Rand::DblUniform(0.0, 1.0)), + static_cast(gz::math::Rand::DblUniform(0.0, 1.0)), + static_cast(gz::math::Rand::DblUniform(0.0, 1.0)), + static_cast(gz::math::Rand::DblUniform(0.0, 1.0)), 1.0}); this->lastUpdate = this->simTime; @@ -69,7 +69,7 @@ void RenderingServerPlugin::PerformRenderingOperations() //! [findScene] void RenderingServerPlugin::FindScene() { - auto loadedEngNames = ignition::rendering::loadedEngines(); + auto loadedEngNames = gz::rendering::loadedEngines(); if (loadedEngNames.empty()) { igndbg << "No rendering engine is loaded yet" << std::endl; @@ -83,7 +83,7 @@ void RenderingServerPlugin::FindScene() igndbg << "More than one engine is available. " << "Using engine [" << engineName << "]" << std::endl; } - auto engine = ignition::rendering::engine(engineName); + auto engine = gz::rendering::engine(engineName); if (!engine) { ignerr << "Internal error: failed to load engine [" << engineName @@ -121,15 +121,15 @@ void RenderingServerPlugin::FindScene() //! [findScene] ////////////////////////////////////////////////// -void RenderingServerPlugin::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void RenderingServerPlugin::PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { this->simTime = _info.simTime; } IGNITION_ADD_PLUGIN( RenderingServerPlugin, - ignition::gazebo::System, + gz::sim::System, RenderingServerPlugin::ISystemConfigure, RenderingServerPlugin::ISystemPreUpdate ) diff --git a/examples/plugin/rendering_plugins/RenderingServerPlugin.hh b/examples/plugin/rendering_plugins/RenderingServerPlugin.hh index 9f9218f4c6..155a25b462 100644 --- a/examples/plugin/rendering_plugins/RenderingServerPlugin.hh +++ b/examples/plugin/rendering_plugins/RenderingServerPlugin.hh @@ -17,32 +17,32 @@ #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. class RenderingServerPlugin: - public ignition::gazebo::System, - public ignition::gazebo::ISystemConfigure, - public ignition::gazebo::ISystemPreUpdate + public gz::sim::System, + public gz::sim::ISystemConfigure, + public gz::sim::ISystemPreUpdate { /// \brief Called once at startup /// \param[in] _entity Entity that the plugin is attached to, not used. /// \param[in] _sdf Element with custom configuration, not used. /// \param[in] _ecm Entity component manager /// \param[in] _eventMgr Event manager - public: void Configure(const ignition::gazebo::Entity &_entity, + public: void Configure(const gz::sim::Entity &_entity, const std::shared_ptr &_sdf, - ignition::gazebo::EntityComponentManager &_ecm, - ignition::gazebo::EventManager &_eventMgr) override; + gz::sim::EntityComponentManager &_ecm, + gz::sim::EventManager &_eventMgr) override; /// \brief Called just before each simulation update. /// \param[in] _info Contains information like sim time. /// \param[in] _ecm Entity component manager public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; /// \brief All rendering operations must happen within this call private: void PerformRenderingOperations(); @@ -52,10 +52,10 @@ class RenderingServerPlugin: private: void FindScene(); /// \brief Connection to pre-render event callback - private: ignition::common::ConnectionPtr connection{nullptr}; + private: gz::common::ConnectionPtr connection{nullptr}; /// \brief Pointer to rendering scene - private: ignition::rendering::ScenePtr scene{nullptr}; + private: gz::rendering::ScenePtr scene{nullptr}; /// \brief Current simulation time. private: std::chrono::steady_clock::duration simTime{0}; diff --git a/examples/plugin/rendering_plugins/rendering_plugins.sdf b/examples/plugin/rendering_plugins/rendering_plugins.sdf index 8fbb572bda..97a7540bce 100644 --- a/examples/plugin/rendering_plugins/rendering_plugins.sdf +++ b/examples/plugin/rendering_plugins/rendering_plugins.sdf @@ -3,7 +3,7 @@ + name="gz::sim::systems::Sensors"> ogre2 + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/plugin/system_plugin/SampleSystem.cc b/examples/plugin/system_plugin/SampleSystem.cc index 66b813f963..c920195379 100644 --- a/examples/plugin/system_plugin/SampleSystem.cc +++ b/examples/plugin/system_plugin/SampleSystem.cc @@ -1,12 +1,12 @@ #include "SampleSystem.hh" //! [registerSampleSystem] -#include +#include // Include a line in your source file for each interface implemented. IGNITION_ADD_PLUGIN( sample_system::SampleSystem, - ignition::gazebo::System, + gz::sim::System, sample_system::SampleSystem::ISystemPostUpdate) //! [registerSampleSystem] //! [implementSampleSystem] @@ -20,8 +20,8 @@ SampleSystem::~SampleSystem() { } -void SampleSystem::PostUpdate(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) +void SampleSystem::PostUpdate(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) { ignmsg << "SampleSystem::PostUpdate" << std::endl; } diff --git a/examples/plugin/system_plugin/SampleSystem.hh b/examples/plugin/system_plugin/SampleSystem.hh index e17bf1d98d..b5fd49799b 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 { @@ -26,39 +26,39 @@ namespace sample_system /// plugin interface. class SampleSystem: // This class is a system. - public ignition::gazebo::System, + public gz::sim::System, // This class also implements the ISystemPostUpdate interface. - public ignition::gazebo::ISystemPostUpdate + public gz::sim::ISystemPostUpdate { public: SampleSystem(); public: ~SampleSystem() override; - public: void PostUpdate(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) override; + public: void PostUpdate(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) override; }; class SampleSystem2: // This class is a system. - public ignition::gazebo::System, + public gz::sim::System, // This class also implements the ISystemPreUpdate, ISystemUpdate, // and ISystemPostUpdate interfaces. - public ignition::gazebo::ISystemPreUpdate, - public ignition::gazebo::ISystemUpdate, - public ignition::gazebo::ISystemPostUpdate + public gz::sim::ISystemPreUpdate, + public gz::sim::ISystemUpdate, + public gz::sim::ISystemPostUpdate { public: SampleSystem2(); public: ~SampleSystem2() override; - public: void PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + public: void PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; - public: void Update(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + public: void Update(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; - public: void PostUpdate(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) override; + public: void PostUpdate(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) override; }; } //! [header] diff --git a/examples/plugin/system_plugin/SampleSystem2.cc b/examples/plugin/system_plugin/SampleSystem2.cc index 837d0cfd5a..218b90a22b 100644 --- a/examples/plugin/system_plugin/SampleSystem2.cc +++ b/examples/plugin/system_plugin/SampleSystem2.cc @@ -1,11 +1,11 @@ #include "SampleSystem.hh" //! [registerSampleSystem2] -#include +#include IGNITION_ADD_PLUGIN( sample_system::SampleSystem2, - ignition::gazebo::System, + gz::sim::System, sample_system::SampleSystem2::ISystemPreUpdate, sample_system::SampleSystem2::ISystemUpdate, sample_system::SampleSystem2::ISystemPostUpdate) @@ -21,20 +21,20 @@ SampleSystem2::~SampleSystem2() { } -void SampleSystem2::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void SampleSystem2::PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { ignmsg << "SampleSystem2::PreUpdate" << std::endl; } -void SampleSystem2::Update(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void SampleSystem2::Update(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { ignmsg << "SampleSystem2::Update" << std::endl; } -void SampleSystem2::PostUpdate(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) +void SampleSystem2::PostUpdate(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) { ignmsg << "SampleSystem2::PostUpdate" << std::endl; } diff --git a/examples/scripts/distributed/primary.sdf b/examples/scripts/distributed/primary.sdf index 62961b3008..f82d32e582 100644 --- a/examples/scripts/distributed/primary.sdf +++ b/examples/scripts/distributed/primary.sdf @@ -3,7 +3,7 @@ + name="gz::sim::systems::SceneBroadcaster"> @@ -272,7 +272,7 @@ - + sphere diff --git a/examples/scripts/distributed/secondary.sdf b/examples/scripts/distributed/secondary.sdf index 13312dc93f..7e8bd8dde3 100644 --- a/examples/scripts/distributed/secondary.sdf +++ b/examples/scripts/distributed/secondary.sdf @@ -3,7 +3,7 @@ + name="gz::sim::systems::Physics"> @@ -197,7 +197,7 @@ - + sphere diff --git a/examples/scripts/distributed/standalone.sdf b/examples/scripts/distributed/standalone.sdf index 1b95237900..b5fe8a9f0d 100644 --- a/examples/scripts/distributed/standalone.sdf +++ b/examples/scripts/distributed/standalone.sdf @@ -3,11 +3,11 @@ + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Physics"> @@ -277,7 +277,7 @@ - + sphere diff --git a/examples/scripts/distributed_levels/distributed_levels.sdf.erb b/examples/scripts/distributed_levels/distributed_levels.sdf.erb index 1b0b16e663..42af9962d6 100644 --- a/examples/scripts/distributed_levels/distributed_levels.sdf.erb +++ b/examples/scripts/distributed_levels/distributed_levels.sdf.erb @@ -104,14 +104,14 @@ <% if secondary %> + name="gz::sim::systems::Physics"> <% end %> <% if primary %> + name="gz::sim::systems::SceneBroadcaster"> @@ -374,7 +374,7 @@ - + <% for shape in shapes diff --git a/examples/scripts/distributed_levels/primary.sdf b/examples/scripts/distributed_levels/primary.sdf index 9e79e592af..f0cc06c5fd 100644 --- a/examples/scripts/distributed_levels/primary.sdf +++ b/examples/scripts/distributed_levels/primary.sdf @@ -15,7 +15,7 @@ + name="gz::sim::systems::SceneBroadcaster"> @@ -918,7 +918,7 @@ - + diff --git a/examples/scripts/distributed_levels/secondary.sdf b/examples/scripts/distributed_levels/secondary.sdf index 394e3e797f..a12313ab94 100644 --- a/examples/scripts/distributed_levels/secondary.sdf +++ b/examples/scripts/distributed_levels/secondary.sdf @@ -13,7 +13,7 @@ + name="gz::sim::systems::Physics"> @@ -849,7 +849,7 @@ - + diff --git a/examples/scripts/distributed_levels/standalone.sdf b/examples/scripts/distributed_levels/standalone.sdf index b481243aba..419c7b33f4 100644 --- a/examples/scripts/distributed_levels/standalone.sdf +++ b/examples/scripts/distributed_levels/standalone.sdf @@ -13,14 +13,14 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -923,7 +923,7 @@ - + diff --git a/examples/scripts/log_video_recorder/log_video_recorder.sdf b/examples/scripts/log_video_recorder/log_video_recorder.sdf index 9734ebfc85..77130dbbba 100644 --- a/examples/scripts/log_video_recorder/log_video_recorder.sdf +++ b/examples/scripts/log_video_recorder/log_video_recorder.sdf @@ -11,15 +11,15 @@ + name='gz::sim::systems::SceneBroadcaster'> + name='gz::sim::systems::LogPlayback'> tmp_record + name='gz::sim::systems::LogVideoRecorder'> -5 -5 0.001 5 5 1 diff --git a/examples/standalone/custom_server/custom_server.cc b/examples/standalone/custom_server/custom_server.cc index 6746a30957..96abc26f1a 100644 --- a/examples/standalone/custom_server/custom_server.cc +++ b/examples/standalone/custom_server/custom_server.cc @@ -15,23 +15,23 @@ * */ -#include -#include +#include +#include ///////////////////////////////////////////////// int main() { // Set verbosity level - defaults to 1 if unset - ignition::common::Console::SetVerbosity(4); + gz::common::Console::SetVerbosity(4); // Object to pass custom configuration to the server - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; // Populate with some configuration, for example, the SDF file to load serverConfig.SetSdfFile("shapes.sdf"); // Instantiate server - ignition::gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); // Run the server unpaused for 100 iterations, blocking server.Run(true /*blocking*/, 100 /*iterations*/, false /*paused*/); diff --git a/examples/standalone/each_performance/each.cc b/examples/standalone/each_performance/each.cc index d6d278e307..cf225ea111 100644 --- a/examples/standalone/each_performance/each.cc +++ b/examples/standalone/each_performance/each.cc @@ -16,15 +16,15 @@ */ #include -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ////////////////////////////////////////////////// // This program will output performance comparison data between diff --git a/examples/standalone/external_ecm/external_ecm.cc b/examples/standalone/external_ecm/external_ecm.cc index 6c9fa3f354..7ed1526540 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) @@ -35,7 +35,7 @@ int main(int argc, char **argv) std::string world = argv[1]; // Create a transport node. - ignition::transport::Node node; + gz::transport::Node node; bool executed{false}; bool result{false}; @@ -46,7 +46,7 @@ int main(int argc, char **argv) << "] on service [" << service << "]..." << std::endl << std::endl; // Request and block - ignition::msgs::SerializedStepMap res; + gz::msgs::SerializedStepMap res; executed = node.Request(service, timeout, res, result); if (!executed) @@ -64,22 +64,22 @@ int main(int argc, char **argv) } // Instantiate an ECM and populate with data from message - ignition::gazebo::EntityComponentManager ecm; + gz::sim::EntityComponentManager ecm; ecm.SetState(res.state()); // Print some information - ecm.Each( - [&](const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::Name *_name) -> bool + ecm.Each( + [&](const gz::sim::Entity &_entity, + const gz::sim::components::Name *_name) -> bool { auto parentComp = - ecm.Component(_entity); + ecm.Component(_entity); std::string parentInfo; if (parentComp) { auto parentNameComp = - ecm.Component( + ecm.Component( parentComp->Data()); if (parentNameComp) diff --git a/examples/standalone/gtest_setup/command.sdf b/examples/standalone/gtest_setup/command.sdf index b7c3f7c690..f9fef43f7e 100644 --- a/examples/standalone/gtest_setup/command.sdf +++ b/examples/standalone/gtest_setup/command.sdf @@ -3,7 +3,7 @@ + name="gz::sim::systems::Physics"> @@ -19,7 +19,7 @@ + name="gz::sim::systems::VelocityControl"> diff --git a/examples/standalone/gtest_setup/command_TEST.cc b/examples/standalone/gtest_setup/command_TEST.cc index f8e4f4583f..34c3ec026b 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; @@ -35,31 +35,31 @@ using namespace std::chrono_literals; TEST(ExampleTests, Command) { // Maximum verbosity helps with debugging - ignition::common::Console::SetVerbosity(4); + gz::common::Console::SetVerbosity(4); // Instantiate test fixture - ignition::gazebo::TestFixture fixture("../command.sdf"); + gz::sim::TestFixture fixture("../command.sdf"); // Get the link that we'll be inspecting bool configured{false}; - ignition::gazebo::Link link; + gz::sim::Link link; fixture.OnConfigure( - [&link, &configured](const ignition::gazebo::Entity &_worldEntity, + [&link, &configured](const gz::sim::Entity &_worldEntity, const std::shared_ptr &/*_sdf*/, - ignition::gazebo::EntityComponentManager &_ecm, - ignition::gazebo::EventManager &/*_eventMgr*/) + gz::sim::EntityComponentManager &_ecm, + gz::sim::EventManager &/*_eventMgr*/) { - ignition::gazebo::World world(_worldEntity); + gz::sim::World world(_worldEntity); auto modelEntity = world.ModelByName(_ecm, "commanded"); - EXPECT_NE(ignition::gazebo::kNullEntity, modelEntity); + EXPECT_NE(gz::sim::kNullEntity, modelEntity); - auto model = ignition::gazebo::Model(modelEntity); + auto model = gz::sim::Model(modelEntity); auto linkEntity = model.LinkByName(_ecm, "link"); - EXPECT_NE(ignition::gazebo::kNullEntity, linkEntity); + EXPECT_NE(gz::sim::kNullEntity, linkEntity); - link = ignition::gazebo::Link(linkEntity); + link = gz::sim::Link(linkEntity); EXPECT_TRUE(link.Valid(_ecm)); // Tell Gazebo that we want to observe the link's velocity and acceleration @@ -75,12 +75,12 @@ TEST(ExampleTests, Command) // Check that link is falling due to gravity int iterations{0}; - ignition::math::Vector3d linVel; - ignition::math::Vector3d linAccel; + gz::math::Vector3d linVel; + gz::math::Vector3d linAccel; fixture.OnPostUpdate( [&]( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) { linVel = link.WorldLinearVelocity(_ecm).value(); EXPECT_DOUBLE_EQ(0.0, linVel.Y()); @@ -100,13 +100,13 @@ TEST(ExampleTests, Command) EXPECT_GT(0.0, linAccel.Z()); // Send velocity command - ignition::transport::Node node; + gz::transport::Node node; - ignition::msgs::Twist msg; + gz::msgs::Twist msg; auto linVelMsg = msg.mutable_linear(); linVelMsg->set_x(10); - auto pub = node.Advertise("/model/commanded/cmd_vel"); + auto pub = node.Advertise("/model/commanded/cmd_vel"); pub.Publish(msg); // Commands sent through transport are processed asynchronously and may diff --git a/examples/standalone/gtest_setup/gravity.sdf b/examples/standalone/gtest_setup/gravity.sdf index ee1161fa5f..43d46db809 100644 --- a/examples/standalone/gtest_setup/gravity.sdf +++ b/examples/standalone/gtest_setup/gravity.sdf @@ -3,7 +3,7 @@ + name="gz::sim::systems::Physics"> diff --git a/examples/standalone/gtest_setup/gravity_TEST.cc b/examples/standalone/gtest_setup/gravity_TEST.cc index 6bae7b3e78..cccc44c3c8 100644 --- a/examples/standalone/gtest_setup/gravity_TEST.cc +++ b/examples/standalone/gtest_setup/gravity_TEST.cc @@ -17,52 +17,52 @@ #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include ////////////////////////////////////////////////// // Test that an object falls due to gravity TEST(ExampleTests, Gravity) { // Maximum verbosity helps with debugging - ignition::common::Console::SetVerbosity(4); + gz::common::Console::SetVerbosity(4); // Instantiate test fixture. It starts a server and provides hooks that we'll // use to inspect the running simulation. - ignition::gazebo::TestFixture fixture("../gravity.sdf"); + gz::sim::TestFixture fixture("../gravity.sdf"); int iterations{0}; - ignition::gazebo::Entity modelEntity; - ignition::math::Vector3d gravity; + gz::sim::Entity modelEntity; + gz::math::Vector3d gravity; fixture. // Use configure callback to get values at startup OnConfigure( - [&modelEntity, &gravity](const ignition::gazebo::Entity &_worldEntity, + [&modelEntity, &gravity](const gz::sim::Entity &_worldEntity, const std::shared_ptr &/*_sdf*/, - ignition::gazebo::EntityComponentManager &_ecm, - ignition::gazebo::EventManager &/*_eventMgr*/) + gz::sim::EntityComponentManager &_ecm, + gz::sim::EventManager &/*_eventMgr*/) { // Get gravity - ignition::gazebo::World world(_worldEntity); + gz::sim::World world(_worldEntity); gravity = world.Gravity(_ecm).value(); // Get falling entity modelEntity = world.ModelByName(_ecm, "falling"); - EXPECT_NE(ignition::gazebo::kNullEntity, modelEntity); + EXPECT_NE(gz::sim::kNullEntity, modelEntity); }). // Use post-update callback to get values at the end of every iteration OnPostUpdate( [&iterations, &modelEntity, &gravity]( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) { // Inspect all model poses - auto pose = ignition::gazebo::worldPose(modelEntity, _ecm); + auto pose = gz::sim::worldPose(modelEntity, _ecm); EXPECT_DOUBLE_EQ(0.0, pose.Pos().X()); EXPECT_DOUBLE_EQ(0.0, pose.Pos().Y()); diff --git a/examples/standalone/joy_to_twist/README.md b/examples/standalone/joy_to_twist/README.md index 1dbc40f6a4..eee59ebda7 100644 --- a/examples/standalone/joy_to_twist/README.md +++ b/examples/standalone/joy_to_twist/README.md @@ -1,9 +1,9 @@ # Joy to Twist Standalone program that subscribes to -[ignition::msgs::Joy](https://gazebosim.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) +[gz::msgs::Joy](https://gazebosim.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) messages and converts publishes -[ignition::msgs::Twist](https://gazebosim.org/api/msgs/5.6/classignition_1_1msgs_1_1Twist.html) +[gz::msgs::Twist](https://gazebosim.org/api/msgs/5.6/classignition_1_1msgs_1_1Twist.html) messages according to user-defined configuration. ## Build diff --git a/examples/standalone/joy_to_twist/joy_to_twist.cc b/examples/standalone/joy_to_twist/joy_to_twist.cc index bae34786c0..c485ebb021 100644 --- a/examples/standalone/joy_to_twist/joy_to_twist.cc +++ b/examples/standalone/joy_to_twist/joy_to_twist.cc @@ -19,28 +19,28 @@ * Adapted from https://github.com/ros-teleop/teleop_twist_joy */ -#include +#include #include -ignition::transport::Node::Publisher cmdVelPub; +gz::transport::Node::Publisher cmdVelPub; int enableButton; int enableTurboButton; -ignition::math::Vector3d axisLinear; -ignition::math::Vector3d scaleLinear; -ignition::math::Vector3d scaleLinearTurbo; +gz::math::Vector3d axisLinear; +gz::math::Vector3d scaleLinear; +gz::math::Vector3d scaleLinearTurbo; -ignition::math::Vector3d axisAngular; -ignition::math::Vector3d scaleAngular; -ignition::math::Vector3d scaleAngularTurbo; +gz::math::Vector3d axisAngular; +gz::math::Vector3d scaleAngular; +gz::math::Vector3d scaleAngularTurbo; bool sentDisableMsg; ////////////////////////////////////////////////// -void OnJoy(const ignition::msgs::Joy &_msg) +void OnJoy(const gz::msgs::Joy &_msg) { - ignition::msgs::Twist cmdVelMsg; + gz::msgs::Twist cmdVelMsg; // Turbo mode if (enableTurboButton >= 0 && _msg.buttons(enableTurboButton)) @@ -116,10 +116,10 @@ int main(int argc, char **argv) auto plugin = sdf->Root()->GetElement("world")->GetElement("plugin"); // Setup transport - ignition::transport::Node node; + gz::transport::Node node; auto twistTopic = plugin->Get("twist_topic", "/cmd_vel").first; - cmdVelPub = node.Advertise(twistTopic); + cmdVelPub = node.Advertise(twistTopic); auto joyTopic = plugin->Get("joy_topic", "/joy").first; node.Subscribe("/joy", OnJoy); @@ -127,18 +127,18 @@ int main(int argc, char **argv) enableButton = plugin->Get("enable_button", 0).first; enableTurboButton = plugin->Get("enable_turbo_button", -1).first; - axisLinear = plugin->Get("axis_linear", - ignition::math::Vector3d::UnitX).first; - scaleLinear = plugin->Get("scale_linear", - ignition::math::Vector3d(0.5, 0, 0)).first; - scaleLinearTurbo = plugin->Get( + axisLinear = plugin->Get("axis_linear", + gz::math::Vector3d::UnitX).first; + scaleLinear = plugin->Get("scale_linear", + gz::math::Vector3d(0.5, 0, 0)).first; + scaleLinearTurbo = plugin->Get( "scale_linear_turbo", scaleLinear).first; - axisAngular = plugin->Get("axis_angular", - ignition::math::Vector3d::Zero).first; - scaleAngular = plugin->Get("scale_angular", - ignition::math::Vector3d(0, 0, 0.5)).first; - scaleAngularTurbo = plugin->Get( + axisAngular = plugin->Get("axis_angular", + gz::math::Vector3d::Zero).first; + scaleAngular = plugin->Get("scale_angular", + gz::math::Vector3d(0, 0, 0.5)).first; + scaleAngularTurbo = plugin->Get( "scale_angular_turbo", scaleAngular).first; sentDisableMsg = false; diff --git a/examples/standalone/joystick/README.md b/examples/standalone/joystick/README.md index 9292b6bd9e..e89aa04944 100644 --- a/examples/standalone/joystick/README.md +++ b/examples/standalone/joystick/README.md @@ -1,7 +1,7 @@ # Joystick Standalone program that publishes -[ignition::msgs::Joy](https://gazebosim.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) +[gz::msgs::Joy](https://gazebosim.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) messages from a joystick device using Ignition Transport. The mapping of joystick buttons to fields in the message is the same as [this](http://wiki.ros.org/joy). diff --git a/examples/standalone/joystick/joystick.cc b/examples/standalone/joystick/joystick.cc index 07c0139349..79b2e6844b 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 ////////////////////////////////////////////////// @@ -82,7 +82,7 @@ int main(int argc, char **argv) auto stickyButtons = joy->Get("sticky_buttons", false).first; // Read the amount of dead zone for the analog joystick - float deadzone = ignition::math::clamp( + float deadzone = gz::math::clamp( joy->Get("dead_zone", 0.05f).first, 0.0f, 0.9f); @@ -119,8 +119,8 @@ int main(int argc, char **argv) auto topic = joy->Get("topic", "/joy").first; // Create the publisher of joy messages - ignition::transport::Node node; - auto pub = node.Advertise(topic); + gz::transport::Node node; + auto pub = node.Advertise(topic); fd_set set; struct timeval tv; @@ -128,9 +128,9 @@ int main(int argc, char **argv) bool accumulate = false; bool accumulating = false; - ignition::msgs::Joy joyMsg; - ignition::msgs::Joy lastJoyMsg; - ignition::msgs::Joy stickyButtonsJoyMsg; + gz::msgs::Joy joyMsg; + gz::msgs::Joy lastJoyMsg; + gz::msgs::Joy stickyButtonsJoyMsg; auto stop{false}; while (!stop) @@ -181,7 +181,7 @@ int main(int argc, char **argv) // Update the button joyMsg.set_buttons(event.number, - !ignition::math::equal(value, 0.0f) ? 1 : 0); + !gz::math::equal(value, 0.0f) ? 1 : 0); // For initial events, wait a bit before sending to try to catch // all the initial events. diff --git a/examples/standalone/keyboard/keyboard.cc b/examples/standalone/keyboard/keyboard.cc index 625341fe7b..9bc84438a5 100644 --- a/examples/standalone/keyboard/keyboard.cc +++ b/examples/standalone/keyboard/keyboard.cc @@ -24,11 +24,11 @@ */ -#include -#include +#include +#include #include -#include -#include +#include +#include #include #include #include @@ -48,12 +48,12 @@ #define KEYCODE_W 0x77 -ignition::transport::Node::Publisher cmdVelPub; -ignition::transport::Node::Publisher cmdVelPub2; +gz::transport::Node::Publisher cmdVelPub; +gz::transport::Node::Publisher cmdVelPub2; -ignition::math::Vector3d scaleLinear; +gz::math::Vector3d scaleLinear; -ignition::math::Vector3d scaleAngular; +gz::math::Vector3d scaleAngular; class KeyboardTeleop @@ -175,11 +175,11 @@ void KeyboardTeleop::KeyLoop() break; } - ignition::msgs::Twist cmdVelMsg; + gz::msgs::Twist cmdVelMsg; cmdVelMsg.mutable_linear()->set_x(lScale * linear); cmdVelMsg.mutable_angular()->set_z(aScale * angular); - ignition::msgs::Twist cmdVelMsg2; + gz::msgs::Twist cmdVelMsg2; cmdVelMsg2.mutable_linear()->set_x(lScale * linear2); cmdVelMsg2.mutable_angular()->set_z(aScale * angular2); @@ -221,19 +221,19 @@ int main(int argc, char** argv) auto plugin = sdf->Root()->GetElement("world")->GetElement("plugin"); // Set up transport - ignition::transport::Node node; + gz::transport::Node node; auto twistTopic = plugin->Get("twist_arrows", "/cmd_vel").first; - cmdVelPub = node.Advertise(twistTopic); + cmdVelPub = node.Advertise(twistTopic); auto twistTopic2 = plugin->Get("twist_wasd", "/cmd_vel").first; - cmdVelPub2 = node.Advertise(twistTopic2); + cmdVelPub2 = node.Advertise(twistTopic2); - scaleLinear = plugin->Get("scale_linear", - ignition::math::Vector3d(0.5, 0, 0)).first; + scaleLinear = plugin->Get("scale_linear", + gz::math::Vector3d(0.5, 0, 0)).first; - scaleAngular = plugin->Get("scale_angular", - ignition::math::Vector3d(0, 0, 0.5)).first; + scaleAngular = plugin->Get("scale_angular", + gz::math::Vector3d(0, 0, 0.5)).first; // Only linear X and angular Z are used diff --git a/examples/standalone/marker/marker.cc b/examples/standalone/marker/marker.cc index bc5f46953c..2a5071077d 100644 --- a/examples/standalone/marker/marker.cc +++ b/examples/standalone/marker/marker.cc @@ -15,26 +15,26 @@ * */ -#include -#include +#include +#include #include -#include +#include #include ///////////////////////////////////////////////// int main(int _argc, char **_argv) { - ignition::transport::Node node; + gz::transport::Node node; // Create the marker message - ignition::msgs::Marker markerMsg; - ignition::msgs::Material matMsg; + gz::msgs::Marker markerMsg; + gz::msgs::Material matMsg; markerMsg.set_ns("default"); markerMsg.set_id(0); - markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); - markerMsg.set_type(ignition::msgs::Marker::SPHERE); - markerMsg.set_visibility(ignition::msgs::Marker::GUI); + markerMsg.set_action(gz::msgs::Marker::ADD_MODIFY); + markerMsg.set_type(gz::msgs::Marker::SPHERE); + markerMsg.set_visibility(gz::msgs::Marker::GUI); // Set color to Blue markerMsg.mutable_material()->mutable_ambient()->set_r(0); @@ -47,40 +47,40 @@ int main(int _argc, char **_argv) markerMsg.mutable_material()->mutable_diffuse()->set_a(1); markerMsg.mutable_lifetime()->set_sec(2); markerMsg.mutable_lifetime()->set_nsec(0); - ignition::msgs::Set(markerMsg.mutable_scale(), - ignition::math::Vector3d(1.0, 1.0, 1.0)); + gz::msgs::Set(markerMsg.mutable_scale(), + gz::math::Vector3d(1.0, 1.0, 1.0)); // The rest of this function adds different shapes and/or modifies shapes. // Read the terminal statements to figure out what each node.Request // call accomplishes. std::cout << "Spawning a blue sphere with lifetime 2s\n"; - ignition::common::Time::Sleep(ignition::common::Time(4)); - ignition::msgs::Set(markerMsg.mutable_pose(), - ignition::math::Pose3d(2, 2, 0, 0, 0, 0)); + gz::common::Time::Sleep(gz::common::Time(4)); + gz::msgs::Set(markerMsg.mutable_pose(), + gz::math::Pose3d(2, 2, 0, 0, 0, 0)); node.Request("/marker", markerMsg); std::cout << "Sleeping for 2 seconds\n"; - ignition::common::Time::Sleep(ignition::common::Time(2)); + gz::common::Time::Sleep(gz::common::Time(2)); std::cout << "Spawning a black sphere at the origin with no lifetime\n"; - ignition::common::Time::Sleep(ignition::common::Time(4)); + gz::common::Time::Sleep(gz::common::Time(4)); markerMsg.set_id(1); - ignition::msgs::Set(markerMsg.mutable_pose(), - ignition::math::Pose3d::Zero); + gz::msgs::Set(markerMsg.mutable_pose(), + gz::math::Pose3d::Zero); markerMsg.mutable_material()->mutable_ambient()->set_b(0); markerMsg.mutable_material()->mutable_diffuse()->set_b(0); markerMsg.mutable_lifetime()->set_sec(0); node.Request("/marker", markerMsg); std::cout << "Moving the sphere to x=0, y=1, z=1\n"; - ignition::common::Time::Sleep(ignition::common::Time(4)); - ignition::msgs::Set(markerMsg.mutable_pose(), - ignition::math::Pose3d(0, 1, 1, 0, 0, 0)); + gz::common::Time::Sleep(gz::common::Time(4)); + gz::msgs::Set(markerMsg.mutable_pose(), + gz::math::Pose3d(0, 1, 1, 0, 0, 0)); node.Request("/marker", markerMsg); std::cout << "Shrinking the sphere\n"; - ignition::common::Time::Sleep(ignition::common::Time(4)); - ignition::msgs::Set(markerMsg.mutable_scale(), - ignition::math::Vector3d(0.2, 0.2, 0.2)); + gz::common::Time::Sleep(gz::common::Time(4)); + gz::msgs::Set(markerMsg.mutable_scale(), + gz::math::Vector3d(0.2, 0.2, 0.2)); node.Request("/marker", markerMsg); std::cout << "Changing the sphere to red\n"; @@ -90,7 +90,7 @@ int main(int _argc, char **_argv) markerMsg.mutable_material()->mutable_diffuse()->set_r(1); markerMsg.mutable_material()->mutable_diffuse()->set_g(0); markerMsg.mutable_material()->mutable_diffuse()->set_b(0); - ignition::common::Time::Sleep(ignition::common::Time(4)); + gz::common::Time::Sleep(gz::common::Time(4)); node.Request("/marker", markerMsg); std::cout << "Adding a green box\n"; @@ -100,137 +100,137 @@ int main(int _argc, char **_argv) markerMsg.mutable_material()->mutable_diffuse()->set_r(0); markerMsg.mutable_material()->mutable_diffuse()->set_g(1); markerMsg.mutable_material()->mutable_diffuse()->set_b(0); - ignition::common::Time::Sleep(ignition::common::Time(4)); + gz::common::Time::Sleep(gz::common::Time(4)); markerMsg.set_id(2); - markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); - markerMsg.set_type(ignition::msgs::Marker::BOX); - ignition::msgs::Set(markerMsg.mutable_scale(), - ignition::math::Vector3d(1.0, 1.0, 1.0)); - ignition::msgs::Set(markerMsg.mutable_pose(), - ignition::math::Pose3d(2, 0, .5, 0, 0, 0)); + markerMsg.set_action(gz::msgs::Marker::ADD_MODIFY); + markerMsg.set_type(gz::msgs::Marker::BOX); + gz::msgs::Set(markerMsg.mutable_scale(), + gz::math::Vector3d(1.0, 1.0, 1.0)); + gz::msgs::Set(markerMsg.mutable_pose(), + gz::math::Pose3d(2, 0, .5, 0, 0, 0)); node.Request("/marker", markerMsg); std::cout << "Changing the green box to a cylinder\n"; - ignition::common::Time::Sleep(ignition::common::Time(4)); - markerMsg.set_type(ignition::msgs::Marker::CYLINDER); + gz::common::Time::Sleep(gz::common::Time(4)); + markerMsg.set_type(gz::msgs::Marker::CYLINDER); node.Request("/marker", markerMsg); std::cout << "Connecting the sphere and cylinder with a line\n"; - ignition::common::Time::Sleep(ignition::common::Time(4)); + gz::common::Time::Sleep(gz::common::Time(4)); markerMsg.set_id(3); - ignition::msgs::Set(markerMsg.mutable_pose(), - ignition::math::Pose3d(0, 0, 0, 0, 0, 0)); - markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); - markerMsg.set_type(ignition::msgs::Marker::LINE_LIST); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(0.0, 1.0, 1.0)); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(2, 0, 0.5)); + gz::msgs::Set(markerMsg.mutable_pose(), + gz::math::Pose3d(0, 0, 0, 0, 0, 0)); + markerMsg.set_action(gz::msgs::Marker::ADD_MODIFY); + markerMsg.set_type(gz::msgs::Marker::LINE_LIST); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(0.0, 1.0, 1.0)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(2, 0, 0.5)); node.Request("/marker", markerMsg); std::cout << "Adding a square around the origin\n"; - ignition::common::Time::Sleep(ignition::common::Time(4)); + gz::common::Time::Sleep(gz::common::Time(4)); markerMsg.set_id(4); - markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); - markerMsg.set_type(ignition::msgs::Marker::LINE_STRIP); - ignition::msgs::Set(markerMsg.mutable_point(0), - ignition::math::Vector3d(0.5, 0.5, 0.05)); - ignition::msgs::Set(markerMsg.mutable_point(1), - ignition::math::Vector3d(0.5, -0.5, 0.05)); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(-0.5, -0.5, 0.05)); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(-0.5, 0.5, 0.05)); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(0.5, 0.5, 0.05)); + markerMsg.set_action(gz::msgs::Marker::ADD_MODIFY); + markerMsg.set_type(gz::msgs::Marker::LINE_STRIP); + gz::msgs::Set(markerMsg.mutable_point(0), + gz::math::Vector3d(0.5, 0.5, 0.05)); + gz::msgs::Set(markerMsg.mutable_point(1), + gz::math::Vector3d(0.5, -0.5, 0.05)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(-0.5, -0.5, 0.05)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(-0.5, 0.5, 0.05)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(0.5, 0.5, 0.05)); node.Request("/marker", markerMsg); std::cout << "Adding 100 points inside the square\n"; - ignition::common::Time::Sleep(ignition::common::Time(4)); + gz::common::Time::Sleep(gz::common::Time(4)); markerMsg.set_id(5); - markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); - markerMsg.set_type(ignition::msgs::Marker::POINTS); + markerMsg.set_action(gz::msgs::Marker::ADD_MODIFY); + markerMsg.set_type(gz::msgs::Marker::POINTS); markerMsg.clear_point(); for (int i = 0; i < 100; ++i) { - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d( - ignition::math::Rand::DblUniform(-0.49, 0.49), - ignition::math::Rand::DblUniform(-0.49, 0.49), + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d( + gz::math::Rand::DblUniform(-0.49, 0.49), + gz::math::Rand::DblUniform(-0.49, 0.49), 0.05)); } node.Request("/marker", markerMsg); std::cout << "Adding a semi-circular triangle fan\n"; - ignition::common::Time::Sleep(ignition::common::Time(4)); + gz::common::Time::Sleep(gz::common::Time(4)); markerMsg.set_id(6); - markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); - markerMsg.set_type(ignition::msgs::Marker::TRIANGLE_FAN); + markerMsg.set_action(gz::msgs::Marker::ADD_MODIFY); + markerMsg.set_type(gz::msgs::Marker::TRIANGLE_FAN); markerMsg.clear_point(); - ignition::msgs::Set(markerMsg.mutable_pose(), - ignition::math::Pose3d(0, 1.5, 0, 0, 0, 0)); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(0, 0, 0.05)); + gz::msgs::Set(markerMsg.mutable_pose(), + gz::math::Pose3d(0, 1.5, 0, 0, 0, 0)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(0, 0, 0.05)); double radius = 2; for (double t = 0; t <= M_PI; t+= 0.01) { - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(radius * cos(t), radius * sin(t), 0.05)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(radius * cos(t), radius * sin(t), 0.05)); } node.Request("/marker", markerMsg); std::cout << "Adding two triangles using a triangle list\n"; - ignition::common::Time::Sleep(ignition::common::Time(4)); + gz::common::Time::Sleep(gz::common::Time(4)); markerMsg.set_id(7); - markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); - markerMsg.set_type(ignition::msgs::Marker::TRIANGLE_LIST); + markerMsg.set_action(gz::msgs::Marker::ADD_MODIFY); + markerMsg.set_type(gz::msgs::Marker::TRIANGLE_LIST); markerMsg.clear_point(); - ignition::msgs::Set(markerMsg.mutable_pose(), - ignition::math::Pose3d(0, -1.5, 0, 0, 0, 0)); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(0, 0, 0.05)); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(1, 0, 0.05)); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(1, 1, 0.05)); + gz::msgs::Set(markerMsg.mutable_pose(), + gz::math::Pose3d(0, -1.5, 0, 0, 0, 0)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(0, 0, 0.05)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(1, 0, 0.05)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(1, 1, 0.05)); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(1, 1, 0.05)); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(2, 1, 0.05)); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(2, 2, 0.05)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(1, 1, 0.05)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(2, 1, 0.05)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(2, 2, 0.05)); node.Request("/marker", markerMsg); std::cout << "Adding a rectangular triangle strip\n"; - ignition::common::Time::Sleep(ignition::common::Time(4)); + gz::common::Time::Sleep(gz::common::Time(4)); markerMsg.set_id(8); - markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); - markerMsg.set_type(ignition::msgs::Marker::TRIANGLE_STRIP); + markerMsg.set_action(gz::msgs::Marker::ADD_MODIFY); + markerMsg.set_type(gz::msgs::Marker::TRIANGLE_STRIP); markerMsg.clear_point(); - ignition::msgs::Set(markerMsg.mutable_pose(), - ignition::math::Pose3d(-2, -2, 0, 0, 0, 0)); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(0, 0, 0.05)); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(1, 0, 0.05)); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(0, 1, 0.05)); + gz::msgs::Set(markerMsg.mutable_pose(), + gz::math::Pose3d(-2, -2, 0, 0, 0, 0)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(0, 0, 0.05)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(1, 0, 0.05)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(0, 1, 0.05)); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(1, 1, 0.05)); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(0, 2, 0.05)); - ignition::msgs::Set(markerMsg.add_point(), - ignition::math::Vector3d(1, 2, 0.05)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(1, 1, 0.05)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(0, 2, 0.05)); + gz::msgs::Set(markerMsg.add_point(), + gz::math::Vector3d(1, 2, 0.05)); node.Request("/marker", markerMsg); std::cout << "Adding multiple markers via /marker_array\n"; - ignition::common::Time::Sleep(ignition::common::Time(4)); + gz::common::Time::Sleep(gz::common::Time(4)); - ignition::msgs::Marker_V markerMsgs; - ignition::msgs::Boolean res; + gz::msgs::Marker_V markerMsgs; + gz::msgs::Boolean res; bool result; unsigned int timeout = 5000; @@ -238,9 +238,9 @@ int main(int _argc, char **_argv) auto markerMsg1 = markerMsgs.add_marker(); markerMsg1->set_ns("default"); markerMsg1->set_id(0); - markerMsg1->set_action(ignition::msgs::Marker::ADD_MODIFY); - markerMsg1->set_type(ignition::msgs::Marker::SPHERE); - markerMsg1->set_visibility(ignition::msgs::Marker::GUI); + markerMsg1->set_action(gz::msgs::Marker::ADD_MODIFY); + markerMsg1->set_type(gz::msgs::Marker::SPHERE); + markerMsg1->set_visibility(gz::msgs::Marker::GUI); // Set color to Blue markerMsg1->mutable_material()->mutable_ambient()->set_r(0); @@ -251,18 +251,18 @@ int main(int _argc, char **_argv) markerMsg1->mutable_material()->mutable_diffuse()->set_g(0); markerMsg1->mutable_material()->mutable_diffuse()->set_b(1); markerMsg1->mutable_material()->mutable_diffuse()->set_a(1); - ignition::msgs::Set(markerMsg1->mutable_scale(), - ignition::math::Vector3d(1.0, 1.0, 1.0)); - ignition::msgs::Set(markerMsg1->mutable_pose(), - ignition::math::Pose3d(3, 3, 0, 0, 0, 0)); + gz::msgs::Set(markerMsg1->mutable_scale(), + gz::math::Vector3d(1.0, 1.0, 1.0)); + gz::msgs::Set(markerMsg1->mutable_pose(), + gz::math::Pose3d(3, 3, 0, 0, 0, 0)); // Create second red box marker auto markerMsg2 = markerMsgs.add_marker(); markerMsg2->set_ns("default"); markerMsg2->set_id(0); - markerMsg2->set_action(ignition::msgs::Marker::ADD_MODIFY); - markerMsg2->set_type(ignition::msgs::Marker::BOX); - markerMsg2->set_visibility(ignition::msgs::Marker::GUI); + markerMsg2->set_action(gz::msgs::Marker::ADD_MODIFY); + markerMsg2->set_type(gz::msgs::Marker::BOX); + markerMsg2->set_visibility(gz::msgs::Marker::GUI); // Set color to Red markerMsg2->mutable_material()->mutable_ambient()->set_r(1); @@ -275,18 +275,18 @@ int main(int _argc, char **_argv) markerMsg2->mutable_material()->mutable_diffuse()->set_a(1); markerMsg2->mutable_lifetime()->set_sec(2); markerMsg2->mutable_lifetime()->set_nsec(0); - ignition::msgs::Set(markerMsg2->mutable_scale(), - ignition::math::Vector3d(1.0, 1.0, 1.0)); - ignition::msgs::Set(markerMsg2->mutable_pose(), - ignition::math::Pose3d(3, 3, 2, 0, 0, 0)); + gz::msgs::Set(markerMsg2->mutable_scale(), + gz::math::Vector3d(1.0, 1.0, 1.0)); + gz::msgs::Set(markerMsg2->mutable_pose(), + gz::math::Pose3d(3, 3, 2, 0, 0, 0)); // Create third green cylinder marker auto markerMsg3 = markerMsgs.add_marker(); markerMsg3->set_ns("default"); markerMsg3->set_id(0); - markerMsg3->set_action(ignition::msgs::Marker::ADD_MODIFY); - markerMsg3->set_type(ignition::msgs::Marker::CYLINDER); - markerMsg3->set_visibility(ignition::msgs::Marker::GUI); + markerMsg3->set_action(gz::msgs::Marker::ADD_MODIFY); + markerMsg3->set_type(gz::msgs::Marker::CYLINDER); + markerMsg3->set_visibility(gz::msgs::Marker::GUI); // Set color to Green markerMsg3->mutable_material()->mutable_ambient()->set_r(0); @@ -299,16 +299,16 @@ int main(int _argc, char **_argv) markerMsg3->mutable_material()->mutable_diffuse()->set_a(1); markerMsg3->mutable_lifetime()->set_sec(2); markerMsg3->mutable_lifetime()->set_nsec(0); - ignition::msgs::Set(markerMsg3->mutable_scale(), - ignition::math::Vector3d(1.0, 1.0, 1.0)); - ignition::msgs::Set(markerMsg3->mutable_pose(), - ignition::math::Pose3d(3, 3, 4, 0, 0, 0)); + gz::msgs::Set(markerMsg3->mutable_scale(), + gz::math::Vector3d(1.0, 1.0, 1.0)); + gz::msgs::Set(markerMsg3->mutable_pose(), + gz::math::Pose3d(3, 3, 4, 0, 0, 0)); // Publish the three created markers above simultaneously node.Request("/marker_array", markerMsgs, timeout, res, result); std::cout << "Deleting all the markers\n"; - ignition::common::Time::Sleep(ignition::common::Time(4)); - markerMsg.set_action(ignition::msgs::Marker::DELETE_ALL); + gz::common::Time::Sleep(gz::common::Time(4)); + markerMsg.set_action(gz::msgs::Marker::DELETE_ALL); node.Request("/marker", markerMsg); } diff --git a/examples/standalone/scene_requester/scene_requester.cc b/examples/standalone/scene_requester/scene_requester.cc index 6175a19742..bfe977280d 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) @@ -41,7 +41,7 @@ int main(int argc, char **argv) } // Create a transport node. - ignition::transport::Node node; + gz::transport::Node node; bool executed{false}; bool result{false}; @@ -53,7 +53,7 @@ int main(int argc, char **argv) // Request and block if (type == "graph") { - ignition::msgs::StringMsg res; + gz::msgs::StringMsg res; executed = node.Request(service, timeout, res, result); if (executed && result) @@ -61,7 +61,7 @@ int main(int argc, char **argv) } else { - ignition::msgs::Scene res; + gz::msgs::Scene res; executed = node.Request(service, timeout, res, result); if (executed && result) diff --git a/examples/worlds/3k_shapes.sdf b/examples/worlds/3k_shapes.sdf index ba5ea9298c..b0c9b4cace 100644 --- a/examples/worlds/3k_shapes.sdf +++ b/examples/worlds/3k_shapes.sdf @@ -10,15 +10,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/ackermann_steering.sdf b/examples/worlds/ackermann_steering.sdf index c9ac5973f7..e002de2f9a 100644 --- a/examples/worlds/ackermann_steering.sdf +++ b/examples/worlds/ackermann_steering.sdf @@ -20,15 +20,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -425,7 +425,7 @@ + name="gz::sim::systems::AckermannSteering"> front_left_wheel_joint rear_left_wheel_joint front_right_wheel_joint diff --git a/examples/worlds/actor.sdf b/examples/worlds/actor.sdf index b805eee94f..ffb66386ad 100644 --- a/examples/worlds/actor.sdf +++ b/examples/worlds/actor.sdf @@ -6,20 +6,20 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/actors_population.sdf.erb b/examples/worlds/actors_population.sdf.erb index 79d017e67d..466ff57301 100644 --- a/examples/worlds/actors_population.sdf.erb +++ b/examples/worlds/actors_population.sdf.erb @@ -10,15 +10,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/apply_joint_force.sdf b/examples/worlds/apply_joint_force.sdf index 1825eb7a4b..f9160e48c7 100644 --- a/examples/worlds/apply_joint_force.sdf +++ b/examples/worlds/apply_joint_force.sdf @@ -14,11 +14,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -145,7 +145,7 @@ + name="gz::sim::systems::ApplyJointForce"> j1 diff --git a/examples/worlds/apply_link_wrench.sdf b/examples/worlds/apply_link_wrench.sdf index 50e6c1b387..afa52ef573 100644 --- a/examples/worlds/apply_link_wrench.sdf +++ b/examples/worlds/apply_link_wrench.sdf @@ -27,15 +27,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::ApplyLinkWrench"> box model diff --git a/examples/worlds/breadcrumbs.sdf b/examples/worlds/breadcrumbs.sdf index 79cccff819..432c74329b 100644 --- a/examples/worlds/breadcrumbs.sdf +++ b/examples/worlds/breadcrumbs.sdf @@ -23,15 +23,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -343,7 +343,7 @@ + name="gz::sim::systems::DiffDrive"> front_left_wheel_joint rear_left_wheel_joint front_right_wheel_joint @@ -351,7 +351,7 @@ 1.25 0.3 - + /B1/deploy 3 @@ -394,7 +394,7 @@ - + /B2/deploy 2.0 3 diff --git a/examples/worlds/buoyancy.sdf b/examples/worlds/buoyancy.sdf index f9da7e090c..bab6cf4b5f 100644 --- a/examples/worlds/buoyancy.sdf +++ b/examples/worlds/buoyancy.sdf @@ -28,19 +28,19 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Buoyancy"> 1000 @@ -272,13 +272,13 @@ + name="gz::sim::systems::ApplyJointForce"> propeller_joint + name="gz::sim::systems::LiftDrag"> 1000 1.2535816618911175 -1.4326647564469914 @@ -295,7 +295,7 @@ + name="gz::sim::systems::LiftDrag"> 1000 1.2535816618911175 -1.4326647564469914 @@ -312,7 +312,7 @@ + name="gz::sim::systems::LiftDrag"> 1000 1.2535816618911175 @@ -330,7 +330,7 @@ + name="gz::sim::systems::LiftDrag"> 1000 1.2535816618911175 diff --git a/examples/worlds/camera_sensor.sdf b/examples/worlds/camera_sensor.sdf index cec60815ea..564ea7591c 100644 --- a/examples/worlds/camera_sensor.sdf +++ b/examples/worlds/camera_sensor.sdf @@ -10,20 +10,20 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/camera_video_record_dbl_pendulum.sdf b/examples/worlds/camera_video_record_dbl_pendulum.sdf index 21ba632227..52011be53c 100644 --- a/examples/worlds/camera_video_record_dbl_pendulum.sdf +++ b/examples/worlds/camera_video_record_dbl_pendulum.sdf @@ -23,19 +23,19 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Sensors"> ogre2 @@ -311,7 +311,7 @@ + name="gz::sim::systems::CameraVideoRecorder"> camera/record_video diff --git a/examples/worlds/collada_world_exporter.sdf b/examples/worlds/collada_world_exporter.sdf index cd4b089ddd..47b20fc35b 100644 --- a/examples/worlds/collada_world_exporter.sdf +++ b/examples/worlds/collada_world_exporter.sdf @@ -16,7 +16,7 @@ This example just exports simple shapes into a Collada file. To run use: + name="gz::sim::systems::ColladaWorldExporter"> diff --git a/examples/worlds/contact_sensor.sdf b/examples/worlds/contact_sensor.sdf index 6e84f1c29c..6902b30b0a 100644 --- a/examples/worlds/contact_sensor.sdf +++ b/examples/worlds/contact_sensor.sdf @@ -11,19 +11,19 @@ Run the following to print out contacts, + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Contact"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/conveyor.sdf b/examples/worlds/conveyor.sdf index 1c9bf44cbd..05e00923e1 100644 --- a/examples/worlds/conveyor.sdf +++ b/examples/worlds/conveyor.sdf @@ -15,15 +15,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -145,14 +145,14 @@ + name="gz::sim::systems::TrackController"> base_link + name="gz::sim::systems::TriggeredPublisher"> 87 @@ -163,7 +163,7 @@ + name="gz::sim::systems::TriggeredPublisher"> 88 @@ -174,7 +174,7 @@ + name="gz::sim::systems::TriggeredPublisher"> 83 diff --git a/examples/worlds/debug_shapes.sdf b/examples/worlds/debug_shapes.sdf index 10ed07430f..50fb0c4875 100644 --- a/examples/worlds/debug_shapes.sdf +++ b/examples/worlds/debug_shapes.sdf @@ -11,15 +11,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/depth_camera_sensor.sdf b/examples/worlds/depth_camera_sensor.sdf index e9c3afd2d8..5703af5584 100644 --- a/examples/worlds/depth_camera_sensor.sdf +++ b/examples/worlds/depth_camera_sensor.sdf @@ -10,16 +10,16 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre2 + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/detachable_joint.sdf b/examples/worlds/detachable_joint.sdf index c88799cda7..1aea0d3a24 100644 --- a/examples/worlds/detachable_joint.sdf +++ b/examples/worlds/detachable_joint.sdf @@ -24,15 +24,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -345,7 +345,7 @@ + name="gz::sim::systems::DiffDrive"> front_left_wheel_joint rear_left_wheel_joint front_right_wheel_joint @@ -353,19 +353,19 @@ 1.25 0.3 - + chassis B1 body /B1/detach - + chassis B2 body /B2/detach - + chassis B3 body diff --git a/examples/worlds/diff_drive.sdf b/examples/worlds/diff_drive.sdf index 647509944d..01773a9207 100644 --- a/examples/worlds/diff_drive.sdf +++ b/examples/worlds/diff_drive.sdf @@ -24,15 +24,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -246,7 +246,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint right_wheel_joint 1.25 @@ -426,7 +426,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint right_wheel_joint 1.25 diff --git a/examples/worlds/diff_drive_skid.sdf b/examples/worlds/diff_drive_skid.sdf index 4edf93497d..37b07b6a9d 100644 --- a/examples/worlds/diff_drive_skid.sdf +++ b/examples/worlds/diff_drive_skid.sdf @@ -20,15 +20,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -339,7 +339,7 @@ + name="gz::sim::systems::DiffDrive"> front_left_wheel_joint rear_left_wheel_joint front_right_wheel_joint diff --git a/examples/worlds/elevator.sdf b/examples/worlds/elevator.sdf index 77d01899cb..4b5797384d 100644 --- a/examples/worlds/elevator.sdf +++ b/examples/worlds/elevator.sdf @@ -20,16 +20,16 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre2 + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/empty.sdf b/examples/worlds/empty.sdf index 74fa85eca9..c435c5eb15 100644 --- a/examples/worlds/empty.sdf +++ b/examples/worlds/empty.sdf @@ -59,19 +59,19 @@ ign service -s /world/empty/remove \ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Contact"> diff --git a/examples/worlds/fuel.sdf b/examples/worlds/fuel.sdf index 2fc59f83db..d1bb152732 100644 --- a/examples/worlds/fuel.sdf +++ b/examples/worlds/fuel.sdf @@ -6,15 +6,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/fuel_textured_mesh.sdf b/examples/worlds/fuel_textured_mesh.sdf index f69c8b5aa3..69c9799a4f 100644 --- a/examples/worlds/fuel_textured_mesh.sdf +++ b/examples/worlds/fuel_textured_mesh.sdf @@ -18,20 +18,20 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre2 + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/gpu_lidar_retro_values_sensor.sdf b/examples/worlds/gpu_lidar_retro_values_sensor.sdf index f2d7a27c76..ff639a7b69 100644 --- a/examples/worlds/gpu_lidar_retro_values_sensor.sdf +++ b/examples/worlds/gpu_lidar_retro_values_sensor.sdf @@ -16,16 +16,16 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre2 + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/gpu_lidar_sensor.sdf b/examples/worlds/gpu_lidar_sensor.sdf index c8efaaefda..736c7574c1 100644 --- a/examples/worlds/gpu_lidar_sensor.sdf +++ b/examples/worlds/gpu_lidar_sensor.sdf @@ -11,16 +11,16 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre2 + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/grid.sdf b/examples/worlds/grid.sdf index b775544573..59c27f0c1b 100644 --- a/examples/worlds/grid.sdf +++ b/examples/worlds/grid.sdf @@ -10,19 +10,19 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Contact"> diff --git a/examples/worlds/import_mesh.sdf b/examples/worlds/import_mesh.sdf index b10e41ef5d..a323e31342 100644 --- a/examples/worlds/import_mesh.sdf +++ b/examples/worlds/import_mesh.sdf @@ -18,15 +18,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/joint_controller.sdf b/examples/worlds/joint_controller.sdf index 86e54350a7..12cde0f9a2 100644 --- a/examples/worlds/joint_controller.sdf +++ b/examples/worlds/joint_controller.sdf @@ -18,11 +18,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -156,7 +156,7 @@ + name="gz::sim::systems::JointController"> j1 5.0 @@ -243,7 +243,7 @@ + name="gz::sim::systems::JointController"> j1 true 0.2 diff --git a/examples/worlds/joint_position_controller.sdf b/examples/worlds/joint_position_controller.sdf index b2bd104509..efdc5d2481 100644 --- a/examples/worlds/joint_position_controller.sdf +++ b/examples/worlds/joint_position_controller.sdf @@ -12,11 +12,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -154,7 +154,7 @@ + name="gz::sim::systems::JointPositionController"> j1 rotor_cmd 1 diff --git a/examples/worlds/kinetic_energy_monitor.sdf b/examples/worlds/kinetic_energy_monitor.sdf index 30de44ede4..1ca7a1f733 100644 --- a/examples/worlds/kinetic_energy_monitor.sdf +++ b/examples/worlds/kinetic_energy_monitor.sdf @@ -15,15 +15,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -104,7 +104,7 @@ + name="gz::sim::systems::KineticEnergyMonitor"> sphere_link 100 diff --git a/examples/worlds/levels.sdf b/examples/worlds/levels.sdf index 4174bd6132..23dcb8cf27 100644 --- a/examples/worlds/levels.sdf +++ b/examples/worlds/levels.sdf @@ -13,15 +13,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -4004,7 +4004,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint right_wheel_joint 1.25 @@ -4182,7 +4182,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint right_wheel_joint 1.25 @@ -4192,7 +4192,7 @@ - + vehicle_red diff --git a/examples/worlds/levels_no_performers.sdf b/examples/worlds/levels_no_performers.sdf index fd35357a6e..e1ff8602a7 100644 --- a/examples/worlds/levels_no_performers.sdf +++ b/examples/worlds/levels_no_performers.sdf @@ -28,15 +28,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -4019,7 +4019,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint right_wheel_joint 1.25 @@ -4197,7 +4197,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint right_wheel_joint 1.25 @@ -4207,7 +4207,7 @@ - + 20 -40 2.5 0 0 0 diff --git a/examples/worlds/lift_drag.sdf b/examples/worlds/lift_drag.sdf index d9c1f73bec..ad758bbd8b 100644 --- a/examples/worlds/lift_drag.sdf +++ b/examples/worlds/lift_drag.sdf @@ -17,15 +17,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -248,11 +248,11 @@ + name="gz::sim::systems::JointStatePublisher"> + name="gz::sim::systems::LiftDrag"> 0.1 0.1 0.001 @@ -266,7 +266,7 @@ + name="gz::sim::systems::LiftDrag"> 0.1 0.1 0.001 @@ -280,7 +280,7 @@ + name="gz::sim::systems::ApplyJointForce"> rod_1_joint diff --git a/examples/worlds/lift_drag_battery.sdf b/examples/worlds/lift_drag_battery.sdf index afe4f8dbb9..d9fd9591b7 100644 --- a/examples/worlds/lift_drag_battery.sdf +++ b/examples/worlds/lift_drag_battery.sdf @@ -20,15 +20,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -252,11 +252,11 @@ + name="gz::sim::systems::JointStatePublisher"> + name="gz::sim::systems::LiftDrag"> 0.1 0.1 0.001 @@ -270,7 +270,7 @@ + name="gz::sim::systems::LiftDrag"> 0.1 0.1 0.001 @@ -284,11 +284,11 @@ + name="gz::sim::systems::ApplyJointForce"> rod_1_joint + name="gz::sim::systems::LinearBatteryPlugin"> linear_battery 4.2 diff --git a/examples/worlds/lights.sdf b/examples/worlds/lights.sdf index f1910f0ac7..5eea493852 100644 --- a/examples/worlds/lights.sdf +++ b/examples/worlds/lights.sdf @@ -10,15 +10,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/linear_battery_demo.sdf b/examples/worlds/linear_battery_demo.sdf index b141ba3735..dee09a5f6d 100644 --- a/examples/worlds/linear_battery_demo.sdf +++ b/examples/worlds/linear_battery_demo.sdf @@ -36,11 +36,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -261,7 +261,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint_green right_wheel_joint_green 1.25 @@ -269,7 +269,7 @@ + name="gz::sim::systems::LinearBatteryPlugin"> linear_battery 4.2 @@ -460,7 +460,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint_blue right_wheel_joint_blue 1.25 @@ -468,7 +468,7 @@ + name="gz::sim::systems::LinearBatteryPlugin"> linear_battery 12.592 12.592 diff --git a/examples/worlds/log_playback.sdf b/examples/worlds/log_playback.sdf index 7017ba53d1..fa776b85a7 100644 --- a/examples/worlds/log_playback.sdf +++ b/examples/worlds/log_playback.sdf @@ -13,11 +13,11 @@ + name='gz::sim::systems::SceneBroadcaster'> + name='gz::sim::systems::LogPlayback'> /tmp/log diff --git a/examples/worlds/log_record_dbl_pendulum.sdf b/examples/worlds/log_record_dbl_pendulum.sdf index c7d4d208df..25551a5114 100644 --- a/examples/worlds/log_record_dbl_pendulum.sdf +++ b/examples/worlds/log_record_dbl_pendulum.sdf @@ -18,19 +18,19 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::LogRecord"> diff --git a/examples/worlds/log_record_keyboard.sdf b/examples/worlds/log_record_keyboard.sdf index f8d55000cd..d00b53e0a0 100644 --- a/examples/worlds/log_record_keyboard.sdf +++ b/examples/worlds/log_record_keyboard.sdf @@ -15,15 +15,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::LogRecord"> @@ -244,7 +244,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint_green right_wheel_joint_green 1.25 @@ -422,7 +422,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint_blue right_wheel_joint_blue 1.25 diff --git a/examples/worlds/log_record_resources.sdf b/examples/worlds/log_record_resources.sdf index d258b89e40..bbdc1f26f4 100644 --- a/examples/worlds/log_record_resources.sdf +++ b/examples/worlds/log_record_resources.sdf @@ -11,15 +11,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::LogRecord"> diff --git a/examples/worlds/log_record_shapes.sdf b/examples/worlds/log_record_shapes.sdf index 39fb8797ba..d9335213ac 100644 --- a/examples/worlds/log_record_shapes.sdf +++ b/examples/worlds/log_record_shapes.sdf @@ -17,19 +17,19 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::LogRecord"> diff --git a/examples/worlds/logical_audio_sensor_plugin.sdf b/examples/worlds/logical_audio_sensor_plugin.sdf index a86a0656b0..f4616b78d5 100644 --- a/examples/worlds/logical_audio_sensor_plugin.sdf +++ b/examples/worlds/logical_audio_sensor_plugin.sdf @@ -34,15 +34,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -125,7 +125,7 @@ - + 1 .5 0 0 0 0 0 @@ -174,7 +174,7 @@ - + 1 0 0 0 0 0 0 @@ -223,7 +223,7 @@ - + 1 0 .5 0 0 0 0 @@ -266,7 +266,7 @@ - + 1 0.5 0.5 0.5 0 0 0 diff --git a/examples/worlds/logical_camera_sensor.sdf b/examples/worlds/logical_camera_sensor.sdf index f8eb3cccd0..9cd1398196 100644 --- a/examples/worlds/logical_camera_sensor.sdf +++ b/examples/worlds/logical_camera_sensor.sdf @@ -14,20 +14,20 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::LogicalCamera"> ogre2 + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/multicopter_velocity_control.sdf b/examples/worlds/multicopter_velocity_control.sdf index 75b98272cf..5731d251f8 100644 --- a/examples/worlds/multicopter_velocity_control.sdf +++ b/examples/worlds/multicopter_velocity_control.sdf @@ -30,19 +30,19 @@ You can use the velocity controller and command linear velocity and yaw angular + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::Sensors"> ogre2 @@ -93,7 +93,7 @@ You can use the velocity controller and command linear velocity and yaw angular + name="gz::sim::systems::MulticopterMotorModel"> X3 X3/rotor_0_joint X3/rotor_0 @@ -113,7 +113,7 @@ You can use the velocity controller and command linear velocity and yaw angular + name="gz::sim::systems::MulticopterMotorModel"> X3 X3/rotor_1_joint X3/rotor_1 @@ -133,7 +133,7 @@ You can use the velocity controller and command linear velocity and yaw angular + name="gz::sim::systems::MulticopterMotorModel"> X3 X3/rotor_2_joint X3/rotor_2 @@ -153,7 +153,7 @@ You can use the velocity controller and command linear velocity and yaw angular + name="gz::sim::systems::MulticopterMotorModel"> X3 X3/rotor_3_joint X3/rotor_3 @@ -173,7 +173,7 @@ You can use the velocity controller and command linear velocity and yaw angular + name="gz::sim::systems::MulticopterVelocityControl"> X3 gazebo/command/twist enable @@ -218,7 +218,7 @@ You can use the velocity controller and command linear velocity and yaw angular + name="gz::sim::systems::MulticopterMotorModel"> X4 rotor_0_joint rotor_0 @@ -238,7 +238,7 @@ You can use the velocity controller and command linear velocity and yaw angular velocity + name="gz::sim::systems::MulticopterMotorModel"> X4 rotor_1_joint rotor_1 @@ -258,7 +258,7 @@ You can use the velocity controller and command linear velocity and yaw angular velocity + name="gz::sim::systems::MulticopterMotorModel"> X4 rotor_2_joint rotor_2 @@ -278,7 +278,7 @@ You can use the velocity controller and command linear velocity and yaw angular velocity + name="gz::sim::systems::MulticopterMotorModel"> X4 rotor_3_joint rotor_3 @@ -298,7 +298,7 @@ You can use the velocity controller and command linear velocity and yaw angular velocity + name="gz::sim::systems::MulticopterMotorModel"> X4 rotor_4_joint rotor_4 @@ -318,7 +318,7 @@ You can use the velocity controller and command linear velocity and yaw angular velocity + name="gz::sim::systems::MulticopterMotorModel"> X4 rotor_5_joint rotor_5 @@ -340,7 +340,7 @@ You can use the velocity controller and command linear velocity and yaw angular + name="gz::sim::systems::MulticopterVelocityControl"> X4 gazebo/command/twist enable diff --git a/examples/worlds/nested_model.sdf b/examples/worlds/nested_model.sdf index 34310a6361..d79bb528bc 100644 --- a/examples/worlds/nested_model.sdf +++ b/examples/worlds/nested_model.sdf @@ -7,16 +7,16 @@ + name="gz::sim::systems::Physics"> libignition-physics-tpe-plugin.so + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/pendulum_links.sdf b/examples/worlds/pendulum_links.sdf index 1927835b7a..19dc48d17f 100644 --- a/examples/worlds/pendulum_links.sdf +++ b/examples/worlds/pendulum_links.sdf @@ -17,15 +17,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -268,7 +268,7 @@ + name="gz::sim::systems::VelocityControl"> base upper_link lower_link diff --git a/examples/worlds/performer_detector.sdf b/examples/worlds/performer_detector.sdf index 5350526c03..f155974e02 100644 --- a/examples/worlds/performer_detector.sdf +++ b/examples/worlds/performer_detector.sdf @@ -21,15 +21,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -342,7 +342,7 @@ + name="gz::sim::systems::DiffDrive"> front_left_wheel_joint rear_left_wheel_joint front_right_wheel_joint @@ -373,7 +373,7 @@ + name="gz::sim::systems::PerformerDetector"> /performer_detector @@ -401,7 +401,7 @@ false - + /performer_detector @@ -412,7 +412,7 @@ - + vehicle_blue diff --git a/examples/worlds/plane_propeller_demo.sdf b/examples/worlds/plane_propeller_demo.sdf index 6de0ef7e92..140780920d 100644 --- a/examples/worlds/plane_propeller_demo.sdf +++ b/examples/worlds/plane_propeller_demo.sdf @@ -14,15 +14,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -437,7 +437,7 @@ + name="gz::sim::systems::LiftDrag"> 0.2 10.000 0.0001 @@ -455,7 +455,7 @@ + name="gz::sim::systems::LiftDrag"> 0.2 10.000 0.0001 @@ -786,7 +786,7 @@ + name="gz::sim::systems::LiftDrag"> 0.1 4.000 0.001 @@ -804,7 +804,7 @@ + name="gz::sim::systems::LiftDrag"> 0.1 4.000 0.001 @@ -822,7 +822,7 @@ + name="gz::sim::systems::LiftDrag"> 0.02 4.000 0.001 @@ -840,7 +840,7 @@ + name="gz::sim::systems::LiftDrag"> 0.02 4.000 0.001 @@ -858,7 +858,7 @@ + name="gz::sim::systems::LiftDrag"> 0.00 2.000 @@ -877,7 +877,7 @@ + name="gz::sim::systems::ApplyJointForce"> rod_1_joint diff --git a/examples/worlds/pose_publisher.sdf b/examples/worlds/pose_publisher.sdf index 2c9947512e..67c9d6a8d2 100644 --- a/examples/worlds/pose_publisher.sdf +++ b/examples/worlds/pose_publisher.sdf @@ -15,15 +15,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -267,7 +267,7 @@ + name="gz::sim::systems::PosePublisher"> true false false diff --git a/examples/worlds/quadcopter.sdf b/examples/worlds/quadcopter.sdf index 89a507d1ff..19af3f02f7 100644 --- a/examples/worlds/quadcopter.sdf +++ b/examples/worlds/quadcopter.sdf @@ -19,19 +19,19 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::Sensors"> ogre2 @@ -82,7 +82,7 @@ + name="gz::sim::systems::MulticopterMotorModel"> X3 X3/rotor_0_joint X3/rotor_0 @@ -102,7 +102,7 @@ + name="gz::sim::systems::MulticopterMotorModel"> X3 X3/rotor_1_joint X3/rotor_1 @@ -122,7 +122,7 @@ + name="gz::sim::systems::MulticopterMotorModel"> X3 X3/rotor_2_joint X3/rotor_2 @@ -142,7 +142,7 @@ + name="gz::sim::systems::MulticopterMotorModel"> X3 X3/rotor_3_joint X3/rotor_3 diff --git a/examples/worlds/rolling_shapes.sdf b/examples/worlds/rolling_shapes.sdf index 6c7d287631..eba9b06f48 100644 --- a/examples/worlds/rolling_shapes.sdf +++ b/examples/worlds/rolling_shapes.sdf @@ -10,15 +10,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/sensors.sdf b/examples/worlds/sensors.sdf index eefd6a8ee8..0cb7c70d8c 100644 --- a/examples/worlds/sensors.sdf +++ b/examples/worlds/sensors.sdf @@ -17,31 +17,31 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::AirPressure"> + name="gz::sim::systems::Altimeter"> + name="gz::sim::systems::Imu"> + name="gz::sim::systems::Magnetometer"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/sensors_demo.sdf b/examples/worlds/sensors_demo.sdf index 79c4df0fd1..f4d3cb176f 100644 --- a/examples/worlds/sensors_demo.sdf +++ b/examples/worlds/sensors_demo.sdf @@ -10,16 +10,16 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre2 + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/shapes_bitmask.sdf b/examples/worlds/shapes_bitmask.sdf index 342ccb99aa..aad9a6f0d1 100644 --- a/examples/worlds/shapes_bitmask.sdf +++ b/examples/worlds/shapes_bitmask.sdf @@ -18,15 +18,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/shapes_population.sdf.erb b/examples/worlds/shapes_population.sdf.erb index 4c91b1206b..b4f0ecf534 100644 --- a/examples/worlds/shapes_population.sdf.erb +++ b/examples/worlds/shapes_population.sdf.erb @@ -10,15 +10,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/thermal_camera.sdf b/examples/worlds/thermal_camera.sdf index 325139a1c0..b0596ea84f 100644 --- a/examples/worlds/thermal_camera.sdf +++ b/examples/worlds/thermal_camera.sdf @@ -12,20 +12,20 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre2 + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::UserCommands"> @@ -192,7 +192,7 @@ + name="gz::sim::systems::Thermal"> 200.0 @@ -234,7 +234,7 @@ + name="gz::sim::systems::Thermal"> 600.0 @@ -278,7 +278,7 @@ + name="gz::sim::systems::Thermal"> 400.0 diff --git a/examples/worlds/touch_plugin.sdf b/examples/worlds/touch_plugin.sdf index 7497a15984..a19161caf1 100644 --- a/examples/worlds/touch_plugin.sdf +++ b/examples/worlds/touch_plugin.sdf @@ -23,15 +23,15 @@ The output of the plugin is via + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Contact"> + name="gz::sim::systems::SceneBroadcaster"> @@ -104,7 +104,7 @@ The output of the plugin is via + name="gz::sim::systems::TouchPlugin"> green_box_for_white white_touches_only_green diff --git a/examples/worlds/track_drive.sdf b/examples/worlds/track_drive.sdf index 9680cd01e5..83d398bb63 100644 --- a/examples/worlds/track_drive.sdf +++ b/examples/worlds/track_drive.sdf @@ -24,19 +24,19 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Imu"> @@ -1051,7 +1051,7 @@ + name="gz::sim::systems::DiffDrive"> left_track_wheel1_j right_track_wheel1_j left_track_wheel2_j @@ -2072,7 +2072,7 @@ + name="gz::sim::systems::DiffDrive"> left_track_wheel1_j right_track_wheel1_j left_track_wheel2_j diff --git a/examples/worlds/tracked_vehicle_simple.sdf b/examples/worlds/tracked_vehicle_simple.sdf index fbc77a7d0d..9092046fe4 100644 --- a/examples/worlds/tracked_vehicle_simple.sdf +++ b/examples/worlds/tracked_vehicle_simple.sdf @@ -11,9 +11,9 @@ 0.004 1.0 - - - + + + 1 1 1 1 0.8 0.8 0.8 1 @@ -1067,7 +1067,7 @@ - + left_track front_left_flipper rear_left_flipper @@ -1079,33 +1079,33 @@ 0.5 - + left_track -1.0 1.0 - + right_track -1.0 1.0 - + front_left_flipper -1.0 1.0 - + rear_left_flipper -1.0 1.0 - + front_right_flipper -1.0 1.0 - + rear_right_flipper -1.0 1.0 @@ -1113,7 +1113,7 @@ + name="gz::sim::systems::TriggeredPublisher"> 87 @@ -1124,7 +1124,7 @@ + name="gz::sim::systems::TriggeredPublisher"> 88 @@ -1135,7 +1135,7 @@ + name="gz::sim::systems::TriggeredPublisher"> 83 @@ -1146,7 +1146,7 @@ + name="gz::sim::systems::TriggeredPublisher"> 65 @@ -1157,7 +1157,7 @@ + name="gz::sim::systems::TriggeredPublisher"> 68 @@ -1168,7 +1168,7 @@ + name="gz::sim::systems::TriggeredPublisher"> 81 @@ -1179,7 +1179,7 @@ + name="gz::sim::systems::TriggeredPublisher"> 69 @@ -1190,7 +1190,7 @@ + name="gz::sim::systems::TriggeredPublisher"> 90 @@ -1201,7 +1201,7 @@ + name="gz::sim::systems::TriggeredPublisher"> 67 diff --git a/examples/worlds/triggered_publisher.sdf b/examples/worlds/triggered_publisher.sdf index e9812361c1..9fcafb7832 100644 --- a/examples/worlds/triggered_publisher.sdf +++ b/examples/worlds/triggered_publisher.sdf @@ -19,23 +19,23 @@ moment the box hits the ground, the second box should start falling. + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Contact"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Altimeter"> @@ -413,7 +413,7 @@ moment the box hits the ground, the second box should start falling. + name="gz::sim::systems::DiffDrive"> front_left_wheel_joint rear_left_wheel_joint front_right_wheel_joint @@ -446,19 +446,19 @@ moment the box hits the ground, the second box should start falling. + name="gz::sim::systems::TouchPlugin"> vehicle_blue trigger true - + body box1 box_body /box1/detach - + body box2 box_body @@ -513,19 +513,19 @@ moment the box hits the ground, the second box should start falling. - + linear: {x: 3} - + data: true - + -7.5 diff --git a/examples/worlds/trisphere_cycle_wheel_slip.sdf b/examples/worlds/trisphere_cycle_wheel_slip.sdf index 7738361315..4042c2191a 100644 --- a/examples/worlds/trisphere_cycle_wheel_slip.sdf +++ b/examples/worlds/trisphere_cycle_wheel_slip.sdf @@ -16,15 +16,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -514,7 +514,7 @@ + name="gz::sim::systems::WheelSlip"> 0.15 0 @@ -911,7 +911,7 @@ + name="gz::sim::systems::WheelSlip"> 1 1 diff --git a/examples/worlds/tunnel.sdf b/examples/worlds/tunnel.sdf index a61e9546ff..d7a447b3b2 100644 --- a/examples/worlds/tunnel.sdf +++ b/examples/worlds/tunnel.sdf @@ -18,15 +18,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -903,7 +903,7 @@ 0 0 .2 0 0 0 - + x1 2 2 2 diff --git a/examples/worlds/velocity_control.sdf b/examples/worlds/velocity_control.sdf index 71c30486f9..bf296c6b83 100644 --- a/examples/worlds/velocity_control.sdf +++ b/examples/worlds/velocity_control.sdf @@ -18,15 +18,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -309,7 +309,7 @@ + name="gz::sim::systems::VelocityControl"> @@ -484,7 +484,7 @@ + name="gz::sim::systems::VelocityControl"> 0.3 0 0 0 0 -0.1 diff --git a/examples/worlds/video_record_dbl_pendulum.sdf b/examples/worlds/video_record_dbl_pendulum.sdf index ddbe423ff3..1a1dc02523 100644 --- a/examples/worlds/video_record_dbl_pendulum.sdf +++ b/examples/worlds/video_record_dbl_pendulum.sdf @@ -17,15 +17,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/worlds/wind.sdf b/examples/worlds/wind.sdf index d5d58b73b7..c5f34a68b2 100644 --- a/examples/worlds/wind.sdf +++ b/examples/worlds/wind.sdf @@ -11,15 +11,15 @@ Example: + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -434,7 +434,7 @@ Example: + name="gz::sim::systems::WindEffects"> 1 diff --git a/examples/worlds/world_joint.sdf b/examples/worlds/world_joint.sdf index a0c75fe327..9c8017c536 100644 --- a/examples/worlds/world_joint.sdf +++ b/examples/worlds/world_joint.sdf @@ -10,15 +10,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/include/CMakeLists.txt b/include/CMakeLists.txt index 25ec89762d..4b2bdd7bb1 100644 --- a/include/CMakeLists.txt +++ b/include/CMakeLists.txt @@ -1 +1,2 @@ -add_subdirectory(ignition) +add_subdirectory(gz) +install(DIRECTORY ignition DESTINATION ${IGN_INCLUDE_INSTALL_DIR_FULL}) diff --git a/include/gz/CMakeLists.txt b/include/gz/CMakeLists.txt new file mode 100644 index 0000000000..e4f01467e8 --- /dev/null +++ b/include/gz/CMakeLists.txt @@ -0,0 +1 @@ +add_subdirectory(sim) diff --git a/include/ignition/gazebo/CMakeLists.txt b/include/gz/sim/CMakeLists.txt similarity index 100% rename from include/ignition/gazebo/CMakeLists.txt rename to include/gz/sim/CMakeLists.txt diff --git a/include/gz/sim/Conversions.hh b/include/gz/sim/Conversions.hh new file mode 100644 index 0000000000..3f415d3a68 --- /dev/null +++ b/include/gz/sim/Conversions.hh @@ -0,0 +1,665 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#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 +#include +#include +#include +#include +#include +#include + +#include "gz/sim/config.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Types.hh" + +namespace ignition +{ + namespace gazebo + { + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + /// \brief Helper function that sets a mutable msgs::SensorNoise object + /// to the values contained in a sdf::Noise object. + /// \param[out] _msg SensorNoise message to set. + /// \param[in] _sdf SDF Noise object. + void IGNITION_GAZEBO_VISIBLE + set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf); + + /// \brief Helper function that sets a mutable msgs::WorldStatistics object + /// to the values contained in a gz::sim::UpdateInfo object. + /// \param[out] _msg WorldStatistics message to set. + /// \param[in] _in UpdateInfo object. + void IGNITION_GAZEBO_VISIBLE + set(msgs::WorldStatistics *_msg, const UpdateInfo &_in); + + /// \brief Helper function that sets a mutable msgs::Time object + /// to the values contained in a std::chrono::steady_clock::duration + /// object. + /// \param[out] _msg Time message to set. + /// \param[in] _in Chrono duration object. + void IGNITION_GAZEBO_VISIBLE + set(msgs::Time *_msg, const std::chrono::steady_clock::duration &_in); + + /// \brief Generic conversion from an SDF geometry to another type. + /// \param[in] _in SDF geometry. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const sdf::Geometry &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from an SDF geometry to a geometry + /// message. + /// \param[in] _in SDF geometry. + /// \return Geometry message. + template<> + msgs::Geometry convert(const sdf::Geometry &_in); + + /// \brief Generic conversion from a msgs Pose to another type. + /// \param[in] _in msgs Pose + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const msgs::Pose &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion for msgs Pose to math Pose + /// \param[in] _in msgs Pose + /// \return math Pose. + template<> + math::Pose3d convert(const msgs::Pose &_in); + + /// \brief Generic conversion from a geometry message to another type. + /// \param[in] _in Geometry message. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const msgs::Geometry &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from a geometry message to a geometry + /// SDF object. + /// \param[in] _in Geometry message. + /// \return SDF geometry. + template<> + sdf::Geometry convert(const msgs::Geometry &_in); + + /// \brief Generic conversion from an SDF material to another type. + /// \param[in] _in SDF material. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const sdf::Material &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from an SDF material to a material + /// message. + /// \param[in] _in SDF material. + /// \return Material message. + template<> + msgs::Material convert(const sdf::Material &_in); + + /// \brief Generic conversion from a material message to another type. + /// \param[in] _in Material message. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const msgs::Material &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from a material message to a material + /// SDF object. + /// \param[in] _in Material message. + /// \return SDF material. + template<> + sdf::Material convert(const msgs::Material &_in); + + /// \brief Generic conversion from an SDF actor to another type. + /// \param[in] _in SDF actor. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const sdf::Actor &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from an SDF actor to an actor + /// message. + /// \param[in] _in SDF actor. + /// \return Actor message. + template<> + msgs::Actor convert(const sdf::Actor &_in); + + /// \brief Generic conversion from an actor message to another type. + /// \param[in] _in Actor message. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const msgs::Actor& _in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from an actor message to an actor + /// SDF object. + /// \param[in] _in Actor message. + /// \return Actor SDF object. + template<> + sdf::Actor convert(const msgs::Actor &_in); + + /// \brief Generic conversion from an SDF light to another type. + /// \param[in] _in SDF light. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const sdf::Light &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from an SDF light to a light + /// message. + /// \param[in] _in SDF light. + /// \return Light message. + template<> + msgs::Light convert(const sdf::Light &_in); + + + /// \brief Generic conversion from a light message to another type. + /// \param[in] _in Light message. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const msgs::Light& _in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from a light message to a light + /// SDF object. + /// \param[in] _in Light message. + /// \return Light SDF object. + template<> + sdf::Light convert(const msgs::Light &_in); + + /// \brief Generic conversion from an SDF gui to another type. + /// \param[in] _in SDF gui. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const sdf::Gui &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from an SDF gui to a gui message. + /// \param[in] _in SDF gui. + /// \return Gui message. + template<> + msgs::GUI convert(const sdf::Gui &_in); + + /// \brief Generic conversion from a steady clock duration to another type. + /// \param[in] _in Steady clock duration. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const std::chrono::steady_clock::duration &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from a steady clock duration to a time + /// message. + /// \param[in] _in Steady clock duration. + /// \return Ignition time message. + template<> + msgs::Time convert(const std::chrono::steady_clock::duration &_in); + + /// \brief Generic conversion from a time message to another type. + /// \param[in] _in Time message. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const msgs::Time &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from a time message to a steady clock + /// duration. + /// \param[in] _in Time message. + /// \return Steady clock duration. + template<> + std::chrono::steady_clock::duration convert(const msgs::Time &_in); + + /// \brief Generic conversion from a math inertial to another type. + /// \param[in] _in Math inertial. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const math::Inertiald &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from a math inertial to an inertial + /// message. + /// \param[in] _in Math inertial. + /// \return Inertial message. + template<> + msgs::Inertial convert(const math::Inertiald &_in); + + /// \brief Generic conversion from an inertial message to another type. + /// \param[in] _in Inertial message. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const msgs::Inertial &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from an inertial message to an inertial + /// math object. + /// \param[in] _in Inertial message. + /// \return math inertial. + template<> + math::Inertiald convert(const msgs::Inertial &_in); + + /// \brief Generic conversion from an SDF joint axis to another type. + /// \param[in] _in SDF joint axis. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const sdf::JointAxis &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from an SDF joint axis to an axis + /// message. + /// \param[in] _in SDF joint axis. + /// \return Axis message. + template<> + msgs::Axis convert(const sdf::JointAxis &_in); + + /// \brief Generic conversion from an axis message to another type. + /// \param[in] _in Axis message. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const msgs::Axis &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from an axis message to a joint axis + /// SDF object. + /// \param[in] _in Axis message. + /// \return SDF joint axis. + template<> + sdf::JointAxis convert(const msgs::Axis &_in); + + /// \brief Generic conversion from an SDF scene to another type. + /// \param[in] _in SDF scene. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const sdf::Scene &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from an SDF scene to a scene message + /// \param[in] _in SDF scene. + /// \return Scene message. + template<> + msgs::Scene convert(const sdf::Scene &_in); + + /// \brief Generic conversion from a scene message to another type. + /// \param[in] _in Scene message. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const msgs::Scene &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from a scene message to a scene + /// SDF object. + /// \param[in] _in Scene message. + /// \return SDF scene. + template<> + sdf::Scene convert(const msgs::Scene &_in); + + /// \brief Generic conversion from an SDF atmosphere to another type. + /// \param[in] _in SDF atmosphere. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const sdf::Atmosphere &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from an SDF atmosphere to an atmosphere + /// message + /// \param[in] _in SDF atmosphere. + /// \return Atmosphere message. + template<> + msgs::Atmosphere convert(const sdf::Atmosphere &_in); + + /// \brief Generic conversion from an atmosphere message to another type. + /// \param[in] _in Atmosphere message. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const msgs::Atmosphere &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from an atmosphere message to an + /// atmosphere SDF object. + /// \param[in] _in Atmosphere message. + /// \return SDF scene. + template<> + sdf::Atmosphere convert(const msgs::Atmosphere &_in); + + + /// \brief Generic conversion from an SDF Physics to another type. + /// \param[in] _in SDF Physics. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const sdf::Physics &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from an SDF physics to a physics + /// message. + /// \param[in] _in SDF physics. + /// \return Physics message. + template<> + msgs::Physics convert(const sdf::Physics &_in); + + /// \brief Generic conversion from a physics message to another type. + /// \param[in] _in Physics message. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const msgs::Physics &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from a physics message to a physics + /// SDF object. + /// \param[in] _in Physics message. + /// \return SDF physics. + template<> + sdf::Physics convert(const msgs::Physics &_in); + + + /// \brief Generic conversion from an SDF Sensor to another type. + /// \param[in] _in SDF Sensor. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const sdf::Sensor &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from an SDF sensor to a sensor + /// message. + /// \param[in] _in SDF sensor. + /// \return Sensor message. + template<> + msgs::Sensor convert(const sdf::Sensor &_in); + + /// \brief Generic conversion from a sensor message to another type. + /// \param[in] _in Sensor message. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const msgs::Sensor &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from a sensor message to a sensor + /// SDF object. + /// \param[in] _in Sensor message. + /// \return SDF sensor. + template<> + sdf::Sensor convert(const msgs::Sensor &_in); + + /// \brief Generic conversion from a sensor noise message to another type. + /// \param[in] _in SensorNoise message. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const msgs::SensorNoise &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from a sensor noise message to a noise + /// SDF object. + /// \param[in] _in Sensor noise message. + /// \return SDF noise. + template<> + sdf::Noise convert(const msgs::SensorNoise &_in); + + /// \brief Generic conversion from a world statistics message to another + /// type. + /// \param[in] _in WorldStatistics message. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const msgs::WorldStatistics &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from a world statistics message to an + /// `gz::sim::UpdateInfo` object. + /// \param[in] _in WorldStatistics message. + /// \return Update info. + template<> + UpdateInfo convert(const msgs::WorldStatistics &_in); + + /// \brief Generic conversion from update info to another type. + /// \param[in] _in Update info. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const UpdateInfo &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from update info to a world statistics + /// message. + /// \param[in] _in Update info. + /// \return World statistics message. + template<> + msgs::WorldStatistics convert(const UpdateInfo &_in); + + /// \brief Generic conversion from an SDF collision to another type. + /// \param[in] _in SDF collision. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const sdf::Collision &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from an SDF collision to a collision + /// message. + /// \param[in] _in SDF collision. + /// \return Collision message. + template<> + msgs::Collision convert(const sdf::Collision &_in); + + /// \brief Generic conversion from a collision message to another type. + /// \param[in] _in Collision message. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const msgs::Collision &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from a collision message to a collision + /// SDF object. + /// \param[in] _in Collision message. + /// \return SDF collision. + template<> + sdf::Collision convert(const msgs::Collision &_in); + + /// \brief Generic conversion from a string to another type. + /// \param[in] _in string. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const std::string &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from a string to an Entity_Type msg. + /// \param[in] _in string message. + /// \return Entity_Type. + template<> + msgs::Entity_Type convert(const std::string &_in); + + /// \brief Generic conversion from axis aligned box object to another type. + /// \param[in] _in Axis aligned box object. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const math::AxisAlignedBox &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from a math axis aligned box object to an + /// axis aligned box message + /// \param[in] _in Axis aligned box message + /// \return Axis aligned box message. + template<> + msgs::AxisAlignedBox convert(const math::AxisAlignedBox &_in); + + /// \brief Generic conversion from an axis aligned box message to another + /// type. + /// \param[in] _in Axis aligned box message + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const msgs::AxisAlignedBox &_in) + { + (void)_in; + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from an math axis aligned box message to + /// an axis aligned box object. + /// \param[in] _in Axis aligned box object + /// \return Axis aligned box object. + template<> + math::AxisAlignedBox convert(const msgs::AxisAlignedBox &_in); + } + } +} +#endif diff --git a/include/gz/sim/Entity.hh b/include/gz/sim/Entity.hh new file mode 100644 index 0000000000..b4a8f08c75 --- /dev/null +++ b/include/gz/sim/Entity.hh @@ -0,0 +1,66 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_ENTITY_HH_ +#define GZ_GAZEBO_ENTITY_HH_ + +#include +#include +#include + +/// \brief This library is part of the [Ignition +/// Robotics](https://ignitionrobotics.org) project. +namespace ignition +{ + /// \brief Gazebo is a leading open source robotics simulator, that + /// provides high fidelity physics, rendering, and sensor simulation. + namespace gazebo + { + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + // Adding component namespace information here because there is + // currently no one component class that seems like a good place to hold + // this documentation. + /// \brief Components represent data, such as position information. An + /// Entity usually has one or more associated components. + /// + /// The set of Components assigned to an Entity also act as a key. + /// Systems process Entities based on their key. For example, a physics + /// system may process only entities that have pose and inertia + /// components. + namespace components {} + + /// \brief An Entity identifies a single object in simulation such as + /// a model, link, or light. At its core, an Entity is just an identifier. + /// + /// An Entity usually has one or more associated Components. Components + /// represent data, such as position information. + /// + /// The set of Components assigned to an Entity also act as a key. + /// Systems process Entities based on their key. For example, a physics + /// system may process only entities that have pose and inertia + /// components. + /// + /// An Entity that needs to be identified and used by Systems should be + /// created through the EntityComponentManager. + using Entity = uint64_t; + + /// \brief Indicates a non-existant or invalid Entity. + const Entity kNullEntity{0}; + } + } +} +#endif diff --git a/include/gz/sim/EntityComponentManager.hh b/include/gz/sim/EntityComponentManager.hh new file mode 100644 index 0000000000..101419db27 --- /dev/null +++ b/include/gz/sim/EntityComponentManager.hh @@ -0,0 +1,778 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_ENTITYCOMPONENTMANAGER_HH_ +#define GZ_GAZEBO_ENTITYCOMPONENTMANAGER_HH_ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include "gz/sim/Entity.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Types.hh" + +#include "gz/sim/components/Component.hh" +#include "gz/sim/detail/View.hh" + +namespace ignition +{ + namespace gazebo + { + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + // Forward declarations. + class IGNITION_GAZEBO_HIDDEN EntityComponentManagerPrivate; + + /// \brief Type alias for the graph that holds entities. + /// Each vertex is an entity, and the direction points from the parent to + /// its children. + /// All edges are positive booleans. + using EntityGraph = math::graph::DirectedGraph; + + /** \class EntityComponentManager EntityComponentManager.hh \ + * ignition/gazebo/EntityComponentManager.hh + **/ + /// \brief The EntityComponentManager constructs, deletes, and returns + /// components and entities. + /// A component can be of any class which inherits from + /// `components::BaseComponent`. + class IGNITION_GAZEBO_VISIBLE EntityComponentManager + { + /// \brief Constructor + public: EntityComponentManager(); + + /// \brief Destructor + public: ~EntityComponentManager(); + + /// \brief Creates a new Entity. + /// \return An id for the Entity, or kNullEntity on failure. + public: Entity CreateEntity(); + + /// \brief Get the number of entities on the server. + /// \return Entity count. + public: size_t EntityCount() const; + + /// \brief Request an entity deletion. This will insert the request + /// into a queue. The queue is processed toward the end of a simulation + /// update step. + /// + /// \details It is recommended that systems don't call this function + /// directly, and instead use the `sim::SdfEntityCreator` class to + /// remove entities. + /// + /// \param[in] _entity Entity to be removed. + /// \param[in] _recursive Whether to recursively delete all child + /// entities. True by default. + public: void RequestRemoveEntity(const Entity _entity, + bool _recursive = true); + + /// \brief Request to remove all entities. This will insert the request + /// into a queue. The queue is processed toward the end of a simulation + /// update step. + public: void RequestRemoveEntities(); + + /// \brief Get whether an Entity exists. + /// \param[in] _entity Entity to confirm. + /// \return True if the Entity exists. + public: bool HasEntity(const Entity _entity) const; + + /// \brief Get the first parent of the given entity. + /// \details Entities are not expected to have multiple parents. + /// TODO(louise) Either prevent multiple parents or provide full support + /// for multiple parents. + /// \param[in] _entity Entity. + /// \return The parent entity or kNullEntity if there's none. + public: Entity ParentEntity(const Entity _entity) const; + + /// \brief Set the parent of an entity. + /// + /// \details It is recommended that systems don't call this function + /// directly, and instead use the `sim::SdfEntityCreator` class to + /// create entities that have the correct parent-child relationship. + /// + /// \param[in] _child Entity to set the parent + /// \param[in] _parent Entity which should be an immediate parent _child + /// entity. + /// \return True if successful. Will fail if entities don't exist. + public: bool SetParentEntity(const Entity _child, const Entity _parent); + + /// \brief Get whether a component type has ever been created. + /// \param[in] _typeId ID of the component type to check. + /// \return True if the provided _typeId has been created. + public: bool HasComponentType(const ComponentTypeId _typeId) const; + + /// \brief Check whether an entity has a specific component. + /// \param[in] _entity The entity to check. + /// \param[in] _key The component to check. + /// \return True if the component key belongs to the entity. + public: bool EntityHasComponent(const Entity _entity, + const ComponentKey &_key) const; + + /// \brief Check whether an entity has a specific component type. + /// \param[in] _entity The entity to check. + /// \param[in] _typeId Component type id to check. + /// \return True if the entity exists and has at least one component + /// with the provided type. + public: bool EntityHasComponentType(const Entity _entity, + const ComponentTypeId &_typeId) const; + + /// \brief Get whether an entity has all the given component types. + /// \param[in] _entity The entity to check. + /// \param[in] _types Component types to check that the Entity has. + /// \return True if the given entity has all the given types. + public: bool EntityMatches(Entity _entity, + const std::set &_types) const; + + /// \brief Remove a component from an entity based on a key. + /// \param[in] _entity The entity. + /// \param[in] _key A key that uniquely identifies a component. + /// \return True if the entity and component existed and the component was + /// removed. + public: bool RemoveComponent( + const Entity _entity, const ComponentKey &_key); + + /// \brief Remove a component from an entity based on a type id. + /// \param[in] _entity The entity. + /// \param[in] _typeId Component's type Id. + /// \return True if the entity and component existed and the component was + /// removed. + public: bool RemoveComponent( + const Entity _entity, const ComponentTypeId &_typeId); + + /// \brief Remove a component from an entity based on a type. + /// \param[in] _entity The entity. + /// \tparam Component type. + /// \return True if the entity and component existed and the component was + /// removed. + public: template + bool RemoveComponent(Entity _entity); + + /// \brief Rebuild all the views. This could be an expensive + /// operation. + public: void RebuildViews(); + + /// \brief Create a component of a particular type. This will copy the + /// _data parameter. + /// \param[in] _entity The entity that will be associated with + /// the component. + /// \param[in] _data Data used to construct the component. + /// \return Key that uniquely identifies the component. + public: template + ComponentKey CreateComponent(const Entity _entity, + const ComponentTypeT &_data); + + /// \brief Get a component assigned to an entity based on a + /// component type. + /// \param[in] _entity The entity. + /// \return The component of the specified type assigned to specified + /// Entity, or nullptr if the component could not be found. + public: template + const ComponentTypeT *Component(const Entity _entity) const; + + /// \brief Get a mutable component assigned to an entity based on a + /// component type. + /// \param[in] _entity The entity. + /// \return The component of the specified type assigned to specified + /// Entity, or nullptr if the component could not be found. + public: template + ComponentTypeT *Component(const Entity _entity); + + /// \brief Get a component based on a key. + /// \param[in] _key A key that uniquely identifies a component. + /// \return The component associated with the key, or nullptr if the + /// component could not be found. + public: template + const ComponentTypeT *Component(const ComponentKey &_key) const; + + /// \brief Get a mutable component based on a key. + /// \param[in] _key A key that uniquely identifies a component. + /// \return The component associated with the key, or nullptr if the + /// component could not be found. + public: template + ComponentTypeT *Component(const ComponentKey &_key); + + /// \brief Get a mutable component assigned to an entity based on a + /// component type. If the component doesn't exist, create it and + /// initialize with the given default value. + /// \param[in] _entity The entity. + /// \param[in] _default The value that should be used to construct + /// the component in case the component doesn't exist. + /// \return The component of the specified type assigned to the specified + /// entity. + public: template + ComponentTypeT *ComponentDefault(Entity _entity, + const typename ComponentTypeT::Type &_default = + typename ComponentTypeT::Type()); + + /// \brief Get the data from a component. + /// * If the component type doesn't hold any data, this won't compile. + /// * If the entity doesn't have that component, it will return nullopt. + /// * If the entity has the component, return its data. + /// \param[in] _entity The entity. + /// \tparam ComponentTypeT Component type + /// \return The data of the component of the specified type assigned to + /// specified Entity, or nullptr if the component could not be found. + public: template + std::optional ComponentData( + const Entity _entity) const; + + /// \brief Set the data from a component. + /// * If the component type doesn't hold any data, this won't compile. + /// * If the entity doesn't have that component, the component will be + /// created. + /// * If the entity has the component, its data will be updated. + /// \param[in] _entity The entity. + /// \param[in] _data New component data + /// \tparam ComponentTypeT Component type + /// \return True if data has changed. It will always be true if the data + /// type doesn't have an equality operator. + public: template + bool SetComponentData(const Entity _entity, + const typename ComponentTypeT::Type &_data); + + /// \brief Get the type IDs of all components attached to an entity. + /// \param[in] _entity Entity to check. + /// \return All the component type IDs. + public: std::unordered_set ComponentTypes( + Entity _entity) const; + + /// \brief The first component instance of the specified type. + /// \return First component instance of the specified type, or nullptr + /// if the type does not exist. + public: template + const ComponentTypeT *First() const; + + /// \brief The first component instance of the specified type. + /// \return First component instance of the specified type, or nullptr + /// if the type does not exist. + public: template + ComponentTypeT *First(); + + /// \brief Get an entity which matches the value of all the given + /// components. For example, the following will return the entity which + /// has an name component equal to "name" and has a model component: + /// + /// auto entity = EntityByComponents(components::Name("name"), + /// components::Model()); + /// + /// \details Component type must have inequality operator. + /// + /// \param[in] _desiredComponents All the components which must match. + /// \return Entity or kNullEntity if no entity has the exact components. + public: template + Entity EntityByComponents( + const ComponentTypeTs &..._desiredComponents) const; + + /// \brief Get all entities which match the value of all the given + /// components. For example, the following will return the entities which + /// have a name component equal to "camera" and a sensor component: + /// + /// auto entities = EntitiesByComponents(components::Name("camera"), + /// components::Sensor()); + /// + /// \details Component type must have inequality operator. + /// + /// \param[in] _desiredComponents All the components which must match. + /// \return All matching entities, or an empty vector if no child entity + /// has the exact components. + public: template + std::vector EntitiesByComponents( + const ComponentTypeTs &..._desiredComponents) const; + + /// \brief Get all entities which match the value of all the given + /// components and are immediate children of a given parent entity. + /// For example, the following will return a child of entity `parent` + /// which has an int component equal to 123, and a string component + /// equal to "name": + /// + /// auto entity = ChildrenByComponents(parent, 123, std::string("name")); + /// + /// \details Component type must have inequality operator. + /// + /// \param[in] _parent Entity which should be an immediate parent of the + /// returned entity. + /// \param[in] _desiredComponents All the components which must match. + /// \return All matching entities, or an empty vector if no child entity + /// has the exact components. + public: template + std::vector ChildrenByComponents(Entity _parent, + const ComponentTypeTs &..._desiredComponents) const; + + /// why is this required? + private: template + struct identity; // NOLINT + + /// \brief A version of Each() that doesn't use a cache. The cached + /// version, Each(), is preferred. + /// Get all entities which contain given component types, as well + /// as the components. + /// \param[in] _f Callback function to be called for each matching entity. + /// The function parameter are all the desired component types, in the + /// order they're listed on the template. The callback function can + /// return false to stop subsequent calls to the callback, otherwise + /// a true value should be returned. + /// \tparam ComponentTypeTs All the desired component types. + /// \warning This function should not be called outside of System's + /// PreUpdate, Update, or PostUpdate callbacks. + public: template + void EachNoCache(typename identity>::type _f) const; + + /// \brief A version of Each() that doesn't use a cache. The cached + /// version, Each(), is preferred. + /// Get all entities which contain given component types, as well + /// as the mutable components. + /// \param[in] _f Callback function to be called for each matching entity. + /// The function parameter are all the desired component types, in the + /// order they're listed on the template. The callback function can + /// return false to stop subsequent calls to the callback, otherwise + /// a true value should be returned. + /// \tparam ComponentTypeTs All the desired mutable component types. + /// \warning This function should not be called outside of System's + /// PreUpdate, Update, or PostUpdate callbacks. + public: template + void EachNoCache(typename identity>::type _f); + + /// \brief Get all entities which contain given component types, as well + /// as the components. Note that an entity marked for removal (but not + /// processed yet) will be included in the list of entities iterated by + /// this call. + /// \param[in] _f Callback function to be called for each matching entity. + /// The function parameter are all the desired component types, in the + /// order they're listed on the template. The callback function can + /// return false to stop subsequent calls to the callback, otherwise + /// a true value should be returned. + /// \tparam ComponentTypeTs All the desired component types. + /// \warning This function should not be called outside of System's + /// PreUpdate, Update, or PostUpdate callbacks. + public: template + void Each(typename identity>::type _f) const; + + /// \brief Get all entities which contain given component types, as well + /// as the mutable components. Note that an entity marked for removal (but + /// not processed yet) will be included in the list of entities iterated + /// by this call. + /// \param[in] _f Callback function to be called for each matching entity. + /// The function parameter are all the desired component types, in the + /// order they're listed on the template. The callback function can + /// return false to stop subsequent calls to the callback, otherwise + /// a true value should be returned. + /// \tparam ComponentTypeTs All the desired mutable component types. + /// \warning This function should not be called outside of System's + /// PreUpdate, Update, or PostUpdate callbacks. + public: template + void Each(typename identity>::type _f); + + /// \brief Call a function for each parameter in a pack. + /// \param[in] _f Function to be called. + /// \param[in] _components Parameters which should be passed to the + /// function. + public: template + static void ForEach(Function _f, const ComponentTypeTs &... _components); + + /// \brief Get all newly created entities which contain given component + /// types, as well as the components. This "newness" is cleared at the end + /// of a simulation step. + /// \param[in] _f Callback function to be called for each matching entity. + /// The function parameter are all the desired component types, in the + /// order they're listed on the template. The callback function can + /// return false to stop subsequent calls to the callback, otherwise + /// a true value should be returned. + /// \tparam ComponentTypeTs All the desired component types. + /// \warning Since entity creation occurs during PreUpdate, this function + /// should not be called in a System's PreUpdate callback (it's okay to + /// call this function in the Update callback). If you need to call this + /// function in a system's PostUpdate callback, you should use the const + /// version of this method. + public: template + void EachNew(typename identity>::type _f); + + /// \brief Get all newly created entities which contain given component + /// types, as well as the components. This "newness" is cleared at the end + /// of a simulation step. This is the const version. + /// \param[in] _f Callback function to be called for each matching entity. + /// The function parameter are all the desired component types, in the + /// order they're listed on the template. The callback function can + /// return false to stop subsequent calls to the callback, otherwise + /// a true value should be returned. + /// \tparam ComponentTypeTs All the desired component types. + /// \warning Since entity creation occurs during PreUpdate, this function + /// should not be called in a System's PreUpdate callback (it's okay to + /// call this function in the Update or PostUpdate callback). + public: template + void EachNew(typename identity>::type _f) const; + + /// \brief Get all entities which contain given component types and are + /// about to be removed, as well as the components. + /// \param[in] _f Callback function to be called for each matching entity. + /// The function parameter are all the desired component types, in the + /// order they're listed on the template. The callback function can + /// return false to stop subsequent calls to the callback, otherwise + /// a true value should be returned. + /// \tparam ComponentTypeTs All the desired component types. + /// \warning This function should not be called outside of System's + /// PostUpdate callback. + public: template + void EachRemoved(typename identity>::type _f) const; + + /// \brief Get a graph with all the entities. Entities are vertices and + /// edges point from parent to children. + /// \return Entity graph. + public: const EntityGraph &Entities() const; + + /// \brief Get all entities which are descendants of a given entity, + /// including the entity itself. + /// \param[in] _entity Entity whose descendants we want. + /// \return All child entities recursively, including _entity. It will be + /// empty if the entity doesn't exist. + public: std::unordered_set Descendants(Entity _entity) const; + + /// \brief Get a message with the serialized state of the given entities + /// and components. + /// \details The header of the message will not be populated, it is the + /// responsibility of the caller to timestamp it before use. + /// \param[in] _entities Entities to be serialized. Leave empty to get + /// all entities. + /// \param[in] _types Type ID of components to be serialized. Leave empty + /// to get all components. + public: msgs::SerializedState State( + const std::unordered_set &_entities = {}, + const std::unordered_set &_types = {}) const; + + /// \brief Get a message with the serialized state of all entities and + /// components that are changing in the current iteration + /// + /// Currently supported: + /// * New entities and all of their components + /// * Removed entities and all of their components + /// + /// Future work: + /// * Entities which had a component added + /// * Entities which had a component removed + /// * Entities which had a component modified + /// + /// \details The header of the message will not be populated, it is the + /// responsibility of the caller to timestamp it before use. + public: msgs::SerializedState ChangedState() const; + + /// \brief Get whether there are new entities. + /// \return True if there are new entities. + public: bool HasNewEntities() const; + + /// \brief Get whether there are any entities marked to be removed. + /// \return True if there are entities marked to be removed. + public: bool HasEntitiesMarkedForRemoval() const; + + /// \brief Get whether there are one-time component changes. These changes + /// do not happen frequently and should be processed immediately. + /// \return True if there are any components with one-time changes. + public: bool HasOneTimeComponentChanges() const; + + /// \brief Get the components types that are marked as periodic changes. + /// \return All the components that at least one entity marked as + /// periodic changes. + public: std::unordered_set + ComponentTypesWithPeriodicChanges() const; + + /// \brief Set the absolute state of the ECM from a serialized message. + /// Entities / components that are in the new state but not in the old + /// one will be created. + /// Entities / components that are marked as removed will be removed, but + /// they won't be removed if they're not present in the state. + /// \details The header of the message will not be handled, it is the + /// responsibility of the caller to use the timestamp. + /// \param[in] _stateMsg Message containing state to be set. + public: void SetState(const msgs::SerializedState &_stateMsg); + + /// \brief Get a message with the serialized state of the given entities + /// and components. + /// \details The header of the message will not be populated, it is the + /// responsibility of the caller to timestamp it before use. + /// \param[in] _state serialized state + /// \param[in] _entities Entities to be serialized. Leave empty to get + /// all entities. + /// \param[in] _types Type ID of components to be serialized. Leave empty + /// to get all components. + /// \param[in] _full True to get all the entities and components. + /// False will get only components and entities that have changed. + public: void State( + msgs::SerializedStateMap &_state, + const std::unordered_set &_entities = {}, + const std::unordered_set &_types = {}, + bool _full = false) const; + + /// \brief Get a message with the serialized state of all entities and + /// components that are changing in the current iteration + /// + /// Currently supported: + /// * New entities and all of their components + /// * Removed entities and all of their components + /// + /// Future work: + /// * Entities which had a component added + /// * Entities which had a component removed + /// * Entities which had a component modified + /// + /// \param[in] _state New serialized state. + /// \details The header of the message will not be populated, it is the + /// responsibility of the caller to timestamp it before use. + public: void ChangedState(msgs::SerializedStateMap &_state) const; + + /// \brief Set the absolute state of the ECM from a serialized message. + /// Entities / components that are in the new state but not in the old + /// one will be created. + /// Entities / components that are marked as removed will be removed, but + /// they won't be removed if they're not present in the state. + /// \details The header of the message will not be handled, it is the + /// responsibility of the caller to use the timestamp. + /// \param[in] _stateMsg Message containing state to be set. + public: void SetState(const msgs::SerializedStateMap &_stateMsg); + + /// \brief Set the changed state of a component. + /// \param[in] _entity The entity. + /// \param[in] _type Type of the component. + /// \param[in] _c Changed state value, defaults to one-time-change. + public: void SetChanged( + const Entity _entity, const ComponentTypeId _type, + gz::sim::ComponentState _c = ComponentState::OneTimeChange); + + /// \brief Get a component's state. + /// \param[in] _entity Entity that contains the component. + /// \param[in] _typeId Component type ID. + /// \return Component's current state + public: gz::sim::ComponentState ComponentState(const Entity _entity, + const ComponentTypeId _typeId) const; + + /// \brief All future entities will have an id that starts at _offset. + /// This can be used to avoid entity id collisions, such as during log + /// playback. + /// \param[in] _offset Offset value. + public: void SetEntityCreateOffset(uint64_t _offset); + + /// \brief Clear the list of newly added entities so that a call to + /// EachAdded after this will have no entities to iterate. This function + /// is protected to facilitate testing. + protected: void ClearNewlyCreatedEntities(); + + /// \brief Process all entity remove requests. This will remove + /// entities and their components. This function is protected to + /// facilitate testing. + protected: void ProcessRemoveEntityRequests(); + + /// \brief Mark all components as not changed. + protected: void SetAllComponentsUnchanged(); + + /// \brief Get whether an Entity exists and is new. + /// + /// Entities are considered new in the time between their creation and a + /// call to ClearNewlyCreatedEntities + /// \param[in] _entity Entity id to check. + /// \return True if the Entity is new. + private: bool IsNewEntity(const Entity _entity) const; + + /// \brief Get whether an Entity has been marked to be removed. + /// \param[in] _entity Entity id to check. + /// \return True if the Entity has been marked to be removed. + private: bool IsMarkedForRemoval(const Entity _entity) const; + + /// \brief Delete an existing Entity. + /// \param[in] _entity The entity to remove. + /// \returns True if the Entity existed and was deleted. + private: bool RemoveEntity(const Entity _entity); + + /// \brief The first component instance of the specified type. + /// \return First component instance of the specified type, or nullptr + /// if the type does not exist. + private: components::BaseComponent *First( + const ComponentTypeId _componentTypeId); + + /// \brief Implementation of CreateComponent. + /// \param[in] _entity The entity that will be associated with + /// the component. + /// \param[in] _componentTypeId Id of the component type. + /// \param[in] _data Data used to construct the component. + /// \return Key that uniquely identifies the component. + private: ComponentKey CreateComponentImplementation( + const Entity _entity, + const ComponentTypeId _componentTypeId, + const components::BaseComponent *_data); + + /// \brief Get a component based on a component type. + /// \param[in] _entity The entity. + /// \param[in] _type Id of the component type. + /// \return The component of the specified type assigned to specified + /// Entity, or nullptr if the component could not be found. + private: const components::BaseComponent *ComponentImplementation( + const Entity _entity, + const ComponentTypeId _type) const; + + /// \brief Get a mutable component based on a component type. + /// \param[in] _entity The entity. + /// \param[in] _type Id of the component type. + /// \return The component of the specified type assigned to specified + /// Entity, or nullptr if the component could not be found. + private: components::BaseComponent *ComponentImplementation( + const Entity _entity, + const ComponentTypeId _type); + + /// \brief Get a component based on a key. + /// \param[in] _key A key that uniquely identifies a component. + /// \return The component associated with the key, or nullptr if the + /// component could not be found. + private: const components::BaseComponent *ComponentImplementation( + const ComponentKey &_key) const; + + /// \brief Get a mutable component based on a key. + /// \param[in] _key A key that uniquely identifies a component. + /// \return The component associated with the key, or nullptr if the + /// component could not be found. + private: components::BaseComponent *ComponentImplementation( + const ComponentKey &_key); + + /// \brief End of the AddComponentToView recursion. This function is + /// called when Rest is empty. + /// \param[in, out] _view The FirstComponent will be added to the + /// _view. + /// \param[in] _entity The entity. + private: template::type = 0> + void AddComponentsToView(detail::View &_view, + const Entity _entity) const; + + /// \brief Recursively add components to a view. This function is + /// called when Rest is NOT empty. + /// \param[in, out] _view The FirstComponent will be added to the + /// _view. + /// \param[in] _entity The entity. + private: template::type = 0> + void AddComponentsToView(detail::View &_view, + const Entity _entity) const; + + /// \brief Find a View that matches the set of ComponentTypeIds. If + /// a match is not found, then a new view is created. + /// \tparam ComponentTypeTs All the component types that define a view. + /// \return A reference to the view. + private: template + detail::View &FindView() const; + + /// \brief Find a view based on the provided component type ids. + /// \param[in] _types The component type ids that serve as a key into + /// a map of views. + /// \param[out] _iter Iterator to the found element in the view map. + /// Check the return value to see if this iterator is valid. + /// \return True if the view was found, false otherwise. + private: bool FindView(const std::set &_types, + std::map::iterator &_iter) const; // NOLINT + + /// \brief Add a new view to the set of stored views. + /// \param[in] _types The set of component type ids that is the key + /// for the view. + /// \param[in] _view The view to add. + /// \return An iterator to the view. + private: std::map::iterator + AddView(const std::set &_types, + detail::View &&_view) const; + + /// \brief Update views that contain the provided entity. + /// \param[in] _entity The entity. + private: void UpdateViews(const Entity _entity); + + /// \brief Get a component ID based on an entity and the component's type. + /// \param[in] _entity The entity. + /// \param[in] _type Component type ID. + private: ComponentId EntityComponentIdFromType( + const Entity _entity, const ComponentTypeId _type) const; + + /// \brief Add an entity and its components to a serialized state message. + /// \param[out] _msg The state message. + /// \param[in] _entity The entity to be added. + /// \param[in] _types Component types to be added. Leave empty for all + /// components. + private: void AddEntityToMessage(msgs::SerializedState &_msg, + Entity _entity, + const std::unordered_set &_types = {}) const; + + /// \brief Private data pointer. + private: std::unique_ptr dataPtr; + + /// \brief Add an entity and its components to a serialized state message. + /// \param[out] _msg The state message. + /// \param[in] _entity The entity to be added. + /// \param[in] _types Component types to be added. Leave empty for all + /// components. + /// \param[in] _full True to get all the entities and components. + /// False will get only components and entities that have changed. + /// \note This function will mark `Changed` components as not changed. + /// See the todo in the implementation. + private: void AddEntityToMessage(msgs::SerializedStateMap &_msg, + Entity _entity, + const std::unordered_set &_types = {}, + bool _full = false) const; + + // Make runners friends so that they can manage entity creation and + // removal. This should be safe since runners are internal + // to Gazebo. + friend class GuiRunner; + friend class SimulationRunner; + + // Make network managers friends so they have control over component + // states. Like the runners, the managers are internal. + friend class NetworkManagerPrimary; + friend class NetworkManagerSecondary; + + // Make View a friend so that it can access components. + // This should be safe since View is internal to Gazebo. + friend class detail::View; + }; + } + } +} + +#include "gz/sim/detail/EntityComponentManager.hh" + +#endif diff --git a/include/gz/sim/EventManager.hh b/include/gz/sim/EventManager.hh new file mode 100644 index 0000000000..cd42c21b61 --- /dev/null +++ b/include/gz/sim/EventManager.hh @@ -0,0 +1,148 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_EVENTMANAGER_HH_ +#define GZ_GAZEBO_EVENTMANAGER_HH_ + +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +namespace ignition +{ + namespace gazebo + { + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + // Forward declarations. + class IGNITION_GAZEBO_HIDDEN EventManagerPrivate; + + /// \brief The EventManager is used to send/receive notifications of + /// simulator events. + /// + /// The simulator environment and corresponding systems can either connect + /// to an Event or emit an Event as needed to signal actions that need to + /// occur. + /// + /// See \ref gz::sim::events for a complete list of events. + class IGNITION_GAZEBO_VISIBLE EventManager + { + /// \brief Constructor + public: EventManager(); + + /// \brief Destructor + public: ~EventManager(); + + /// \brief Add a connection to an event. + /// \param[in] _subscriber A std::function callback function. The function + /// signature must match that of the event (template parameter E). + /// \return A Connection pointer, which will automatically call + /// Disconnect when it goes out of scope. + public: template + gz::common::ConnectionPtr + Connect(const typename E::CallbackT &_subscriber) + { + if (this->events.find(typeid(E)) == this->events.end()) { + this->events[typeid(E)] = std::make_unique(); + } + + E *eventPtr = dynamic_cast(this->events[typeid(E)].get()); + // All values in the map should be derived from Event, + // so this shouldn't be an issue, but it doesn't hurt to check. + if (eventPtr != nullptr) + { + return eventPtr->Connect(_subscriber); + } + else + { + ignerr << "Failed to connect event: " + << typeid(E).name() << std::endl; + return nullptr; + } + } + + /// \brief Emit an event signal to connected subscribers. + /// \param[in] _args function arguments to be passed to the event + /// callbacks. Must match the signature of the event type E. + public: template + void Emit(Args && ... _args) + { + if (this->events.find(typeid(E)) == this->events.end()) + { + // If there are no events of type E in the map, create it. + // But it also means there is nothing to signal. + // + // This is also needed to suppress unused function warnings + // for Events that are purely emitted, with no connections. + this->events[typeid(E)] = std::make_unique(); + return; + } + + E *eventPtr = dynamic_cast(this->events[typeid(E)].get()); + // All values in the map should be derived from Event, + // so this shouldn't be an issue, but it doesn't hurt to check. + if (eventPtr != nullptr) + { + eventPtr->Signal(std::forward(_args) ...); + } + else + { + ignerr << "Failed to signal event: " + << typeid(E).name() << std::endl; + } + } + + + /// \brief Convenience type for storing typeinfo references. + private: using TypeInfoRef = std::reference_wrapper; + + /// \brief Hash functor for TypeInfoRef + private: struct Hasher + { + std::size_t operator()(TypeInfoRef _code) const + { + return _code.get().hash_code(); + } + }; + + /// \brief Equality functor for TypeInfoRef + private: struct EqualTo + { + bool operator()(TypeInfoRef _lhs, TypeInfoRef _rhs) const + { + return _lhs.get() == _rhs.get(); + } + }; + + /// \brief Container of used signals. + private: std::unordered_map, + Hasher, EqualTo> events; + }; + } + } +} + +#endif // GZ_GAZEBO_EVENTMANAGER_HH_ diff --git a/include/gz/sim/Events.hh b/include/gz/sim/Events.hh new file mode 100644 index 0000000000..e5240d821c --- /dev/null +++ b/include/gz/sim/Events.hh @@ -0,0 +1,66 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_EVENTS_HH_ +#define GZ_GAZEBO_EVENTS_HH_ + +#include + +#include + +#include "gz/sim/config.hh" +#include "gz/sim/Entity.hh" + +namespace ignition +{ + namespace gazebo + { + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + /// \brief Namespace for all events. Refer to the EventManager class for + /// more information about events. + namespace events + { + /// \brief The pause event can be used to pause or unpause simulation. + /// Emit a value of true to pause simulation, and emit a value of false + /// to unpause simulation. + /// + /// For example, to pause simulation use: + /// \code + /// eventManager.Emit(true); + /// \endcode + using Pause = gz::common::EventT; + + /// \brief The stop event can be used to terminate simulation. + /// Emit this signal to terminate an active simulation. + /// + /// For example: + /// \code + /// eventManager.Emit(); + /// \endcode + using Stop = gz::common::EventT; + + /// \brief Event used to load plugins for an entity into simulation. + /// Pass in the entity which will own the plugins, and an SDF element for + /// the entity, which may contain multiple `` tags. + using LoadPlugins = common::EventT; + } + } // namespace events + } // namespace gazebo +} // namespace ignition + +#endif // GZ_GAZEBO_EVENTS_HH_ diff --git a/include/gz/sim/Link.hh b/include/gz/sim/Link.hh new file mode 100644 index 0000000000..84b9a780cb --- /dev/null +++ b/include/gz/sim/Link.hh @@ -0,0 +1,282 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_LINK_HH_ +#define GZ_GAZEBO_LINK_HH_ + +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace ignition +{ + namespace gazebo + { + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + // Forward declarations. + class IGNITION_GAZEBO_HIDDEN LinkPrivate; + // + /// \class Link Link.hh ignition/gazebo/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. + /// All the functions provided here are meant to be used with a link + /// entity. + /// + /// For example, given a link's entity, to find the value of its + /// name component, one could use the entity-component manager (`ecm`) + /// directly as follows: + /// + /// std::string name = ecm.Component(entity)->Data(); + /// + /// Using this class however, the same information can be obtained with + /// a simpler function call: + /// + /// Link link(entity); + /// std::string name = link.Name(ecm); + /// + class IGNITION_GAZEBO_VISIBLE Link + { + /// \brief Constructor + /// \param[in] _entity Link entity + public: explicit Link(gz::sim::Entity _entity = kNullEntity); + + /// \brief Copy constructor + /// \param[in] _link Link to copy. + public: Link(const Link &_link); + + /// \brief Move constructor + /// \param[in] _link Link to move. + public: Link(Link &&_link) noexcept; + + /// \brief Move assignment operator. + /// \param[in] _link Link component to move. + /// \return Reference to this. + public: Link &operator=(Link &&_link) noexcept; + + /// \brief Copy assignment operator. + /// \param[in] _link Link to copy. + /// \return Reference to this. + public: Link &operator=(const Link &_link); + + /// \brief Destructor + public: ~Link(); + + /// \brief Get the entity which this Link is related to. + /// \return Link entity. + public: gz::sim::Entity Entity() const; + + /// \brief Reset Entity to a new one + /// \param[in] _newEntity New link entity. + public: void ResetEntity(gz::sim::Entity _newEntity); + + /// \brief Check whether this link correctly refers to an entity that + /// has a components::Link. + /// \param[in] _ecm Entity-component manager. + /// \return True if it's a valid link in the manager. + public: bool Valid(const EntityComponentManager &_ecm) const; + + /// \brief Get the link's unscoped name. + /// \param[in] _ecm Entity-component manager. + /// \return Link's name or nullopt if the entity does not have a + /// components::Name component + public: std::optional Name( + const EntityComponentManager &_ecm) const; + + /// \brief Get the parent model + /// \param[in] _ecm Entity-component manager. + /// \return Parent Model or nullopt if the entity does not have a + /// components::ParentEntity component. + public: std::optional ParentModel( + const EntityComponentManager &_ecm) const; + + /// \brief Check if this is the canonical link. + /// \param[in] _ecm Entity-component manager. + /// \return True if it is the canonical link. + public: bool IsCanonical(const EntityComponentManager &_ecm) const; + + /// \brief Get whether this link has wind enabled. + /// \param[in] _ecm Entity-component manager. + /// \return True if wind mode is on. + public: bool WindMode(const EntityComponentManager &_ecm) const; + + /// \brief Get the ID of a collision entity which is an immediate child of + /// this link. + /// \param[in] _ecm Entity-component manager. + /// \param[in] _name Collision name. + /// \return Collision entity. + public: gz::sim::Entity CollisionByName( + const EntityComponentManager &_ecm, + const std::string &_name) const; + + /// \brief Get the ID of a visual entity which is an immediate child of + /// this link. + /// \param[in] _ecm Entity-component manager. + /// \param[in] _name Visual name. + /// \return Visual entity. + public: gz::sim::Entity VisualByName(const EntityComponentManager &_ecm, + const std::string &_name) const; + + /// \brief Get all collisions which are immediate children of this link. + /// \param[in] _ecm Entity-component manager. + /// \return All collisions in this link. + public: std::vector Collisions( + const EntityComponentManager &_ecm) const; + + /// \brief Get all visuals which are immediate children of this link. + /// \param[in] _ecm Entity-component manager. + /// \return All visuals in this link. + public: std::vector Visuals( + const EntityComponentManager &_ecm) const; + + /// \brief Get the number of collisions which are immediate children of + /// this link. + /// \param[in] _ecm Entity-component manager. + /// \return Number of collisions in this link. + public: uint64_t CollisionCount(const EntityComponentManager &_ecm) const; + + /// \brief Get the number of visuals which are immediate children of this + /// link. + /// \param[in] _ecm Entity-component manager. + /// \return Number of visuals in this link. + public: uint64_t VisualCount(const EntityComponentManager &_ecm) const; + + /// \brief Get the pose of the link frame in the world coordinate frame. + /// \param[in] _ecm Entity-component manager. + /// \return Absolute Pose of the link or nullopt if the entity does not + /// have a components::WorldPose component. + public: std::optional WorldPose( + const EntityComponentManager &_ecm) const; + + /// \brief Get the world pose of the link inertia. + /// \param[in] _ecm Entity-component manager. + /// \return Inertial pose in world frame or nullopt if the + /// link does not have the components components::WorldPose and + /// components::Inertial. + public: std::optional WorldInertialPose( + const EntityComponentManager &_ecm) const; + + /// \brief Get the linear velocity at the origin of of the link frame + /// expressed in the world frame, using an offset expressed in a + /// body-fixed frame. If no offset is given, the velocity at the origin of + /// the Link frame will be returned. + /// \param[in] _ecm Entity-component manager. + /// \return Linear velocity of the link or nullopt if the velocity checks + /// aren't enabled. + /// \sa EnableVelocityChecks + public: std::optional WorldLinearVelocity( + const EntityComponentManager &_ecm) const; + + /// \brief Get the linear velocity of a point on the body in the world + /// frame, using an offset expressed in a body-fixed frame. + /// \param[in] _ecm Entity-component manager. + /// \param[in] _offset Offset of the point from the origin of the Link + /// frame, expressed in the body-fixed frame. + /// \return Linear velocity of the point on the body or nullopt if + /// velocity checks aren't enabled. + /// \sa EnableVelocityChecks + public: std::optional WorldLinearVelocity( + const EntityComponentManager &_ecm, + const math::Vector3d &_offset) const; + + /// \brief Get the angular velocity of the link in the world frame + /// \param[in] _ecm Entity-component manager. + /// \return Angular velocity of the link or nullopt if velocity checks + /// aren't enabled. + /// \sa EnableVelocityChecks + public: std::optional WorldAngularVelocity( + const EntityComponentManager &_ecm) const; + + /// \brief By default, Gazebo will not report velocities for a link, so + /// functions like `WorldLinearVelocity` will return nullopt. This + /// function can be used to enable all velocity checks. + /// \param[in] _ecm Mutable reference to the ECM. + /// \param[in] _enable True to enable checks, false to disable. Defaults + /// to true. + public: void EnableVelocityChecks(EntityComponentManager &_ecm, + bool _enable = true) const; + + /// \brief Get the linear acceleration of the body in the world frame. + /// \param[in] _ecm Entity-component manager. + /// \return Linear acceleration of the body in the world frame or nullopt + /// if acceleration checks aren't enabled. + /// \sa EnableAccelerationChecks + public: std::optional WorldLinearAcceleration( + const EntityComponentManager &_ecm) const; + + /// \brief By default, Gazebo will not report accelerations for a link, so + /// functions like `WorldLinearAcceleration` will return nullopt. This + /// function can be used to enable all acceleration checks. + /// \param[in] _ecm Mutable reference to the ECM. + /// \param[in] _enable True to enable checks, false to disable. Defaults + /// to true. + public: void EnableAccelerationChecks(EntityComponentManager &_ecm, + bool _enable = true) const; + + /// \brief Get the inertia matrix in the world frame. + /// \param[in] _ecm Entity-component manager. + /// \return Inertia matrix in world frame, returns nullopt if link + /// does not have components components::Inertial and + /// components::WorldPose. + public: std::optional WorldInertiaMatrix( + const EntityComponentManager &_ecm) const; + + /// \brief Get the rotational and translational kinetic energy of the + /// link with respect to the world frame. + /// \param[in] _ecm Entity-component manager. + /// \return Kinetic energy in world frame, returns nullopt if link + /// does not have components components::Inertial, + /// components::WorldAngularVelocity, components::WorldLinearVelocity, + /// and components::WorldPose. + public: std::optional WorldKineticEnergy( + const EntityComponentManager &_ecm) const; + + /// \brief Add a force expressed in world coordinates and applied at the + /// center of mass of the link. + /// \param[in] _ecm Mutable Entity-component manager. + /// \param[in] _force Force to be applied expressed in world coordinates + public: void AddWorldForce(EntityComponentManager &_ecm, + const math::Vector3d &_force) const; + + /// \brief Add a wrench expressed in world coordinates and applied to + /// the link at the link's origin. This wrench is applied for one + /// simulation step. + /// \param[in] _ecm Mutable Entity-component manager. + /// \param[in] _force Force to be applied expressed in world coordinates + /// \param[in] _torque Torque to be applied expressed in world coordinates + public: void AddWorldWrench(EntityComponentManager &_ecm, + const math::Vector3d &_force, + const math::Vector3d &_torque) const; + + /// \brief Pointer to private data. + private: std::unique_ptr dataPtr; + }; + } + } +} +#endif diff --git a/include/gz/sim/Model.hh b/include/gz/sim/Model.hh new file mode 100644 index 0000000000..4179c6431b --- /dev/null +++ b/include/gz/sim/Model.hh @@ -0,0 +1,184 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_MODEL_HH_ +#define GZ_GAZEBO_MODEL_HH_ + +#include +#include +#include + +#include + +#include +#include +#include +#include + +namespace ignition +{ + namespace gazebo + { + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + // Forward declarations. + class IGNITION_GAZEBO_HIDDEN ModelPrivate; + // + /// \class Model Model.hh ignition/gazebo/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. + /// All the functions provided here are meant to be used with a model + /// entity. + /// + /// For example, given a model's entity, to find the value of its + /// name component, one could use the entity-component manager (`ecm`) + /// directly as follows: + /// + /// std::string name = ecm.Component(entity)->Data(); + /// + /// Using this class however, the same information can be obtained with + /// a simpler function call: + /// + /// Model model(entity); + /// std::string name = model.Name(ecm); + /// + /// \todo(louise) Store the ecm instead of passing it at every API call. + class IGNITION_GAZEBO_VISIBLE Model { + /// \brief Constructor + /// \param[in] _entity Model entity + public: explicit Model(gz::sim::Entity _entity = kNullEntity); + + /// \brief Copy constructor + /// \param[in] _model Model to copy. + public: Model(const Model &_model); + + /// \brief Move constructor + /// \param[in] _model Model to move. + public: Model(Model &&_model) noexcept; + + /// \brief Move assignment operator. + /// \param[in] _model Model component to move. + /// \return Reference to this. + public: Model &operator=(Model &&_model) noexcept; + + /// \brief Copy assignment operator. + /// \param[in] _model Model to copy. + /// \return Reference to this. + public: Model &operator=(const Model &_model); + + /// \brief Destructor + public: virtual ~Model(); + + /// \brief Get the entity which this Model is related to. + /// \return Model entity. + public: gz::sim::Entity Entity() const; + + /// \brief Check whether this model correctly refers to an entity that + /// has a components::Model. + /// \param[in] _ecm Entity-component manager. + /// \return True if it's a valid model in the manager. + public: bool Valid(const EntityComponentManager &_ecm) const; + + /// \brief Get the model's unscoped name. + /// \param[in] _ecm Entity-component manager. + /// \return Model's name. + public: std::string Name(const EntityComponentManager &_ecm) const; + + /// \brief Get whether this model is static. + /// \param[in] _ecm Entity-component manager. + /// \return True if static. + public: bool Static(const EntityComponentManager &_ecm) const; + + /// \brief Get whether this model has self-collide enabled. + /// \param[in] _ecm Entity-component manager. + /// \return True if self-colliding. + public: bool SelfCollide(const EntityComponentManager &_ecm) const; + + /// \brief Get whether this model has wind enabled. + /// \param[in] _ecm Entity-component manager. + /// \return True if wind mode is on. + public: bool WindMode(const EntityComponentManager &_ecm) const; + + /// \brief Get the source file where this model came from. If empty, + /// the model wasn't loaded directly from a file, probably from an SDF + /// string. + /// \param[in] _ecm Entity-component manager. + /// \return Path to the source SDF file. + public: std::string SourceFilePath(const EntityComponentManager &_ecm) + const; + + /// \brief Get the ID of a joint entity which is an immediate child of + /// this model. + /// \param[in] _ecm Entity-component manager. + /// \param[in] _name Joint name. + /// \return Joint entity. + /// \todo(anyone) Make const + public: gz::sim::Entity JointByName(const EntityComponentManager &_ecm, + const std::string &_name); + + /// \brief Get the ID of a link entity which is an immediate child of + /// this model. + /// \param[in] _ecm Entity-component manager. + /// \param[in] _name Link name. + /// \return Link entity. + /// \todo(anyone) Make const + public: gz::sim::Entity LinkByName(const EntityComponentManager &_ecm, + const std::string &_name); + + /// \brief Get all joints which are immediate children of this model. + /// \param[in] _ecm Entity-component manager. + /// \return All joints in this model. + public: std::vector Joints( + const EntityComponentManager &_ecm) const; + + /// \brief Get all links which are immediate children of this model. + /// \param[in] _ecm Entity-component manager. + /// \return All links in this model. + public: std::vector Links( + const EntityComponentManager &_ecm) const; + + /// \brief Get the number of joints which are immediate children of this + /// model. + /// \param[in] _ecm Entity-component manager. + /// \return Number of joints in this model. + public: uint64_t JointCount(const EntityComponentManager &_ecm) const; + + /// \brief Get the number of links which are immediate children of this + /// model. + /// \param[in] _ecm Entity-component manager. + /// \return Number of links in this model. + public: uint64_t LinkCount(const EntityComponentManager &_ecm) const; + + /// \brief Set a command to change the model's pose. + /// \param[in] _ecm Entity-component manager. + /// \param[in] _pose New model pose. + public: void SetWorldPoseCmd(EntityComponentManager &_ecm, + const math::Pose3d &_pose); + + /// \brief Get the model's canonical link entity. + /// \param[in] _ecm Entity-component manager. + /// \return Link entity. + public: gz::sim::Entity CanonicalLink( + const EntityComponentManager &_ecm) const; + + /// \brief Pointer to private data. + private: std::unique_ptr dataPtr; + }; + } + } +} +#endif diff --git a/include/gz/sim/SdfEntityCreator.hh b/include/gz/sim/SdfEntityCreator.hh new file mode 100644 index 0000000000..d738d55f77 --- /dev/null +++ b/include/gz/sim/SdfEntityCreator.hh @@ -0,0 +1,176 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_CREATEREMOVE_HH_ +#define GZ_GAZEBO_CREATEREMOVE_HH_ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +namespace ignition +{ + namespace gazebo + { + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + // Forward declarations. + class SdfEntityCreatorPrivate; + // + /// \class SdfEntityCreator SdfEntityCreator.hh + /// ignition/gazebo/SdfEntityCreator.hh + /// \brief Provides convenient functions to spawn entities and load their + /// plugins from SDF elements, to remove them, and to change their + /// hierarchy. + /// + /// This class provides wrappers around entities and components + /// which are more convenient and straight-forward to use than dealing + /// with the `EntityComponentManager` directly. + class IGNITION_GAZEBO_VISIBLE SdfEntityCreator + { + /// \brief Constructor + /// \param[in] _ecm Entity component manager. This class keeps a pointer + /// to it, but doesn't assume ownership. + /// \param[in] _eventManager Event manager. This class keeps a pointer + /// to it, but doesn't assume ownership. + public: explicit SdfEntityCreator(EntityComponentManager &_ecm, + EventManager &_eventManager); + + /// \brief Copy constructor + /// \param[in] _creator SdfEntityCreator to copy. + public: SdfEntityCreator(const SdfEntityCreator &_creator); + + /// \brief Move constructor + /// \param[in] _creator SdfEntityCreator to move. + public: SdfEntityCreator(SdfEntityCreator &&_creator) noexcept; + + /// \brief Move assignment operator. + /// \param[in] _creator SdfEntityCreator component to move. + /// \return Reference to this. + public: SdfEntityCreator &operator=(SdfEntityCreator &&_creator) noexcept; + + /// \brief Copy assignment operator. + /// \param[in] _creator SdfEntityCreator to copy. + /// \return Reference to this. + public: SdfEntityCreator &operator=(const SdfEntityCreator &_creator); + + /// \brief Destructor. + public: ~SdfEntityCreator(); + + /// \brief Create all entities that exist in the sdf::World object and + /// load their plugins. + /// \param[in] _world SDF world object. + /// \return World entity. + public: Entity CreateEntities(const sdf::World *_world); + + /// \brief Create all entities that exist in the sdf::Model object and + /// load their plugins. Also loads plugins of child sensors. + /// \param[in] _model SDF model object. + /// \return Model entity. + public: Entity CreateEntities(const sdf::Model *_model); + + /// \brief Create all entities that exist in the sdf::Actor object and + /// load their plugins. + /// \param[in] _actor SDF actor object. + /// \return Actor entity. + public: Entity CreateEntities(const sdf::Actor *_actor); + + /// \brief Create all entities that exist in the sdf::Light object and + /// load their plugins. + /// \param[in] _light SDF light object. + /// \return Light entity. + public: Entity CreateEntities(const sdf::Light *_light); + + /// \brief Create all entities that exist in the sdf::Link object and + /// load their plugins. + /// \param[in] _link SDF link object. + /// \return Link entity. + public: Entity CreateEntities(const sdf::Link *_link); + + /// \brief Create all entities that exist in the sdf::Joint object and + /// load their plugins. + /// \param[in] _joint SDF joint object. + /// \return Joint entity. + public: Entity CreateEntities(const sdf::Joint *_joint); + + /// \brief Create all entities that exist in the sdf::Visual object and + /// load their plugins. + /// \param[in] _visual SDF visual object. + /// \return Visual entity. + public: Entity CreateEntities(const sdf::Visual *_visual); + + /// \brief Create all entities that exist in the sdf::Collision object and + /// load their plugins. + /// \param[in] _collision SDF collision object. + /// \return Collision entity. + public: Entity CreateEntities(const sdf::Collision *_collision); + + /// \brief Create all entities that exist in the sdf::Sensor object. + /// Sensor plugins won't be directly loaded by this function. + /// \param[in] _sensor SDF sensor object. + /// \return Sensor entity. + /// \sa CreateEntities(const sdf::Model *) + public: Entity CreateEntities(const sdf::Sensor *_sensor); + + /// \brief Request an entity deletion. This will insert the request + /// into a queue. The queue is processed toward the end of a simulation + /// update step. + /// \param[in] _entity Entity to be removed. + /// \param[in] _recursive Whether to recursively delete all child + /// entities. True by default. + public: void RequestRemoveEntity(const Entity _entity, + bool _recursive = true); + + /// \brief Set an entity's parent entity. This function takes care of + /// updating the `EntityComponentManager` and necessary components. + /// \param[in] _child Entity which should be parented. + /// \param[in] _parent Entity which should be _child's parent. + public: void SetParent(Entity _child, Entity _parent); + + /// \brief Overloaded function to recursively create model entities + /// and make sure a) only one canonical link is created per model tree, + /// and b) we override the nested model's static property to true if + /// its parent is static + /// \param[in] _model SDF model object. + /// \param[in] _createCanonicalLink True to create a canonical link + /// component and attach to its child link entity + /// \param[in] _staticParent True if parent is static, false otherwise. + /// \return Model entity. + private: Entity CreateEntities(const sdf::Model *_model, + bool _createCanonicalLink, bool _staticParent); + + /// \brief Pointer to private data. + private: std::unique_ptr dataPtr; + }; + } + } +} +#endif diff --git a/include/gz/sim/Server.hh b/include/gz/sim/Server.hh new file mode 100644 index 0000000000..0f2806fe37 --- /dev/null +++ b/include/gz/sim/Server.hh @@ -0,0 +1,295 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_SERVER_HH_ +#define GZ_GAZEBO_SERVER_HH_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace ignition +{ + namespace gazebo + { + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + // Forware declarations + class ServerPrivate; + + /// \class Server Server.hh ignition/gazebo/Server.hh + /// \brief The server instantiates and controls simulation. + /// + /// ## Example Usage + /// + /// A basic simulation server can be instantiated and run using + /// + /// ``` + /// gz::sim::Server server; + /// server.Run(); + /// ``` + /// + /// An SDF File can be passed into the server via a ServerConfig object. + /// The server will parse the SDF file and create entities for the + /// elements contained in the file. + /// + /// ``` + /// gz::sim::ServerConfig config; + /// config.SetSdfFile("path_to_file.sdf"); + /// gz::sim::Server server(config); + /// server.Run(); + /// ``` + /// + /// The Run() function accepts a few arguments, one of which is whether + /// simulation should start in a paused state. The default value of this + /// argument is true, which starts simulation paused. This means that by + /// default, running the server will cause systems to update but some + /// systems may not update because paused == true. For example, + /// a physics system will not update its state when paused is + /// true. So, while a Server can be Running, simulation itself can be + /// paused. + /// + /// Simulation is paused by default because a common use case is to load + /// a world from the command line. If simulation starts running, the + /// GUI client may miss the first few simulation iterations. + /// + /// ## Services + /// + /// The following are services provided by the Server. + /// The `` in the service list is the name of the + /// simulated world. + /// + /// List syntax: *service_name(request_msg_type) : response_msg_type* + /// + /// 1. `/world//scene/info(none)` : gz::msgs::Scene + /// + Returns the current scene information. + /// + /// 2. `/gazebo/resource_paths/get` : gz::msgs::StringMsg_V + /// + Get list of resource paths. + /// + /// 3. `/gazebo/resource_paths/add` : gz::msgs::Empty + /// + Add new resource paths. + /// + /// 4. `/server_control`(gz::msgs::ServerControl) : + /// gz::msgs::Boolean + /// + Control the simulation server. + /// + /// ## Topics + /// + /// The following are topics provided by the Server. + /// The `` in the service list is the name of the + /// simulated world. + /// + /// List syntax: *topic_name : published_msg_type* + /// + /// 1. `/world//clock` : gz::msgs::Clock + /// + /// 2. `/world//stats` : gz::msgs::WorldStatistics + /// + This topic is throttled to 5Hz. + /// + /// 3. `/gazebo/resource_paths` : gz::msgs::StringMsg_V + /// + Updated list of resource paths. + /// + class IGNITION_GAZEBO_VISIBLE Server + { + /// \brief Construct the server using the parameters specified in a + /// ServerConfig. + /// \param[in] _config Server configuration parameters. If this + /// parameter is omitted, then an empty world is loaded. + public: explicit Server(const ServerConfig &_config = ServerConfig()); + + /// \brief Destructor + public: ~Server(); + + /// \brief Set the update period. The update period is the wall-clock time + /// between ECS updates. + /// Note that this is different from the simulation update rate. ECS + /// systems will be updated even while sim time is paused. + /// \param[in] _updatePeriod Duration between updates. + /// \param[in] _worldIndex Index of the world to query. + public: void SetUpdatePeriod( + const std::chrono::steady_clock::duration &_updatePeriod, + const unsigned int _worldIndex = 0); + + /// \brief Run the server. By default this is a non-blocking call, + /// which means the server runs simulation in a separate thread. Pass + /// in true to the _blocking argument to run the server in the current + /// thread. + /// \param[in] _blocking False to run the server in a new thread. True + /// to run the server in the current thread. + /// \param[in] _iterations Number of steps to perform. A value of + /// zero will run indefinitely. + /// \param[in] _paused True to start simulation in a paused state, + /// false, to start simulation unpaused. + /// \return In non-blocking mode, the return value is true if a thread + /// was successfully created. In blocking mode, true will be returned + /// if the Server ran for the specified number of iterations or was + /// terminated. False will always be returned if signal handlers could + /// not be initialized, and if the server is already running. + public: bool Run(const bool _blocking = false, + const uint64_t _iterations = 0, + const bool _paused = true); + + /// \brief Run the server once, all systems will be updated once and + /// then this returns. This is a blocking call. + /// \param[in] _paused True to run the simulation in a paused state, + /// false to run simulation unpaused. The simulation iterations will + /// be increased by 1. + /// \return False if the server was terminated before completing, + /// not being initialized, or if the server is already running. + public: bool RunOnce(const bool _paused = true); + + /// \brief Get whether the server is running. The server can have zero + /// or more simulation worlds, each of which may or may not be + /// running. See Running(const unsigned int) to get the running status + /// of a world. + /// \return True if the server is running. + public: bool Running() const; + + /// \brief Get whether a world simulation instance is running. When + /// running is true, then systems are being updated but simulation may + /// or may not be stepping forward. Check the value of Paused() to + /// determine if a world simulation instance is stepping forward. + /// If Paused() returns true, then simulation is not stepping foward. + /// \param[in] _worldIndex Index of the world to query. + /// \return True if the server is running, or std::nullopt + /// if _worldIndex is invalid. + public: std::optional Running(const unsigned int _worldIndex) const; + + /// \brief Set whether a world simulation instance is paused. + /// When paused is true, then simulation for the world is not stepping + /// forward. + /// \param[in] _paused True to pause the world, false to unpause. + /// \param[in] _worldIndex Index of the world to query. + /// \return True if the world referenced by _worldIndex exists, false + /// otherwise. + public: bool SetPaused(const bool _paused, + const unsigned int _worldIndex = 0) const; + + /// \brief Get whether a world simulation instance is paused. + /// When paused is true, then simulation for the world is not stepping + /// forward. + /// \param[in] _worldIndex Index of the world to query. + /// \return True if the world simulation instance is paused, false if + /// stepping forward, or std::nullopt if _worldIndex is invalid. + public: std::optional Paused( + const unsigned int _worldIndex = 0) const; + + /// \brief Get the number of iterations the server has executed. + /// \param[in] _worldIndex Index of the world to query. + /// \return The current iteration count, + /// or std::nullopt if _worldIndex is invalid. + public: std::optional IterationCount( + const unsigned int _worldIndex = 0) const; + + /// \brief Get the number of entities on the server. + /// \param[in] _worldIndex Index of the world to query. + /// \return Entity count, or std::nullopt if _worldIndex is invalid. + public: std::optional EntityCount( + const unsigned int _worldIndex = 0) const; + + /// \brief Get the number of systems on the server. + /// \param[in] _worldIndex Index of the world to query. + /// \return System count, or std::nullopt if _worldIndex is invalid. + public: std::optional SystemCount( + const unsigned int _worldIndex = 0) const; + + /// \brief Add a System to the server. The server must not be running when + /// calling this. + /// \param[in] _system system to be added + /// \param[in] _worldIndex Index of the world to query. + /// \return Whether the system was added successfully, or std::nullopt + /// if _worldIndex is invalid. + public: std::optional AddSystem( + const SystemPluginPtr &_system, + const unsigned int _worldIndex = 0); + + /// \brief Add a System to the server. The server must not be running when + /// calling this. + /// \param[in] _system System to be added + /// \param[in] _worldIndex Index of the world to add to. + /// \return Whether the system was added successfully, or std::nullopt + /// if _worldIndex is invalid. + public: std::optional AddSystem( + const std::shared_ptr &_system, + const unsigned int _worldIndex = 0); + + /// \brief Get an Entity based on a name. + /// \details If multiple entities with the same name exist, the first + /// entity found will be returned. + /// \param [in] _name Name of the entity to get from the specified + /// world. + /// \param[in] _worldIndex Index of the world to query. + /// \return The entity, or std::nullopt if the entity or world + /// doesn't exist. + public: std::optional EntityByName(const std::string &_name, + const unsigned int _worldIndex = 0) const; + + /// \brief Return true if the specified world has an entity with the + /// provided name. + /// \param[in] _name Name of the entity. + /// \param[in] _worldIndex Index of the world. + /// \return True if the _worldIndex is valid and the + /// entity exists in the world. + public: bool HasEntity(const std::string &_name, + const unsigned int _worldIndex = 0) const; + + /// \brief Return true if the specified world has an entity with the + /// provided name and the entity was queued for deletion. Note that + /// the entity is not removed immediately. Entity deletion happens at + /// the end of the next (or current depending on when this function is + /// called) simulation step. + /// \details If multiple entities with the same name exist, only the + /// first entity found will be deleted. + /// \param[in] _name Name of the entity to delete. + /// \param[in] _recursive Whether to recursively delete all child + /// entities. True by default. + /// \param[in] _worldIndex Index of the world. + /// \return True if the entity exists in the world and it was queued + /// for deletion. + public: bool RequestRemoveEntity(const std::string &_name, + bool _recursive = true, + const unsigned int _worldIndex = 0); + + /// \brief Return true if the specified world has an entity with the + /// provided id and the entity was queued for deletion. Note that + /// the entity is not removed immediately. Entity deletion happens at + /// the end of the next (or current depending on when this function is + /// called) simulation step. + /// \param[in] _entity The entity to delete. + /// \param[in] _recursive Whether to recursively delete all child + /// entities. True by default. + /// \param[in] _worldIndex Index of the world. + /// \return True if the entity exists in the world and it was queued + /// for deletion. + public: bool RequestRemoveEntity(const Entity _entity, + bool _recursive = true, + const unsigned int _worldIndex = 0); + + /// \brief Private data + private: std::unique_ptr dataPtr; + }; + } + } +} + +#endif diff --git a/include/gz/sim/ServerConfig.hh b/include/gz/sim/ServerConfig.hh new file mode 100644 index 0000000000..8766127ae6 --- /dev/null +++ b/include/gz/sim/ServerConfig.hh @@ -0,0 +1,436 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_SERVERCONFIG_HH_ +#define GZ_GAZEBO_SERVERCONFIG_HH_ + +#include +#include +#include +#include // NOLINT(*) +#include +#include +#include +#include +#include + +namespace ignition +{ + namespace gazebo + { + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + // Forward declarations. + class ServerConfigPrivate; + + /// \class ServerConfig ServerConfig.hh ignition/gazebo/ServerConfig.hh + /// \brief Configuration parameters for a Server. An instance of this + /// object can be used to construct a Server with a particular + /// configuration. + class IGNITION_GAZEBO_VISIBLE ServerConfig + { + class PluginInfoPrivate; + /// \brief Information about a plugin that should be loaded by the + /// server. + /// \details Currently supports attaching a plugin to an entity given its + /// type and name, but it can't tell apart multiple entities with the same + /// name in different parts of the entity tree. + /// \sa const std::list &Plugins() const + public: class IGNITION_GAZEBO_VISIBLE PluginInfo + { + /// \brief Default constructor. + public: PluginInfo(); + + /// \brief Destructor. + public: ~PluginInfo(); + + /// \brief Constructor with plugin information specified. + /// \param[in] _entityName Name of the entity which should receive + /// this plugin. The name is used in conjuction with _entityType to + /// uniquely identify an entity. + /// \param[in] _entityType Entity type which should receive this + /// plugin. The type is used in conjuction with _entityName to + /// uniquely identify an entity. + /// \param[in] _filename Plugin library filename. + /// \param[in] _name Name of the interface within the plugin library + /// to load. + /// \param[in] _sdf Plugin XML elements associated with this plugin. + public: PluginInfo(const std::string &_entityName, + const std::string &_entityType, + const std::string &_filename, + const std::string &_name, + const sdf::ElementPtr &_sdf); + + /// \brief Copy constructor. + /// \param[in] _info Plugin to copy. + public: PluginInfo(const PluginInfo &_info); + + /// \brief Equal operator. + /// \param[in] _info PluginInfo to copy. + /// \return Reference to this class. + public: PluginInfo &operator=(const PluginInfo &_info); + + /// \brief Get the name of the entity which should receive + /// this plugin. The name is used in conjuction with _entityType to + /// uniquely identify an entity. + /// \return Entity name. + public: const std::string &EntityName() const; + + /// \brief Set the name of the entity which should receive + /// this plugin. The name is used in conjuction with _entityType to + /// uniquely identify an entity. + /// \param[in] _entityName Entity name. + public: void SetEntityName(const std::string &_entityName); + + /// \brief Get the entity type which should receive this + /// plugin. The type is used in conjuction with EntityName to + /// uniquely identify an entity. + /// \return Entity type string. + public: const std::string &EntityType() const; + + /// \brief Set the type of the entity which should receive this + /// plugin. The type is used in conjuction with EntityName to + /// uniquely identify an entity. + /// \param[in] _entityType Entity type string. + public: void SetEntityType(const std::string &_entityType); + + /// \brief Get the plugin library filename. + /// \return Plugin library filename. + public: const std::string &Filename() const; + + /// \brief Set the type of the entity which should receive this + /// plugin. The type is used in conjuction with EntityName to + /// uniquely identify an entity. + /// \param[in] _filename Entity type string. + public: void SetFilename(const std::string &_filename); + + /// \brief Name of the interface within the plugin library + /// to load. + /// \return Interface name. + public: const std::string &Name() const; + + /// \brief Set the name of the interface within the plugin library + /// to load. + /// \param[in] _name Interface name. + public: void SetName(const std::string &_name); + + /// \brief Plugin XML elements associated with this plugin. + /// \return SDF pointer. + public: const sdf::ElementPtr &Sdf() const; + + /// \brief Set the plugin XML elements associated with this plugin. + /// \param[in] _sdf SDF pointer, it will be cloned. + public: void SetSdf(const sdf::ElementPtr &_sdf); + + /// \brief Private data pointer + private: std::unique_ptr dataPtr; + }; + + /// \brief Constructor + public: ServerConfig(); + + /// \brief Copy constructor. + /// \param[in] _config ServerConfig to copy. + public: ServerConfig(const ServerConfig &_config); + + /// \brief Destructor + public: ~ServerConfig(); + + /// \brief Set an SDF file to be used with the server. + /// + /// Setting the SDF file will override any value set by `SetSdfString`. + /// + /// \param[in] _file Full path to an SDF file. + /// \return (reserved for future use) + public: bool SetSdfFile(const std::string &_file); + + /// \brief Get the SDF file that has been set. An empty string will be + /// returned if an SDF file has not been set. + /// \return The full path to the SDF file, or empty string. + public: std::string SdfFile() const; + + /// \brief Set an SDF string to be used by the server. + /// + /// Setting the SDF string will override any value set by `SetSdfFile`. + /// + /// \param[in] _sdfString Full path to an SDF file. + /// \return (reserved for future use) + public: bool SetSdfString(const std::string &_sdfString); + + /// \brief Get the SDF String that has been set. An empty string will + /// be returned if an SDF string has not been set. + /// \return The full contents of the SDF string, or empty string. + public: std::string SdfString() const; + + /// \brief Set the update rate in Hertz. Value <=0 are ignored. + /// \param[in] _hz The desired update rate of the server in Hertz. + public: void SetUpdateRate(const double &_hz); + + /// \brief Get the update rate in Hertz. + /// \return The desired update rate of the server in Hertz, or nullopt if + /// an UpdateRate has not been set. + public: std::optional UpdateRate() const; + + /// \brief Get whether the server is using the level system + /// \return True if the server is set to use the level system + public: bool UseLevels() const; + + /// \brief Get whether the server is using the level system. + /// \param[in] _levels Value to set. + public: void SetUseLevels(const bool _levels); + + /// \brief Get whether the server is using the distributed sim system + /// \return True if the server is set to use the distributed simulation + /// system + /// \sa SetNetworkRole(const std::string &_role) + public: bool UseDistributedSimulation() const; + + /// \brief Set the number of network secondary servers that the + /// primary server should expect. This value is valid only when + /// SetNetworkRole("primary") is also used. + /// \param[in] _secondaries Number of secondary servers. + /// \sa SetNetworkRole(const std::string &_role) + /// \sa NetworkRole() const + public: void SetNetworkSecondaries(unsigned int _secondaries); + + /// \brief Get the number of secondary servers that a primary server + /// should expect. + /// \return Number of secondary servers. + /// \sa SetNetworkSecondaries(unsigned int _secondaries) + public: unsigned int NetworkSecondaries() const; + + /// \brief Set the network role, which is one of [primary, secondary]. + /// If primary is used, then make sure to also set the numer of + /// network secondaries via + /// SetNetworkSecondaries(unsigned int _secondaries). + /// \param[in] _role Network role, one of [primary, secondary]. + /// \note Setting a network role enables distributed simulation. + /// \sa SetNetworkSecondaries(unsigned int _secondaries) + public: void SetNetworkRole(const std::string &_role); + + /// \brief Get the network role. See + /// SetNetworkRole(const std::string &_role) for more information + /// about distributed simulation and network roles. + /// \return The network role. + /// \sa SetNetworkRole(const std::string &_role) + public: std::string NetworkRole() const; + + /// \brief Get whether the server is recording states + /// \return True if the server is set to record states + public: bool UseLogRecord() const; + + /// \brief Set whether the server is recording states + /// \param[in] _record Value to set + public: void SetUseLogRecord(const bool _record); + + /// \brief Get path to place recorded states + /// \return Path to place recorded states + public: const std::string LogRecordPath() const; + + /// \brief Set path to place recorded states + /// \param[in] _recordPath Path to place recorded states + public: void SetLogRecordPath(const std::string &_recordPath); + + /// \brief Get whether to ignore the path specified in SDF. + /// \return Whether to ignore the path specified in SDF + /// TODO(anyone) Deprecate on Dome, SDF path will always be ignored. + public: bool LogIgnoreSdfPath() const; + + /// \brief Set whether to ignore the path specified in SDF. Path in SDF + /// should be ignored if a record path is specified on the command line, + /// for example. + /// \param[in] _ignore Whether to ignore the path specified in SDF + /// TODO(anyone) Deprecate on Dome, SDF path will always be ignored. + public: void SetLogIgnoreSdfPath(bool _ignore); + + /// \brief Add a topic to record. + /// \param[in] _topic Topic name, which can include wildcards. + public: void AddLogRecordTopic(const std::string &_topic); + + /// \brief Clear topics to record. This will remove all topics set + /// using AddLogRecordTopic. + public: void ClearLogRecordTopics(); + + /// \brief Get the topics to record that were added using + /// AddLogRecordTopic. + /// \return The topics to record. + public: const std::vector &LogRecordTopics() const; + + /// \brief Get path to recorded states to play back + /// \return Path to recorded states + public: const std::string LogPlaybackPath() const; + + /// \brief Set path to recorded states to play back + /// \param[in] _playbackPath Path to recorded states + public: void SetLogPlaybackPath(const std::string &_playbackPath); + + /// \brief Get whether meshes and material files are recorded + /// \return True if resources should be recorded. + public: bool LogRecordResources() const; + + /// \brief Set whether meshes and material files are recorded + /// \param[in] _recordResources Value to set + public: void SetLogRecordResources(bool _recordResources); + + /// \brief Get file path to compress log files to + /// \return File path to compress log files to + public: std::string LogRecordCompressPath() const; + + /// \brief Set file path to compress log files to + /// \param[in] _path File path to compress log files to + public: void SetLogRecordCompressPath(const std::string &_path); + + /// \brief The given random seed. + /// \return The random seed or 0 if not specified. + public: unsigned int Seed() const; + + /// \brief Set the random seed. + /// \param[in] _seed The seed. + public: void SetSeed(unsigned int _seed); + + /// \brief Get the update period duration. + /// \return The desired update period, or nullopt if + /// an UpdateRate has not been set. + public: std::optional + UpdatePeriod() const; + + /// \brief Path to where simulation resources, such as models downloaded + /// 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. + 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. + public: void SetResourceCache(const std::string &_path); + + /// \brief Physics engine plugin library to load. + /// \return File containing physics engine library. + public: const std::string &PhysicsEngine() const; + + /// \brief Set the physics engine plugin library. + /// \param[in] _physicsEngine File containing physics engine library. + public: void SetPhysicsEngine(const std::string &_physicsEngine); + + /// \brief Render engine plugin library to load. + /// \return File containing render engine library. + public: const std::string &RenderEngineServer() const; + + /// \brief Render engine plugin library to load. + /// \return File containing render engine library. + public: const std::string &RenderEngineGui() const; + + /// \brief Set the render engine server plugin library. + /// \param[in] _renderEngineServer File containing render engine library. + public: void SetRenderEngineServer( + const std::string &_renderEngineServer); + + /// \brief Set the render engine gui plugin library. + /// \param[in] _renderEngineGui File containing render engine library. + public: void SetRenderEngineGui(const std::string &_renderEngineGui); + + /// \brief Instruct simulation to attach a plugin to a specific + /// entity when simulation starts. + /// \param[in] _info Information about the plugin to load. + public: void AddPlugin(const PluginInfo &_info); + + /// \brief Add multiple plugins to the simulation + /// \param[in] _plugins List of Information about the plugin to load. + public: void AddPlugins(const std::list &_plugins); + + /// \brief Generate PluginInfo for Log recording based on the + /// internal state of this ServerConfig object: + /// \sa UseLogRecord + /// \sa LogRecordPath + /// \sa LogRecordResources + /// \sa LogRecordCompressPath + /// \sa LogRecordTopics + public: PluginInfo LogRecordPlugin() const; + + /// \brief Generate PluginInfo for Log playback based on the + /// internal state of this ServerConfig object: + /// \sa LogPlaybackPath + public: PluginInfo LogPlaybackPlugin() const; + + /// \brief Get all the plugins that should be loaded. + /// \return A list of all the plugins specified via + /// AddPlugin(const PluginInfo &). + public: const std::list &Plugins() const; + + /// \brief Equal operator. + /// \param[in] _cfg ServerConfig to copy. + /// \return Reference to this class. + public: ServerConfig &operator=(const ServerConfig &_cfg); + + /// \brief Get the timestamp of this ServerConfig. This is the system + /// time when this ServerConfig was created. The timestamp is used + /// internally to create log file paths so that both state and console + /// logs are co-located. + /// \return Time when this ServerConfig was created. + public: const std::chrono::time_point & + Timestamp() const; + + /// \brief Private data pointer + private: std::unique_ptr dataPtr; + }; + + /// \brief Parse plugins from XML configuration file. + /// \param[in] _fname Absolute path to the configuration file to parse. + /// \return A list of all of the plugins found in the configuration file + std::list + IGNITION_GAZEBO_VISIBLE + parsePluginsFromFile(const std::string &_fname); + + /// \brief Parse plugins from XML configuration string. + /// \param[in] _str XML configuration content to parse + /// \return A list of all of the plugins found in the configuration string. + std::list + IGNITION_GAZEBO_VISIBLE + parsePluginsFromString(const std::string &_str); + + /// \brief Load plugin information, following ordering. + /// + /// This method is used when no plugins are found in an SDF + /// file to load either a default or custom set of plugins. + /// + /// The following order is used to resolve: + /// 1. Config file located at IGN_GAZEBO_SERVER_CONFIG_PATH environment + /// variable. + /// * If IGN_GAZEBO_SERVER_CONFIG_PATH is set but empty, no plugins + /// are loaded. + /// 2. File at ${IGN_HOMEDIR}/.ignition/gazebo/server.config + /// 3. File at ${IGN_DATA_INSTALL_DIR}/server.config + /// + /// If any of the above files exist but are empty, resolution + /// stops and the plugin list will be empty. + /// + // + /// \param[in] _isPlayback Is the server in playback mode. If so, fallback + /// to playback_server.config. + // + /// \return A list of plugins to load, based on above ordering + std::list + IGNITION_GAZEBO_VISIBLE + loadPluginInfo(bool _isPlayback = false); + } + } +} + +#endif diff --git a/include/gz/sim/System.hh b/include/gz/sim/System.hh new file mode 100644 index 0000000000..cb7b92c0d4 --- /dev/null +++ b/include/gz/sim/System.hh @@ -0,0 +1,126 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_SYSTEM_HH_ +#define GZ_GAZEBO_SYSTEM_HH_ + +#include + +#include +#include +#include +#include +#include + +#include + +namespace ignition +{ + namespace gazebo + { + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + /// \brief Namespace for all System plugins. Refer to the System class for + /// more information about systems. + namespace systems {} + + /// \class System System.hh ignition/gazebo/System.hh + /// \brief Base class for a System. + /// + /// A System operates on Entities that have certain Components. A System + /// will only operate on an Entity if it has all of the required + /// Components. + /// + /// Systems are executed in three phases, with each phase for a given step + /// corresponding to the entities at time UpdateInfo::simTime: + /// * PreUpdate + /// * Has read-write access to world entities and components. + /// * This is where systems say what they'd like to happen at time + /// UpdateInfo::simTime. + /// * Can be used to modify state before physics runs, for example for + /// applying control signals or performing network syncronization. + /// * Update + /// * Has read-write access to world entities and components. + /// * Used for physics simulation step (i.e., simulates what happens at + /// time UpdateInfo::simTime). + /// * PostUpdate + /// * Has read-only access to world entities and components. + /// * Captures everything that happened at time UpdateInfo::simTime. + /// * Used to read out results at the end of a simulation step to be used + /// for sensor or controller updates. + /// + /// It's important to note that UpdateInfo::simTime does not refer to the + /// current time, but the time reached after the PreUpdate and Update calls + /// have finished. So, if any of the *Update functions are called with + /// simulation paused, time does not advance, which means the time reached + /// after PreUpdate and Update is the same as the starting time. This + /// explains why UpdateInfo::simTime is initially 0 if simulation is started + /// paused, while UpdateInfo::simTime is initially UpdateInfo::dt if + /// simulation is started un-paused. + class IGNITION_GAZEBO_VISIBLE System + { + /// \brief Constructor + public: System(); + + /// \brief Destructor + public: virtual ~System(); + }; + + /// \class ISystemConfigure ISystem.hh ignition/gazebo/System.hh + /// \brief Interface for a system that implements optional configuration + /// + /// Configure is called after the system is instatiated and all entities + /// and components are loaded from the corresponding SDF world, and before + /// simulation begins exectution. + class IGNITION_GAZEBO_VISIBLE ISystemConfigure { + /// \brief Configure the system + /// \param[in] _entity The entity this plugin is attached to. + /// \param[in] _sdf The SDF Element associated with this system plugin. + /// \param[in] _ecm The EntityComponentManager of the given simulation + /// instance. + /// \param[in] _eventMgr The EventManager of the given simulation + /// instance. + public: virtual void Configure( + const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + EventManager &_eventMgr) = 0; + }; + + /// \class ISystemPreUpdate ISystem.hh ignition/gazebo/System.hh + /// \brief Interface for a system that uses the PreUpdate phase + class IGNITION_GAZEBO_VISIBLE ISystemPreUpdate { + public: virtual void PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) = 0; + }; + + /// \class ISystemUpdate ISystem.hh ignition/gazebo/System.hh + /// \brief Interface for a system that uses the Update phase + class IGNITION_GAZEBO_VISIBLE ISystemUpdate { + public: virtual void Update(const UpdateInfo &_info, + EntityComponentManager &_ecm) = 0; + }; + + /// \class ISystemPostUpdate ISystem.hh ignition/gazebo/System.hh + /// \brief Interface for a system that uses the PostUpdate phase + class IGNITION_GAZEBO_VISIBLE ISystemPostUpdate{ + public: virtual void PostUpdate(const UpdateInfo &_info, + const EntityComponentManager &_ecm) = 0; + }; + } + } +} +#endif diff --git a/include/gz/sim/SystemLoader.hh b/include/gz/sim/SystemLoader.hh new file mode 100644 index 0000000000..6c8eef0b5f --- /dev/null +++ b/include/gz/sim/SystemLoader.hh @@ -0,0 +1,81 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_SYSTEMLOADER_HH_ +#define GZ_GAZEBO_SYSTEMLOADER_HH_ + +#include +#include +#include + +#include + +#include +#include +#include + +namespace ignition +{ + namespace gazebo + { + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + // Forward declarations. + class IGNITION_GAZEBO_HIDDEN SystemLoaderPrivate; + + /// \class SystemLoader SystemLoader.hh ignition/gazebo/SystemLoader.hh + /// \brief Class for loading/unloading System plugins. + class IGNITION_GAZEBO_VISIBLE SystemLoader + { + /// \brief Constructor + public: explicit SystemLoader(); + + /// \brief Destructor + public: ~SystemLoader(); + + /// \brief Add path to search for plugins. + /// \param[in] _path New path to be added. + public: void AddSystemPluginPath(const std::string &_path); + + /// \brief Load and instantiate system plugin from an SDF element. + /// \param[in] _sdf SDF Element describing plugin instance to be loaded. + /// \returns Shared pointer to system instance or nullptr. + public: std::optional LoadPlugin( + const sdf::ElementPtr &_sdf); + + /// \brief Load and instantiate system plugin from name/filename. + /// \param[in] _filename Shared library filename to load plugin from. + /// \param[in] _name Class name to be instantiated. + /// \param[in] _sdf SDF Element describing plugin instance to be loaded. + /// \returns Shared pointer to system instance or nullptr. + public: std::optional LoadPlugin( + const std::string &_filename, + const std::string &_name, + const sdf::ElementPtr &_sdf); + + /// \brief Makes a printable string with info about systems + /// \returns A pretty string + public: std::string PrettyStr() const; + + /// \brief Pointer to private data. + private: std::unique_ptr dataPtr; + }; + } + using SystemLoaderPtr = std::shared_ptr; + } +} +#endif // GZ_GAZEBO_SYSTEMLOADER_HH_ + diff --git a/include/gz/sim/SystemPluginPtr.hh b/include/gz/sim/SystemPluginPtr.hh new file mode 100644 index 0000000000..42979e46d5 --- /dev/null +++ b/include/gz/sim/SystemPluginPtr.hh @@ -0,0 +1,37 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_SYSTEMPLUGINPTR_HH_ +#define GZ_GAZEBO_SYSTEMPLUGINPTR_HH_ + +#include +#include + +namespace ignition +{ + namespace gazebo + { + using SystemPluginPtr = gz::plugin::SpecializedPluginPtr< + System, + ISystemConfigure, + ISystemPreUpdate, + ISystemUpdate, + ISystemPostUpdate + >; + } +} + +#endif diff --git a/include/gz/sim/TestFixture.hh b/include/gz/sim/TestFixture.hh new file mode 100644 index 0000000000..83bcd897d4 --- /dev/null +++ b/include/gz/sim/TestFixture.hh @@ -0,0 +1,113 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_TESTFIXTURE_HH_ +#define GZ_GAZEBO_TESTFIXTURE_HH_ + +#include +#include + +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/ServerConfig.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +// +class IGNITION_GAZEBO_HIDDEN TestFixturePrivate; +/// \brief Helper class to write automated tests. It provides a convenient API +/// to load a world file, step simulation and check entities and components. +/// +/// ## Usage +/// +/// // Load a world with a fixture +/// gz::sim::TestFixture fixture("path_to.sdf"); +/// +/// // Register callbacks, for example: +/// fixture.OnPostUpdate([&](const gz::sim::UpdateInfo &, +/// const gz::sim::EntityComponentManager &_ecm) +/// { +/// // Add expectations here +/// }).Finalize(); +/// // Be sure to call finalize before running the server. +/// +/// // Run the server +/// fixture.Server()->Run(true, 1000, false); +/// +class IGNITION_GAZEBO_VISIBLE TestFixture +{ + /// \brief Constructor + /// \param[in] _path Path to SDF file. + public: explicit TestFixture(const std::string &_path); + + /// \brief Constructor + /// \param[in] _config Server config file + public: explicit TestFixture(const ServerConfig &_config); + + /// \brief Destructor + public: virtual ~TestFixture(); + + /// \brief Wrapper around a system's pre-update callback + /// \param[in] _cb Function to be called every pre-update + /// The _entity and _sdf will correspond to the world entity. + /// \return Reference to self. + public: TestFixture &OnConfigure(std::function &_sdf, + EntityComponentManager &_ecm, + EventManager &_eventMgr)> _cb); + + /// \brief Wrapper around a system's pre-update callback + /// \param[in] _cb Function to be called every pre-update + /// \return Reference to self. + public: TestFixture &OnPreUpdate(std::function _cb); + + /// \brief Wrapper around a system's update callback + /// \param[in] _cb Function to be called every update + /// \return Reference to self. + public: TestFixture &OnUpdate(std::function _cb); + + /// \brief Wrapper around a system's post-update callback + /// \param[in] _cb Function to be called every post-update + /// \return Reference to self. + public: TestFixture &OnPostUpdate(std::function _cb); + + /// \brief Finalize all the functions and add fixture to server. + /// Finalize must be called before running the server, otherwise none of the + /// `On*` functions will be called. + /// The `OnConfigure` callback is called immediately on finalize. + public: TestFixture &Finalize(); + + /// \brief Get pointer to underlying server. + public: std::shared_ptr Server() const; + + /// \internal + /// \brief Pointer to private data. + // TODO(chapulina) Use IGN_UTILS_UNIQUE_IMPL_PTR(dataPtr) when porting to v6 + private: TestFixturePrivate *dataPtr; +}; +} +} +} +#endif diff --git a/include/gz/sim/Types.hh b/include/gz/sim/Types.hh new file mode 100644 index 0000000000..b36001c9ce --- /dev/null +++ b/include/gz/sim/Types.hh @@ -0,0 +1,105 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_TYPES_HH_ +#define GZ_GAZEBO_TYPES_HH_ + +#include +#include +#include +#include +#include + +namespace ignition +{ + namespace gazebo + { + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + // Forward declarations. + class EntityComponentManager; + + /// \brief Information passed to systems on the update callback. + /// \todo(louise) Update descriptions once reset is supported. + struct UpdateInfo + { + /// \brief Total time elapsed in simulation. This will not increase while + /// paused. + std::chrono::steady_clock::duration simTime{0}; + + /// \brief Total wall clock time elapsed while simulation is running. This + /// will not increase while paused. + std::chrono::steady_clock::duration realTime{0}; + + /// \brief Simulation time handled during a single update. + std::chrono::steady_clock::duration dt{0}; + + /// \brief Total number of elapsed simulation iterations. + // cppcheck-suppress unusedStructMember + uint64_t iterations{0}; + + /// \brief True if simulation is paused, which means the simulation + /// time is not currently running, but systems are still being updated. + /// It is the responsibilty of a system update appropriately based on + /// the status of paused. For example, a physics systems should not + /// update state when paused is true. + // cppcheck-suppress unusedStructMember + bool paused{true}; + }; + + /// \brief Possible states for a component. + enum class ComponentState + { + /// \brief Component value has not changed. + NoChange = 0, + + /// \brief Component value has changed, and is changing periodically. + /// This indicates to systems that it is ok to drop a few samples. + PeriodicChange = 1, + + /// \brief Component value has suffered a one-time change. + /// This indicates to systems that this change must be processed and + /// can't be dropped. + OneTimeChange = 2 + }; + + /// \brief A unique identifier for a component instance. The uniqueness + /// of a ComponentId is scoped to the component's type. + /// \sa ComponentKey. + using ComponentId = int; + + /// \brief A unique identifier for a component type. A component type + /// must be derived from `components::BaseComponent` and can contain plain + /// data or something more complex like `gz::math::Pose3d`. + using ComponentTypeId = uint64_t; + + /// \brief A key that uniquely identifies, at the global scope, a component + /// instance + using ComponentKey = std::pair; + + /// \brief typedef for query callbacks + using EntityQueryCallback = std::function; + + /// \brief Id that indicates an invalid component. + static const ComponentId kComponentIdInvalid = -1; + + /// \brief Id that indicates an invalid component type. + static const ComponentTypeId kComponentTypeIdInvalid = UINT64_MAX; + } + } +} +#endif diff --git a/include/gz/sim/Util.hh b/include/gz/sim/Util.hh new file mode 100644 index 0000000000..9741933c6a --- /dev/null +++ b/include/gz/sim/Util.hh @@ -0,0 +1,258 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_UTIL_HH_ +#define GZ_GAZEBO_UTIL_HH_ + +#include + +#include +#include +#include + +#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 +{ + namespace gazebo + { + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + // + /// \brief Helper function to compute world pose of an entity + /// \param[in] _entity Entity to get the world pose for + /// \param[in] _ecm Immutable reference to ECM. + /// \return World pose of entity + math::Pose3d IGNITION_GAZEBO_VISIBLE worldPose(const Entity &_entity, + const EntityComponentManager &_ecm); + + /// \brief Helper function to generate scoped name for an entity. + /// \param[in] _entity Entity to get the name for. + /// \param[in] _ecm Immutable reference to ECM. + /// \param[in] _delim Delimiter to put between names, defaults to "/". + /// \param[in] _includePrefix True to include the type prefix before the + /// entity name + std::string IGNITION_GAZEBO_VISIBLE scopedName(const Entity &_entity, + const EntityComponentManager &_ecm, const std::string &_delim = "/", + bool _includePrefix = true); + + /// \brief Helper function to get an entity given its scoped name. + /// The scope may start at any level by default. For example, in this + /// hierarchy: + /// + /// world_name + /// model_name + /// link_name + /// + /// All these names will return the link entity: + /// + /// * world_name::model_name::link_name + /// * model_name::link_name + /// * link_name + /// + /// \param[in] _scopedName Entity's scoped name. + /// \param[in] _ecm Immutable reference to ECM. + /// \param[in] _relativeTo Entity that the scoped name is relative to. The + /// scoped name does not include the name of this entity. If not provided, + /// the scoped name could be relative to any entity. + /// \param[in] _delim Delimiter between names, defaults to "::", it can't + /// be empty. + /// \return All entities that match the scoped name and relative to + /// requirements, or an empty set otherwise. + std::unordered_set IGNITION_GAZEBO_VISIBLE entitiesFromScopedName( + const std::string &_scopedName, const EntityComponentManager &_ecm, + Entity _relativeTo = kNullEntity, + const std::string &_delim = "::"); + + /// \brief Generally, each entity will be of some specific high-level type, + /// such as World, Sensor, Collision, etc, and one type only. + /// The entity type is usually marked by having some component that + /// represents that type, such as `gz::sim::components::Visual`. + /// + /// This function returns the type ID of the given entity's type, which + /// can be checked against different types. For example, if the + /// entity is a model, this will be true: + /// + /// `sim::components::Model::typeId == entityTypeId(entity, ecm)` + /// + /// In case the entity isn't of any known type, this will return + /// `gz::sim::kComponentTypeIdInvalid`. + /// + /// In case the entity has more than one type, only one of them will be + /// returned. This is not standard usage. + /// + /// \param[in] _entity Entity to get the type for. + /// \param[in] _ecm Immutable reference to ECM. + /// \return ID of entity's type-defining components. + ComponentTypeId IGNITION_GAZEBO_VISIBLE entityTypeId(const Entity &_entity, + const EntityComponentManager &_ecm); + + /// \brief Generally, each entity will be of some specific high-level type, + /// such as "world", "sensor", "collision", etc, and one type only. + /// + /// This function returns a lowercase string for each type. For example, + /// "light", "actor", etc. + /// + /// In case the entity isn't of any known type, this will return an empty + /// string. + /// + /// In case the entity has more than one type, only one of them will be + /// returned. This is not standard usage. + /// + /// Note that this is different from component type names. + /// + /// \param[in] _entity Entity to get the type for. + /// \param[in] _ecm Immutable reference to ECM. + /// \return ID of entity's type-defining components. + std::string IGNITION_GAZEBO_VISIBLE entityTypeStr(const Entity &_entity, + const EntityComponentManager &_ecm); + + /// \brief Get the world to which the given entity belongs. + /// \param[in] _entity Entity to get the world for. + /// \param[in] _ecm Immutable reference to ECM. + /// \return World entity ID. + Entity IGNITION_GAZEBO_VISIBLE worldEntity(const Entity &_entity, + const EntityComponentManager &_ecm); + + /// \brief Get the first world entity that's found. + /// \param[in] _ecm Immutable reference to ECM. + /// \return World entity ID. + Entity IGNITION_GAZEBO_VISIBLE worldEntity( + const EntityComponentManager &_ecm); + + /// \brief Helper function to remove a parent scope from a given name. + /// This removes the first name found before the delimiter. + /// \param[in] _name Input name possibly generated by scopedName. + /// \param[in] _delim Delimiter between names. + /// \return A new string with the parent scope removed. + std::string IGNITION_GAZEBO_VISIBLE removeParentScope( + const std::string &_name, const std::string &_delim); + + /// \brief Combine a URI and a file path into a full path. + /// If the URI is already a full path or contains a scheme, it won't be + /// modified. + /// If the URI is a relative path, the file path will be prepended. + /// \param[in] _uri URI, which can have a scheme, or be full or relative + /// paths. + /// \param[in] _filePath The path to a file in disk. + /// \return The full path URI. + std::string IGNITION_GAZEBO_VISIBLE asFullPath(const std::string &_uri, + const std::string &_filePath); + + /// \brief Get resource paths based on latest environment variables. + /// \return All paths in the IGN_GAZEBO_RESOURCE_PATH variable. + std::vector IGNITION_GAZEBO_VISIBLE resourcePaths(); + + /// \brief Add resource paths based on latest environment variables. + /// This will update the SDF and Ignition environment variables, and + /// optionally add more paths to the list. + /// \param[in] _paths Optional paths to add. + void IGNITION_GAZEBO_VISIBLE addResourcePaths( + const std::vector &_paths = {}); + + /// \brief Get the top level model of an entity + /// \param[in] _entity Input entity + /// \param[in] _ecm Constant reference to ECM. + /// \return Entity of top level model. If _entity has no top level model, + /// kNullEntity is returned. + gz::sim::Entity IGNITION_GAZEBO_VISIBLE topLevelModel( + const Entity &_entity, const EntityComponentManager &_ecm); + + /// \brief Helper function to generate a valid transport topic, given + /// a list of topics ordered by preference. The generated topic will be, + /// in this order: + /// + /// 1. The first topic unchanged, if valid. + /// 2. A valid version of the first topic, if possible. + /// 3. The second topic unchanged, if valid. + /// 4. A valid version of the second topic, if possible. + /// 5. ... + /// 6. If no valid topics could be generated, return an empty string. + /// + /// \param[in] _topics Topics ordered by preference. + std::string IGNITION_GAZEBO_VISIBLE validTopic( + const std::vector &_topics); + + /// \brief Helper function to "enable" a component (i.e. create it if it + /// doesn't exist) or "disable" a component (i.e. remove it if it exists). + /// \param[in] _ecm Mutable reference to the ECM + /// \param[in] _entity Entity whose component is being enabled + /// \param[in] _enable True to enable (create), false to disable (remove). + /// Defaults to true. + /// \return True if a component was created or removed, false if nothing + /// changed. + template + bool enableComponent(EntityComponentManager &_ecm, + Entity _entity, bool _enable = true) + { + bool changed{false}; + + auto exists = _ecm.Component(_entity); + if (_enable && !exists) + { + _ecm.CreateComponent(_entity, ComponentType()); + changed = true; + } + else if (!_enable && exists) + { + _ecm.RemoveComponent(_entity); + changed = true; + } + return changed; + } + + /// \brief Helper function to get an entity from an entity message. + /// The returned entity is not guaranteed to exist. + /// + /// The message is used as follows: + /// + /// if id not null + /// use id + /// else if name not null and type not null + /// use name + type + /// else + /// error + /// end + /// + /// \param[in] _ecm Entity component manager + /// \param[in] _msg Entity message + /// \return Entity ID, or kNullEntity if a matching entity couldn't be + /// found. + Entity IGNITION_GAZEBO_VISIBLE entityFromMsg( + const EntityComponentManager &_ecm, const msgs::Entity &_msg); + + /// \brief Environment variable holding resource paths. + const std::string kResourcePathEnv{"IGN_GAZEBO_RESOURCE_PATH"}; + + /// \brief Environment variable used by SDFormat to find URIs inside + /// `` + const std::string kSdfPathEnv{"SDF_PATH"}; + + /// \brief Environment variable holding server config paths. + const std::string kServerConfigPathEnv{"IGN_GAZEBO_SERVER_CONFIG_PATH"}; + + /// \brief Environment variable holding paths to custom rendering engine + /// plugins. + const std::string kRenderPluginPathEnv{"IGN_GAZEBO_RENDER_ENGINE_PATH"}; + } + } +} +#endif diff --git a/include/gz/sim/World.hh b/include/gz/sim/World.hh new file mode 100644 index 0000000000..b609aad35f --- /dev/null +++ b/include/gz/sim/World.hh @@ -0,0 +1,189 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_WORLD_HH_ +#define GZ_GAZEBO_WORLD_HH_ + +#include +#include +#include + +#include +#include + +#include "gz/sim/config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Types.hh" + +namespace ignition +{ + namespace gazebo + { + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + // Forward declarations. + class IGNITION_GAZEBO_HIDDEN WorldPrivate; + // + /// \class World World.hh ignition/gazebo/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. + /// All the functions provided here are meant to be used with a world + /// entity. + /// + /// For example, given a world's entity, to find the value of its + /// name component, one could use the entity-component manager (`ecm`) + /// directly as follows: + /// + /// std::string name = ecm.Component(entity)->Data(); + /// + /// Using this class however, the same information can be obtained with + /// a simpler function call: + /// + /// World world(entity); + /// std::string name = world.Name(ecm); + class IGNITION_GAZEBO_VISIBLE World { + /// \brief Constructor + /// \param[in] _entity World entity + public: explicit World(gz::sim::Entity _entity = kNullEntity); + + /// \brief Copy constructor + /// \param[in] _world World to copy. + public: World(const World &_world); + + /// \brief Move constructor + /// \param[in] _world World to move. + public: World(World &&_world) noexcept; + + /// \brief Move assignment operator. + /// \param[in] _world World component to move. + /// \return Reference to this. + public: World &operator=(World &&_world) noexcept; + + /// \brief Copy assignment operator. + /// \param[in] _world World to copy. + /// \return Reference to this. + public: World &operator=(const World &_world); + + /// \brief Destructor + public: virtual ~World(); + + /// \brief Get the entity which this World is related to. + /// \return World entity. + public: gz::sim::Entity Entity() const; + + /// \brief Check whether this world correctly refers to an entity that + /// has a components::World. + /// \param[in] _ecm Entity-component manager. + /// \return True if it's a valid world in the manager. + public: bool Valid(const EntityComponentManager &_ecm) const; + + /// \brief Get the world's unscoped name. + /// \param[in] _ecm Entity-component manager. + /// \return World's name or nullopt if the entity does not have a + /// components::Name component + public: std::optional Name( + const EntityComponentManager &_ecm) const; + + /// \brief Get the gravity in m/s^2. + /// \param[in] _ecm Entity-component manager. + /// \return Gravity vector or nullopt if the entity does not + /// have a components::Gravity component. + public: std::optional Gravity( + const EntityComponentManager &_ecm) const; + + /// \brief Get the magnetic field in Tesla. + /// \param[in] _ecm Entity-component manager. + /// \return Magnetic field vector or nullopt if the entity does not + /// have a components::MagneticField component. + public: std::optional MagneticField( + const EntityComponentManager &_ecm) const; + + /// \brief Get atmosphere information. + /// \param[in] _ecm Entity-component manager. + /// \return Magnetic field vector or nullopt if the entity does not + /// have a components::Atmosphere component. + public: std::optional Atmosphere( + const EntityComponentManager &_ecm) const; + + /// \brief Get the ID of a light entity which is an immediate child of + /// this world. + /// \param[in] _ecm Entity-component manager. + /// \param[in] _name Light name. + /// \return Light entity. + public: gz::sim::Entity LightByName(const EntityComponentManager &_ecm, + const std::string &_name) const; + + /// \brief Get the ID of a actor entity which is an immediate child of + /// this world. + /// \param[in] _ecm Entity-component manager. + /// \param[in] _name Actor name. + /// \return Actor entity. + public: gz::sim::Entity ActorByName(const EntityComponentManager &_ecm, + const std::string &_name) const; + + /// \brief Get the ID of a model entity which is an immediate child of + /// this world. + /// \param[in] _ecm Entity-component manager. + /// \param[in] _name Model name. + /// \return Model entity. + public: gz::sim::Entity ModelByName(const EntityComponentManager &_ecm, + const std::string &_name) const; + + /// \brief Get all lights which are immediate children of this world. + /// \param[in] _ecm Entity-component manager. + /// \return All lights in this world. + public: std::vector Lights( + const EntityComponentManager &_ecm) const; + + /// \brief Get all actors which are immediate children of this world. + /// \param[in] _ecm Entity-component manager. + /// \return All actors in this world. + public: std::vector Actors( + const EntityComponentManager &_ecm) const; + + /// \brief Get all models which are immediate children of this world. + /// \param[in] _ecm Entity-component manager. + /// \return All models in this world. + public: std::vector Models( + const EntityComponentManager &_ecm) const; + + /// \brief Get the number of lights which are immediate children of this + /// world. + /// \param[in] _ecm Entity-component manager. + /// \return Number of lights in this world. + public: uint64_t LightCount(const EntityComponentManager &_ecm) const; + + /// \brief Get the number of actors which are immediate children of this + /// world. + /// \param[in] _ecm Entity-component manager. + /// \return Number of actors in this world. + public: uint64_t ActorCount(const EntityComponentManager &_ecm) const; + + /// \brief Get the number of models which are immediate children of this + /// world. + /// \param[in] _ecm Entity-component manager. + /// \return Number of models in this world. + public: uint64_t ModelCount(const EntityComponentManager &_ecm) const; + + /// \brief Pointer to private data. + private: std::unique_ptr dataPtr; + }; + } + } +} +#endif diff --git a/include/gz/sim/components/Actor.hh b/include/gz/sim/components/Actor.hh new file mode 100644 index 0000000000..29a32275c1 --- /dev/null +++ b/include/gz/sim/components/Actor.hh @@ -0,0 +1,55 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_ACTOR_HH_ +#define GZ_GAZEBO_COMPONENTS_ACTOR_HH_ + +#include + +#include + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace serializers +{ + using ActorSerializer = + serializers::ComponentToMsgSerializer; +} + +namespace components +{ + /// \brief This component contains actor source information. For more + /// information on actors, see [SDF's Actor + /// element](http://sdformat.org/spec?ver=1.6&elem=actor). + using Actor = + Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Actor", Actor) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Actuators.hh b/include/gz/sim/components/Actuators.hh new file mode 100644 index 0000000000..c4ce93ca6c --- /dev/null +++ b/include/gz/sim/components/Actuators.hh @@ -0,0 +1,46 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_ACTUATORS_HH_ +#define GZ_GAZEBO_COMPONENTS_ACTUATORS_HH_ + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains a msgs::Actuators message. This is + /// used for example, to communicate between the MulticopterMotorModel and + /// MulticopterVelocityControl systems + using Actuators = Component; + + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Actuators", Actuators) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/AirPressureSensor.hh b/include/gz/sim/components/AirPressureSensor.hh new file mode 100644 index 0000000000..c40a6340e6 --- /dev/null +++ b/include/gz/sim/components/AirPressureSensor.hh @@ -0,0 +1,46 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_AIRPRESSURE_HH_ +#define GZ_GAZEBO_COMPONENTS_AIRPRESSURE_HH_ + +#include + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains an air pressure sensor, + /// sdf::AirPressure, information. + using AirPressureSensor = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.AirPressureSensor", + AirPressureSensor) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Altimeter.hh b/include/gz/sim/components/Altimeter.hh new file mode 100644 index 0000000000..ee078ed24b --- /dev/null +++ b/include/gz/sim/components/Altimeter.hh @@ -0,0 +1,45 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_ALTIMETER_HH_ +#define GZ_GAZEBO_COMPONENTS_ALTIMETER_HH_ + +#include + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains an altimeter sensor, + /// sdf::Altimeter, information. + using Altimeter = + Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Altimeter", Altimeter) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/AngularAcceleration.hh b/include/gz/sim/components/AngularAcceleration.hh new file mode 100644 index 0000000000..39606570f1 --- /dev/null +++ b/include/gz/sim/components/AngularAcceleration.hh @@ -0,0 +1,54 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_ANGULARACCELERATION_HH_ +#define GZ_GAZEBO_COMPONENTS_ANGULARACCELERATION_HH_ + +#include + +#include +#include + +#include +#include "gz/sim/components/Component.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains angular acceleration of an entity + /// represented by gz::math::Vector3d. + using AngularAcceleration = + Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.AngularAcceleration", + AngularAcceleration) + + /// \brief A component type that contains angular acceleration of an entity in + /// the world frame represented by gz::math::Vector3d. + using WorldAngularAcceleration = + Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.WorldAngularAcceleration", + WorldAngularAcceleration) +} +} +} +} +#endif diff --git a/include/gz/sim/components/AngularVelocity.hh b/include/gz/sim/components/AngularVelocity.hh new file mode 100644 index 0000000000..24eff27fb6 --- /dev/null +++ b/include/gz/sim/components/AngularVelocity.hh @@ -0,0 +1,53 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_ANGULARVELOCITY_HH_ +#define GZ_GAZEBO_COMPONENTS_ANGULARVELOCITY_HH_ + +#include + +#include +#include + +#include +#include "gz/sim/components/Component.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains angular velocity of an entity + /// represented by gz::math::Vector3d. + using AngularVelocity = + Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.AngularVelocity", + AngularVelocity) + + /// \brief A component type that contains angular velocity of an entity in the + /// world frame represented by gz::math::Vector3d. + using WorldAngularVelocity = + Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WorldAngularVelocity", + WorldAngularVelocity) +} +} +} +} +#endif diff --git a/include/gz/sim/components/AngularVelocityCmd.hh b/include/gz/sim/components/AngularVelocityCmd.hh new file mode 100644 index 0000000000..274da7aecc --- /dev/null +++ b/include/gz/sim/components/AngularVelocityCmd.hh @@ -0,0 +1,53 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_ANGULARVELOCITYCMD_HH_ +#define GZ_GAZEBO_COMPONENTS_ANGULARVELOCITYCMD_HH_ + +#include + +#include + +#include +#include "gz/sim/components/Component.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains the commanded angular velocity of + /// an entity, in its own frame, represented by gz::math::Vector3d. + using AngularVelocityCmd = + Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.AngularVelocityCmd", AngularVelocityCmd) + + /// \brief A component type that contains the commanded angular velocity + /// of an entity in the world frame represented by gz::math::Vector3d. + using WorldAngularVelocityCmd = + Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.WorldAngularVelocityCmd", WorldAngularVelocityCmd) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Atmosphere.hh b/include/gz/sim/components/Atmosphere.hh new file mode 100644 index 0000000000..a925542de3 --- /dev/null +++ b/include/gz/sim/components/Atmosphere.hh @@ -0,0 +1,52 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_ATMOSPHERE_HH_ +#define GZ_GAZEBO_COMPONENTS_ATMOSPHERE_HH_ + +#include +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace serializers +{ + using AtmosphereSerializer = + serializers::ComponentToMsgSerializer; +} + +namespace components +{ + /// \brief This component holds atmosphere properties of the world. + using Atmosphere = + Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.Atmosphere", Atmosphere) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/AxisAlignedBox.hh b/include/gz/sim/components/AxisAlignedBox.hh new file mode 100644 index 0000000000..fa1f02955b --- /dev/null +++ b/include/gz/sim/components/AxisAlignedBox.hh @@ -0,0 +1,55 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_AxisAlignedBox_HH_ +#define GZ_GAZEBO_COMPONENTS_AxisAlignedBox_HH_ + +#include +#include +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace serializers +{ + using AxisAlignedBoxSerializer = + serializers::ComponentToMsgSerializer; +} + +namespace components +{ + /// \brief A component type that contains axis aligned box, + /// gz::math::AxisAlignedBox, information. + /// The axis aligned box is created from collisions in the entity + using AxisAlignedBox = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.AxisAlignedBox", + AxisAlignedBox) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/BatterySoC.hh b/include/gz/sim/components/BatterySoC.hh new file mode 100644 index 0000000000..8e1ab3a74f --- /dev/null +++ b/include/gz/sim/components/BatterySoC.hh @@ -0,0 +1,41 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_BATTERY_HH_ +#define GZ_GAZEBO_COMPONENTS_BATTERY_HH_ + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +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) +} +} +} +} + +#endif diff --git a/include/ignition/gazebo/components/CMakeLists.txt b/include/gz/sim/components/CMakeLists.txt similarity index 80% rename from include/ignition/gazebo/components/CMakeLists.txt rename to include/gz/sim/components/CMakeLists.txt index d03429131a..83f18ce69d 100644 --- a/include/ignition/gazebo/components/CMakeLists.txt +++ b/include/gz/sim/components/CMakeLists.txt @@ -3,7 +3,7 @@ file(GLOB component_headers *.hh) set (component_includes "") foreach (header_full ${component_headers}) get_filename_component(header ${header_full} NAME) - set(component_includes "${component_includes}#include \n") + set(component_includes "${component_includes}#include \n") endforeach() configure_file( diff --git a/include/gz/sim/components/Camera.hh b/include/gz/sim/components/Camera.hh new file mode 100644 index 0000000000..fbfeccc0c8 --- /dev/null +++ b/include/gz/sim/components/Camera.hh @@ -0,0 +1,45 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_CAMERA_HH_ +#define GZ_GAZEBO_COMPONENTS_CAMERA_HH_ + +#include + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains a camera sensor, + /// sdf::Camera, information. + using Camera = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Camera", Camera) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/CanonicalLink.hh b/include/gz/sim/components/CanonicalLink.hh new file mode 100644 index 0000000000..8255319878 --- /dev/null +++ b/include/gz/sim/components/CanonicalLink.hh @@ -0,0 +1,41 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_CANONICALLINK_HH_ +#define GZ_GAZEBO_COMPONENTS_CANONICALLINK_HH_ + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component that identifies an entity as being a canonical link. + using CanonicalLink = Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.CanonicalLink", CanonicalLink) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/CastShadows.hh b/include/gz/sim/components/CastShadows.hh new file mode 100644 index 0000000000..0b2954a837 --- /dev/null +++ b/include/gz/sim/components/CastShadows.hh @@ -0,0 +1,42 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_CASTSHADOWS_HH_ +#define GZ_GAZEBO_COMPONENTS_CASTSHADOWS_HH_ + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component used to indicate that an entity casts shadows + /// e.g. visual entities + using CastShadows = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.CastShadows", + CastShadows) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/CenterOfVolume.hh b/include/gz/sim/components/CenterOfVolume.hh new file mode 100644 index 0000000000..fd8a2bc6df --- /dev/null +++ b/include/gz/sim/components/CenterOfVolume.hh @@ -0,0 +1,45 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_CENTEROFVOLUME_HH_ +#define GZ_GAZEBO_COMPONENTS_CENTEROFVOLUME_HH_ + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component for an entity's center of volume. Units are in meters. + /// The Vector3 value indicates center of volume of an entity. The + /// 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", + CenterOfVolume) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/ChildLinkName.hh b/include/gz/sim/components/ChildLinkName.hh new file mode 100644 index 0000000000..573f226dd0 --- /dev/null +++ b/include/gz/sim/components/ChildLinkName.hh @@ -0,0 +1,43 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_CHILDLINKNAME_HH_ +#define GZ_GAZEBO_COMPONENTS_CHILDLINKNAME_HH_ + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component used to indicate that a model is childlinkname (i.e. + /// not moveable). + using ChildLinkName = Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.ChildLinkName", ChildLinkName) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Collision.hh b/include/gz/sim/components/Collision.hh new file mode 100644 index 0000000000..b1ca512e0d --- /dev/null +++ b/include/gz/sim/components/Collision.hh @@ -0,0 +1,68 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_COLLISION_HH_ +#define GZ_GAZEBO_COMPONENTS_COLLISION_HH_ + +#include + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace serializers +{ + using CollisionElementSerializer = + serializers::ComponentToMsgSerializer; +} + +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) + + // TODO(anyone) The sdf::Collision DOM object does not yet contain + // surface information. + /// \brief A component that holds the sdf::Collision object. + using CollisionElement = + Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.CollisionElement", + CollisionElement) + + /// \brief A component used to enable customization of contact surface for a + /// collision. The customization itself is done in callback of event + /// CollectContactSurfaceProperties from PhysicsEvents. + using EnableContactSurfaceCustomization = + Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.EnableContactSurfaceCustomization", + EnableContactSurfaceCustomization) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Component.hh b/include/gz/sim/components/Component.hh new file mode 100644 index 0000000000..96243c1082 --- /dev/null +++ b/include/gz/sim/components/Component.hh @@ -0,0 +1,542 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_COMPONENT_HH_ +#define GZ_GAZEBO_COMPONENTS_COMPONENT_HH_ + +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// namespace ignition +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace traits +{ + /// \brief Helper trait to determine if a type is shared_ptr or not + template + struct IsSharedPtr : std::false_type + { + }; + + /// \brief Helper trait to determine if a type is shared_ptr or not + template + struct IsSharedPtr> : std::true_type + { + }; + + /// \brief Type trait that determines if a operator<< is defined on `Stream` + /// and `DataType`, i.e, it checks if the function + /// `Stream& operator<<(Stream&, const DataType&)` exists. + /// Example: + /// \code + /// constexpr bool isDoubleOutStreamable = + /// IsOutStreamable::value + /// \endcode + template + class IsOutStreamable + { + private: template + static auto Test(int _test) + -> decltype(std::declval() + << std::declval(), std::true_type()); + + private: template + static auto Test(...) -> std::false_type; + + public: static constexpr bool value = // NOLINT + decltype(Test(true))::value; + }; + + /// \brief Type trait that determines if a operator>> is defined on `Stream` + /// and `DataType`, i.e, it checks if the function + /// `Stream& operator>>(Stream&, DataType&)` exists. + /// Example: + /// \code + /// constexpr bool isDoubleInStreamable = + /// IsInStreamable::value + /// \endcode + /// + template + class IsInStreamable + { + private: template + static auto Test(int _test) + -> decltype(std::declval() >> std::declval(), + std::true_type()); + + private: template + static auto Test(...) -> std::false_type; + + public: static constexpr bool value = // NOLINT + decltype(Test(0))::value; + }; +} + +namespace serializers +{ + /// \brief Default serializer template to call stream operators only on types + /// that support them. If the stream operator is not available, a warning + /// message is printed. + /// \tparam DataType Type on which the operator will be called. + template + class DefaultSerializer + { + /// Serialization + public: static std::ostream &Serialize(std::ostream &_out, + const DataType &_data) + { + // cppcheck-suppress syntaxError + if constexpr (traits::IsSharedPtr::value) // NOLINT + { + if constexpr (traits::IsOutStreamable::value) + { + _out << *_data; + } + else + { + static bool warned{false}; + if (!warned) + { + ignwarn << "Trying to serialize component with data type [" + << typeid(DataType).name() << "], which doesn't have " + << "`operator<<`. Component will not be serialized." + << std::endl; + warned = true; + } + } + } + else if constexpr (traits::IsOutStreamable::value) + { + _out << _data; + } + else + { + static bool warned{false}; + if (!warned) + { + ignwarn << "Trying to serialize component with data type [" + << typeid(DataType).name() << "], which doesn't have " + << "`operator<<`. Component will not be serialized." + << std::endl; + warned = true; + } + } + return _out; + } + + /// \brief Deserialization + /// \param[in] _in In stream. + /// \param[in] _data Data resulting from deserialization. + public: static std::istream &Deserialize(std::istream &_in, + DataType &_data) + { + if constexpr (traits::IsSharedPtr::value) + { + if constexpr (traits::IsInStreamable::value) + { + _in >> *_data; + } + else + { + static bool warned{false}; + if (!warned) + { + ignwarn << "Trying to deserialize component with data type [" + << typeid(DataType).name() << "], which doesn't have " + << "`operator>>`. Component will not be deserialized." + << std::endl; + warned = true; + } + } + } + else if constexpr (traits::IsInStreamable::value) + { + _in >> _data; + } + else + { + static bool warned{false}; + if (!warned) + { + ignwarn << "Trying to deserialize component with data type [" + << typeid(DataType).name() << "], which doesn't have " + << "`operator>>`. Component will not be deserialized." + << std::endl; + warned = true; + } + } + return _in; + } + }; +} + +namespace components +{ + /// \brief Convenient type to be used by components that don't wrap any data. + /// I.e. they act as tags and their presence is enough to infer something + /// about the entity. + using NoData = std::add_lvalue_reference; +} + +namespace serializers +{ + /// \brief Specialization of DefaultSerializer for NoData + template<> class DefaultSerializer + { + public: static std::ostream &Serialize(std::ostream &_out) + { + _out << "-"; + return _out; + } + + public: static std::istream &Deserialize(std::istream &_in) + { + return _in; + } + }; +} + +namespace components +{ + /// \brief Base class for all components. + class BaseComponent + { + /// \brief Default constructor. + public: BaseComponent() = default; + + /// \brief Default destructor. + public: virtual ~BaseComponent() = default; + + /// \brief Fills a stream with a serialized version of the component. + /// By default, it will leave the stream empty. Derived classes should + /// override this function to support serialization. + /// + /// \param[in] _out Out stream. + public: virtual void Serialize(std::ostream &_out) const + { + // This will avoid a doxygen warning + (void)_out; + static bool warned{false}; + if (!warned) + { + ignwarn << "Trying to serialize component of type [" << this->TypeId() + << "], which hasn't implemented the `Serialize` function. " + << "Component will not be serialized." << std::endl; + warned = true; + } + }; + + /// \brief Fills a component based on a stream with a serialized data. + /// By default, it will do nothing. Derived classes should + /// override this function to support deserialization. + /// + /// \param[in] _in In stream. + public: virtual void Deserialize(std::istream &_in) + { + // This will avoid a doxygen warning + (void)_in; + static bool warned{false}; + if (!warned) + { + ignwarn << "Trying to deserialize component of type [" + << this->TypeId() << "], which hasn't implemented the " + << "`Deserialize` function. Component will not be deserialized." + << std::endl; + warned = true; + } + }; + + /// \brief Returns the unique ID for the component's type. + /// The ID is derived from the name that is manually chosen during the + /// Factory registration and is guaranteed to be the same across compilers + /// and runs. + public: virtual ComponentTypeId TypeId() const = 0; + }; + + /// \brief A component type that wraps any data type. The intention is for + /// this class to be used to create simple components while avoiding a lot of + /// boilerplate code. The Identifier must be a unique type so that type + /// aliases can be used to create new components. However the type does not + /// need to be defined anywhere + /// eg. + /// \code + /// using Static = Component; + /// \endcode + /// + /// Note, however, that this scheme does not have a mechanism to stop someone + /// accidentally defining another component that wraps a bool as such: + /// \code + /// using AnotherComp = Component; + /// \endcode + /// In this case, Static and AnotherComp are exactly the same types and would + /// not be differentiable by the EntityComponentManager. + /// + /// A third template argument can be passed to Component to specify the + /// serializer class to use. If this argument is not provided, Component will + /// use DefaultSerializer where DataType is the first template + /// argument to Component. + /// eg. + /// \code + /// class BoolSerializer; // Defined elsewhere + /// using Static = Component; + /// \endcode + /// + /// \tparam DataType Type of the data being wrapped by this component. + /// \tparam Identifier Unique identifier for the component class, to avoid + /// collision. + /// \tparam Serializer A class that can serialize `DataType`. Defaults to a + /// serializer that uses stream operators `<<` and `>>` on the data if they + /// exist. + template > + class Component : public BaseComponent + { + /// \brief Alias for DataType + public: using Type = DataType; + + /// \brief Default constructor + public: Component() = default; + + /// \brief Constructor + /// \param[in] _data Data to copy + public: explicit Component(DataType _data); + + /// \brief Destructor. + public: ~Component() override = default; + + /// \brief Equality operator. + /// \param[in] _component Component to compare to. + /// \return True if equal. + public: bool operator==(const Component &_component) const; + + /// \brief Inequality operator. + /// \param[in] _component Component to compare to. + /// \return True if different. + public: bool operator!=(const Component &_component) const; + + // Documentation inherited + public: ComponentTypeId TypeId() const override; + + // Documentation inherited + public: void Serialize(std::ostream &_out) const override; + + // Documentation inherited + public: void Deserialize(std::istream &_in) override; + + /// \brief Get the mutable component data. This function will be + /// deprecated in Gazebo 3, replaced by const DataType &Data() const. + /// Use void SetData(const DataType &) to modify data. + /// \return Mutable reference to the actual component information. + /// \todo(nkoenig) Deprecate this function in version 3. + public: DataType &Data(); + + /// \brief Set the data of this component. + /// \param[in] _data New data for this component. + /// \param[in] _eql Equality comparison function. This function should + /// return true if two instances of DataType are equal. + /// \return True if the _eql function returns false. + public: bool SetData(const DataType &_data, + const std::function< + bool(const DataType &, const DataType &)> &_eql); + + /// \brief Get the immutable component data. + /// \return Immutable reference to the actual component information. + public: const DataType &Data() const; + + /// \brief Private data pointer. + private: DataType data; + + /// \brief Unique ID for this component type. This is set through the + /// Factory registration. + public: inline static ComponentTypeId typeId{0}; + + /// \brief Unique name for this component type. This is set through the + /// Factory registration. + public: inline static std::string typeName; + }; + + /// \brief Specialization for components that don't wrap any data. + /// This class to be used to create simple components that represent + /// just a "tag", while avoiding a lot of boilerplate code. The Identifier + /// must be a unique type so that type aliases can be used to create new + /// components. However the type does not need to be defined anywhere eg. + /// + /// using Joint = Component; + /// + template + class Component : public BaseComponent + { + /// \brief Components with no data are always equal to another instance of + /// the same type. + /// \param[in] _component Component to compare to + /// \return True. + public: bool operator==(const Component &_component) const; + + /// \brief Components with no data are always equal to another instance of + /// the same type. + /// \param[in] _component Component to compare to + /// \return False. + public: bool operator!=(const Component &_component) const; + + // Documentation inherited + public: ComponentTypeId TypeId() const override; + + // Documentation inherited + public: void Serialize(std::ostream &_out) const override; + + // Documentation inherited + public: void Deserialize(std::istream &_in) override; + + /// \brief Unique ID for this component type. This is set through the + /// Factory registration. + public: inline static ComponentTypeId typeId{0}; + + /// \brief Unique name for this component type. This is set through the + /// Factory registration. + public: inline static std::string typeName; + }; + + ////////////////////////////////////////////////// + template + Component::Component(DataType _data) + : data(std::move(_data)) + { + } + + ////////////////////////////////////////////////// + template + DataType &Component::Data() + { + return this->data; + } + + ////////////////////////////////////////////////// + template + bool Component::SetData( + const DataType &_data, + const std::function &_eql) + { + bool result = !_eql(_data, this->data); + this->data = _data; + return result; + } + + ////////////////////////////////////////////////// + template + const DataType &Component::Data() const + { + return this->data; + } + + ////////////////////////////////////////////////// + template + bool Component::operator==( + const Component &_component) const + { + return this->data == _component.Data(); + } + + ////////////////////////////////////////////////// + template + bool Component::operator!=( + const Component &_component) const + { + return this->data != _component.Data(); + } + + ////////////////////////////////////////////////// + template + void Component::Serialize( + std::ostream &_out) const + { + Serializer::Serialize(_out, this->Data()); + } + + ////////////////////////////////////////////////// + template + void Component::Deserialize( + std::istream &_in) + { + Serializer::Deserialize(_in, this->Data()); + } + + ////////////////////////////////////////////////// + template + ComponentTypeId Component::TypeId() const + { + return typeId; + } + + ////////////////////////////////////////////////// + template + bool Component::operator==( + const Component &) const + { + return true; + } + + ////////////////////////////////////////////////// + template + bool Component::operator!=( + const Component &) const + { + return false; + } + + ////////////////////////////////////////////////// + template + ComponentTypeId Component::TypeId() const + { + return typeId; + } + + ////////////////////////////////////////////////// + template + void Component::Serialize( + std::ostream &_out) const + { + Serializer::Serialize(_out); + } + + ////////////////////////////////////////////////// + template + void Component::Deserialize( + std::istream &_in) + { + Serializer::Deserialize(_in); + } +} +} +} +} +#endif diff --git a/include/gz/sim/components/ContactSensor.hh b/include/gz/sim/components/ContactSensor.hh new file mode 100644 index 0000000000..cf8aa99f35 --- /dev/null +++ b/include/gz/sim/components/ContactSensor.hh @@ -0,0 +1,43 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_CONTACTSENSOR_HH_ +#define GZ_GAZEBO_COMPONENTS_CONTACTSENSOR_HH_ + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +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", + ContactSensor) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/ContactSensorData.hh b/include/gz/sim/components/ContactSensorData.hh new file mode 100644 index 0000000000..fb8a895699 --- /dev/null +++ b/include/gz/sim/components/ContactSensorData.hh @@ -0,0 +1,46 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_CONTACTDATASENSOR_HH_ +#define GZ_GAZEBO_COMPONENTS_CONTACTDATASENSOR_HH_ + +#include +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains a list of contacts. + using ContactSensorData = + Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ContactSensorData", + ContactSensorData) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/DepthCamera.hh b/include/gz/sim/components/DepthCamera.hh new file mode 100644 index 0000000000..28211a0138 --- /dev/null +++ b/include/gz/sim/components/DepthCamera.hh @@ -0,0 +1,45 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_DEPTHCAMERA_HH_ +#define GZ_GAZEBO_COMPONENTS_DEPTHCAMERA_HH_ + +#include + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains a depth camera sensor, + /// sdf::Camera, information. + using DepthCamera = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.DepthCamera", + DepthCamera) +} +} +} +} +#endif diff --git a/include/gz/sim/components/DetachableJoint.hh b/include/gz/sim/components/DetachableJoint.hh new file mode 100644 index 0000000000..04eca0ff12 --- /dev/null +++ b/include/gz/sim/components/DetachableJoint.hh @@ -0,0 +1,105 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_DETACHABLE_JOINT_HH_ +#define GZ_GAZEBO_COMPONENTS_DETACHABLE_JOINT_HH_ + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief Data structure to hold information about the parent and child links + /// connected by a detachable joint + struct DetachableJointInfo + { + /// \brief Entity of the parent link + Entity parentLink; + /// \brief Entity of the echild link + Entity childLink; + // \brief Type of joint. Only the "fixed" joint type is currently supported. + std::string jointType = {"fixed"}; + + public: bool operator==(const DetachableJointInfo &_info) const + { + return (this->parentLink == _info.parentLink) && + (this->childLink == _info.childLink) && + (this->jointType == _info.jointType); + } + + public: bool operator!=(const DetachableJointInfo &_info) const + { + return !(*this == _info); + } + }; +} + +namespace serializers +{ + /// \brief Serializer for DetachableJointInfo object + class DetachableJointInfoSerializer + { + /// \brief Serialization for `DetachableJointInfo`. + /// \param[in] _out Output stream. + /// \param[in] _info DetachableJointInfo object to stream + /// \return The stream. + public: static std::ostream &Serialize( + std::ostream &_out, + const components::DetachableJointInfo &_info) + { + _out << _info.parentLink << " " << _info.childLink << " " + << _info.jointType; + return _out; + } + + /// \brief Deserialization for `std::set`. + /// \param[in] _in Input stream. + /// \param[in] _info DetachableJointInfo object to populate + /// \return The stream. + public: static std::istream &Deserialize( + std::istream &_in, components::DetachableJointInfo &_info) + { + _in >> _info.parentLink >> _info.childLink >> _info.jointType; + return _in; + } + }; +} + +namespace components +{ + /// \brief A component that identifies an entity as being a detachable joint. + /// It also contains additional information about the joint. + using DetachableJoint = + Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.DetachableJoint", + DetachableJoint) +} +} +} +} + +#endif + diff --git a/include/gz/sim/components/ExternalWorldWrenchCmd.hh b/include/gz/sim/components/ExternalWorldWrenchCmd.hh new file mode 100644 index 0000000000..0b7c5c8c62 --- /dev/null +++ b/include/gz/sim/components/ExternalWorldWrenchCmd.hh @@ -0,0 +1,52 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_EXTERNALWORLDWRENCHCMD_HH_ +#define GZ_GAZEBO_COMPONENTS_EXTERNALWORLDWRENCHCMD_HH_ + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains the external wrench to be applied on + /// an entity expressed in the world frame and represented by + /// gz::msgs::Wrench. + /// Currently this is used for applying wrenches on links. Although the + /// msg::Wrench type has a force_offset member, the value is currently + /// ignored. Instead, the force is applied at the link origin. + /// The wrench uses SI units (N for force and Nâ‹…m for torque). + using ExternalWorldWrenchCmd = + Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ExternalWorldWrenchCmd", + ExternalWorldWrenchCmd) +} +} +} +} + +#endif + diff --git a/include/gz/sim/components/Factory.hh b/include/gz/sim/components/Factory.hh new file mode 100644 index 0000000000..06570235c2 --- /dev/null +++ b/include/gz/sim/components/Factory.hh @@ -0,0 +1,352 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_FACTORY_HH_ +#define GZ_GAZEBO_COMPONENTS_FACTORY_HH_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A base class for an object responsible for creating components. + class IGNITION_GAZEBO_VISIBLE ComponentDescriptorBase + { + /// \brief Destructor + public: virtual ~ComponentDescriptorBase() = default; + + /// \brief Create an instance of a Component. + /// \return Pointer to a component. + public: virtual std::unique_ptr Create() const = 0; + }; + + /// \brief A class for an object responsible for creating components. + /// \tparam ComponentTypeT type of component to describe. + template + class IGNITION_GAZEBO_VISIBLE ComponentDescriptor + : public ComponentDescriptorBase + { + /// \brief Create an instance of a ComponentTypeT Component. + /// \return Pointer to a component. + public: std::unique_ptr Create() const override + { + return std::make_unique(); + } + }; + + /// \brief A base class for an object responsible for creating storages. + class IGNITION_GAZEBO_VISIBLE StorageDescriptorBase + { + /// \brief Destructor + public: virtual ~StorageDescriptorBase() = default; + + /// \brief Create an instance of a storage. + /// \return Pointer to a storage. + public: virtual std::unique_ptr Create() const = 0; + }; + + /// \brief A class for an object responsible for creating storages. + /// \tparam ComponentTypeT type of component that the storage will hold. + template + class IGNITION_GAZEBO_VISIBLE StorageDescriptor + : public StorageDescriptorBase + { + /// \brief Create an instance of a storage that holds ComponentTypeT + /// components. + /// \return Pointer to a component. + public: std::unique_ptr Create() const override + { + return std::make_unique>(); + } + }; + + /// \brief A factory that generates a component based on a string type. + class IGNITION_GAZEBO_VISIBLE Factory + : public gz::common::SingletonT + { + /// \brief Register a component so that the factory can create instances + /// of the component and its storage based on an ID. + /// \param[in] _type Type of component to register. + /// \param[in] _compDesc Object to manage the creation of ComponentTypeT + /// objects. + /// \param[in] _storageDesc Object to manage the creation of storages for + /// objects of type ComponentTypeT. + /// \tparam ComponentTypeT Type of component to register. + public: template + void Register(const std::string &_type, ComponentDescriptorBase *_compDesc, + StorageDescriptorBase *_storageDesc) + { + // Every time a plugin which uses a component type is loaded, it attempts + // to register it again, so we skip it. + if (ComponentTypeT::typeId != 0) + { + return; + } + + auto typeHash = gz::common::hash64(_type); + + // Initialize static member variable - we need to set these + // static members for every shared lib that uses the component, but we + // only add them to the maps below once. + ComponentTypeT::typeId = typeHash; + ComponentTypeT::typeName = _type; + + // Check if component has already been registered by another library + auto runtimeName = typeid(ComponentTypeT).name(); + auto runtimeNameIt = this->runtimeNamesById.find(typeHash); + if (runtimeNameIt != this->runtimeNamesById.end()) + { + // Warn user if type was previously registered with a different name. + // We're leaving the ID set in case this is a false difference across + // libraries. + if (runtimeNameIt->second != runtimeName) + { + std::cerr + << "Registered components of different types with same name: type [" + << runtimeNameIt->second << "] and type [" << runtimeName + << "] with name [" << _type << "]. Second type will not work." + << std::endl; + } + return; + } + + // This happens at static initialization time, so we can't use common + // console + std::string debugEnv; + gz::common::env("IGN_DEBUG_COMPONENT_FACTORY", debugEnv); + if (debugEnv == "true") + { + std::cout << "Registering [" << ComponentTypeT::typeName << "]" + << std::endl; + } + + // Keep track of all types + this->compsById[ComponentTypeT::typeId] = _compDesc; + this->storagesById[ComponentTypeT::typeId] = _storageDesc; + namesById[ComponentTypeT::typeId] = ComponentTypeT::typeName; + runtimeNamesById[ComponentTypeT::typeId] = runtimeName; + } + + /// \brief Unregister a component so that the factory can't create instances + /// of the component or its storage anymore. + /// \tparam ComponentTypeT Type of component to unregister. + public: template + void Unregister() + { + this->Unregister(ComponentTypeT::typeId); + + ComponentTypeT::typeId = 0; + } + + /// \brief Unregister a component so that the factory can't create instances + /// of the component or its storage anymore. + /// \details This function will not reset the `typeId` static variable + /// within the component type itself. Prefer using the templated + /// `Unregister` function when possible. + /// \param[in] _typeId Type of component to unregister. + public: void Unregister(ComponentTypeId _typeId) + { + // Not registered + if (_typeId == 0) + { + return; + } + + { + auto it = this->compsById.find(_typeId); + if (it != this->compsById.end()) + { + delete it->second; + this->compsById.erase(it); + } + } + + { + auto it = this->storagesById.find(_typeId); + if (it != this->storagesById.end()) + { + delete it->second; + this->storagesById.erase(it); + } + } + + { + auto it = namesById.find(_typeId); + if (it != namesById.end()) + { + namesById.erase(it); + } + } + + { + auto it = runtimeNamesById.find(_typeId); + if (it != runtimeNamesById.end()) + { + runtimeNamesById.erase(it); + } + } + } + + /// \brief Create a new instance of a component. + /// \return Pointer to a component. Null if the component + /// type could not be handled. + /// \tparam ComponentTypeT component type requested + public: template + std::unique_ptr New() + { + return std::unique_ptr(static_cast( + this->New(ComponentTypeT::typeId).release())); + } + + /// \brief Create a new instance of a component. + /// \param[in] _type Component id to create. + /// \return Pointer to a component. Null if the component + /// type could not be handled. + public: std::unique_ptr New( + const ComponentTypeId &_type) + { + // Create a new component if a FactoryFn has been assigned to this type. + std::unique_ptr comp; + auto it = this->compsById.find(_type); + if (it != this->compsById.end() && nullptr != it->second) + comp = it->second->Create(); + + return comp; + } + + /// \brief Create a new instance of a component storage. + /// \param[in] _typeId Type of component which the storage will hold. + /// \return Pointer to a storage. Null if the component type could not be + /// handled. + public: std::unique_ptr NewStorage( + const ComponentTypeId &_typeId) + { + std::unique_ptr storage; + auto it = this->storagesById.find(_typeId); + if (it != this->storagesById.end() && nullptr != it->second) + storage = it->second->Create(); + + return storage; + } + + /// \brief Get all the registered component types by ID. + /// return Vector of component IDs. + public: std::vector TypeIds() const + { + std::vector types; + + // Return the list of all known component types. + for (const auto &comp : this->compsById) + types.push_back(comp.first); + + return types; + } + + /// \brief Check if a component type has been registered. + /// return True if registered. + public: bool HasType(ComponentTypeId _typeId) + { + return this->compsById.find(_typeId) != this->compsById.end(); + } + + /// \brief Get a component's type name given its type ID. + /// return Unique component name. + public: std::string Name(ComponentTypeId _typeId) const + { + if (this->namesById.find(_typeId) != this->namesById.end()) + return namesById.at(_typeId); + + return ""; + } + + /// \brief A list of registered components where the key is its id. + /// + /// Note about compsByName and compsById. The maps store pointers as the + /// values, but never cleans them up, which may (at first glance) seem like + /// incorrect behavior. This is not a mistake. Since ComponentDescriptors + /// are created at the point in the code where components are defined, this + /// generally ends up in a shared library that will be loaded at runtime. + /// + /// Because this and the plugin loader both use static variables, and the + /// order of static initialization and destruction are not guaranteed, this + /// can lead to a scenario where the shared library is unloaded (with the + /// ComponentDescriptor), but the Factory still exists. For this reason, + /// we just keep a pointer, which will dangle until the program is shutdown. + private: std::map compsById; + + /// \brief A list of registered storages where the key is its component's + /// type id. + private: std::map storagesById; + + /// \brief A list of IDs and their equivalent names. + /// \details Make it non-static on version 2.0. + public: inline static std::map namesById; + + /// \brief Keep track of the runtime names for types and warn the user if + /// they try to register different types with the same typeName. + /// \details Make it non-static on version 2.0. + public: inline static std::map + runtimeNamesById; + }; + + /// \brief Static component registration macro. + /// + /// Use this macro to register components. + /// + /// \details Each time a plugin which uses a component is loaded, it tries to + /// register the component again, so we prevent that. + /// \param[in] _compType Component type name. + /// \param[in] _classname Class name for component. + #define IGN_GAZEBO_REGISTER_COMPONENT(_compType, _classname) \ + class IGNITION_GAZEBO_VISIBLE IgnGazeboComponents##_classname \ + { \ + public: IgnGazeboComponents##_classname() \ + { \ + if (_classname::typeId != 0) \ + return; \ + using namespace ignition;\ + using Desc = gz::sim::components::ComponentDescriptor<_classname>; \ + using StorageDesc = gz::sim::components::StorageDescriptor<_classname>; \ + gz::sim::components::Factory::Instance()->Register<_classname>(\ + _compType, new Desc(), new StorageDesc());\ + } \ + }; \ + static IgnGazeboComponents##_classname\ + IgnitionGazeboComponentsInitializer##_classname; +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Geometry.hh b/include/gz/sim/components/Geometry.hh new file mode 100644 index 0000000000..5a5ab0f0ab --- /dev/null +++ b/include/gz/sim/components/Geometry.hh @@ -0,0 +1,55 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_GEOMETRY_HH_ +#define GZ_GAZEBO_COMPONENTS_GEOMETRY_HH_ + +#include + +#include + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace serializers +{ + using GeometrySerializer = + serializers::ComponentToMsgSerializer; +} + +namespace components +{ + /// \brief This component holds an entity's geometry. + using Geometry = Component; + + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Geometry", Geometry) + +} +} +} +} + +#endif diff --git a/include/gz/sim/components/GpuLidar.hh b/include/gz/sim/components/GpuLidar.hh new file mode 100644 index 0000000000..e315beae3d --- /dev/null +++ b/include/gz/sim/components/GpuLidar.hh @@ -0,0 +1,43 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_GPU_LIDAR_HH_ +#define GZ_GAZEBO_COMPONENTS_GPU_LIDAR_HH_ + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains a GPU Lidar sensor, + /// sdf::Lidar, information. + using GpuLidar = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.GpuLidar", GpuLidar) +} +} +} +} +#endif diff --git a/include/gz/sim/components/Gravity.hh b/include/gz/sim/components/Gravity.hh new file mode 100644 index 0000000000..fe3cf88a9f --- /dev/null +++ b/include/gz/sim/components/Gravity.hh @@ -0,0 +1,43 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_GRAVITY_HH_ +#define GZ_GAZEBO_COMPONENTS_GRAVITY_HH_ + +#include + +#include +#include + +#include +#include "gz/sim/components/Component.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief Store the gravity acceleration. + using Gravity = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Gravity", Gravity) +} +} +} +} +#endif diff --git a/include/gz/sim/components/Imu.hh b/include/gz/sim/components/Imu.hh new file mode 100644 index 0000000000..29da0cbb62 --- /dev/null +++ b/include/gz/sim/components/Imu.hh @@ -0,0 +1,46 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_IMU_HH_ +#define GZ_GAZEBO_COMPONENTS_IMU_HH_ + +#include + +#include +#include + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains an IMU sensor, + /// sdf::IMU, information. + using Imu = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Imu", Imu) +} +} +} +} +#endif diff --git a/include/gz/sim/components/Inertial.hh b/include/gz/sim/components/Inertial.hh new file mode 100644 index 0000000000..daadc3fa7d --- /dev/null +++ b/include/gz/sim/components/Inertial.hh @@ -0,0 +1,51 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_INERTIAL_HH_ +#define GZ_GAZEBO_COMPONENTS_INERTIAL_HH_ + +#include +#include +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace serializers +{ + using InertialSerializer = + serializers::ComponentToMsgSerializer; +} + +namespace components +{ + /// \brief This component holds an entity's inertial. + using Inertial = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Inertial", Inertial) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Joint.hh b/include/gz/sim/components/Joint.hh new file mode 100644 index 0000000000..29710428a4 --- /dev/null +++ b/include/gz/sim/components/Joint.hh @@ -0,0 +1,40 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_JOINT_HH_ +#define GZ_GAZEBO_COMPONENTS_JOINT_HH_ + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component that identifies an entity as being a joint. + using Joint = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Joint", Joint) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/JointAxis.hh b/include/gz/sim/components/JointAxis.hh new file mode 100644 index 0000000000..df2c6b9865 --- /dev/null +++ b/include/gz/sim/components/JointAxis.hh @@ -0,0 +1,58 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_JOINTAXIS_HH_ +#define GZ_GAZEBO_COMPONENTS_JOINTAXIS_HH_ + +#include +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace serializers +{ + using JointAxisSerializer = + serializers::ComponentToMsgSerializer; +} +namespace components +{ + /// \brief A component that contains the joint axis . This is a simple wrapper + /// around sdf::JointAxis + using JointAxis = Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_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) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/JointEffortLimitsCmd.hh b/include/gz/sim/components/JointEffortLimitsCmd.hh new file mode 100644 index 0000000000..1302ec7119 --- /dev/null +++ b/include/gz/sim/components/JointEffortLimitsCmd.hh @@ -0,0 +1,60 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_JOINTEFFORTLIMITSCMD_HH_ +#define GZ_GAZEBO_COMPONENTS_JOINTEFFORTLIMITSCMD_HH_ + +#include +#include + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + +namespace components +{ + +/// \brief Command for setting effort limits of a joint. Data are a vector +/// with a Vector2 for each DOF. The X() component of the Vector2 specifies +/// the minimum effort limit, the Y() component stands for maximum limit. +/// Set to +-infinity to disable the limits. +/// \note It is expected that the physics plugin reads this component and +/// sets the limit to the dynamics engine. After setting it, the data of this +/// component will be cleared (i.e. the vector will have length zero). +using JointEffortLimitsCmd = Component< + std::vector, + class JointEffortLimitsCmdTag, + serializers::VectorSerializer +>; + +IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.JointEffortLimitsCmd", JointEffortLimitsCmd) +} + +} +} +} + +#endif diff --git a/include/gz/sim/components/JointForce.hh b/include/gz/sim/components/JointForce.hh new file mode 100644 index 0000000000..062e34c17b --- /dev/null +++ b/include/gz/sim/components/JointForce.hh @@ -0,0 +1,46 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_JOINTFORCE_HH_ +#define GZ_GAZEBO_COMPONENTS_JOINTFORCE_HH_ + +#include + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief Force applied to a joint in SI units (Nm for revolute, N for + /// prismatic). + using JointForce = Component, class JointForceTag, + serializers::VectorDoubleSerializer>; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.JointForce", JointForce) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/JointForceCmd.hh b/include/gz/sim/components/JointForceCmd.hh new file mode 100644 index 0000000000..97996111ad --- /dev/null +++ b/include/gz/sim/components/JointForceCmd.hh @@ -0,0 +1,46 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_JOINTFORCECMD_HH_ +#define GZ_GAZEBO_COMPONENTS_JOINTFORCECMD_HH_ + +#include + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief Commanded joint forces (or torques) to be applied to a joint + /// in SI units (Nm for revolute, N for prismatic). The component wraps a + /// 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", + JointForceCmd) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/JointPosition.hh b/include/gz/sim/components/JointPosition.hh new file mode 100644 index 0000000000..b2e5fba5af --- /dev/null +++ b/include/gz/sim/components/JointPosition.hh @@ -0,0 +1,47 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_JOINTPOSITION_HH_ +#define GZ_GAZEBO_COMPONENTS_JOINTPOSITION_HH_ + +#include + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief Joint positions in SI units (rad for revolute, m for prismatic). + /// The component wraps a std::vector of size equal to the degrees of freedom + /// of the joint. + using JointPosition = Component, class JointPositionTag, + serializers::VectorDoubleSerializer>; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.JointPosition", JointPosition) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/JointPositionLimitsCmd.hh b/include/gz/sim/components/JointPositionLimitsCmd.hh new file mode 100644 index 0000000000..218c23c758 --- /dev/null +++ b/include/gz/sim/components/JointPositionLimitsCmd.hh @@ -0,0 +1,58 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_JOINTPOSITIONLIMITSCMD_HH_ +#define GZ_GAZEBO_COMPONENTS_JOINTPOSITIONLIMITSCMD_HH_ + +#include +#include + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + +namespace components +{ +/// \brief Command for setting position limits of a joint. Data are a vector +/// with a Vector2 for each DOF. The X() component of the Vector2 specifies +/// the minimum positional limit, the Y() component stands for maximum limit. +/// Set to +-infinity to disable the limits. +/// \note It is expected that the physics plugin reads this component and +/// sets the limit to the dynamics engine. After setting it, the data of this +/// component will be cleared (i.e. the vector will have length zero). +using JointPositionLimitsCmd = Component< + std::vector, + class JointPositionLimitsCmdTag, + serializers::VectorSerializer +>; + +IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.JointPositionLimitsCmd", JointPositionLimitsCmd) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/JointPositionReset.hh b/include/gz/sim/components/JointPositionReset.hh new file mode 100644 index 0000000000..ab628d014d --- /dev/null +++ b/include/gz/sim/components/JointPositionReset.hh @@ -0,0 +1,49 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_JOINTPOSITIONRESET_HH_ +#define GZ_GAZEBO_COMPONENTS_JOINTPOSITIONRESET_HH_ + +#include + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief Joint positions in SI units (rad for revolute, m for prismatic). + /// + /// The component wraps a std::vector of size equal to the degrees of freedom + /// of the joint. + using JointPositionReset = Component, + class JointPositionResetTag, + serializers::VectorDoubleSerializer>; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.JointPositionReset", JointPositionReset) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/JointType.hh b/include/gz/sim/components/JointType.hh new file mode 100644 index 0000000000..657c8c1b29 --- /dev/null +++ b/include/gz/sim/components/JointType.hh @@ -0,0 +1,74 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_JOINTTYPE_HH_ +#define GZ_GAZEBO_COMPONENTS_JOINTTYPE_HH_ + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace serializers +{ + class JointTypeSerializer + { + /// \brief Serialization for `sdf::JointType`. + /// \param[in] _out Output stream. + /// \param[in] _type JointType to stream + /// \return The stream. + public: static std::ostream &Serialize(std::ostream &_out, + const sdf::JointType &_type) + { + _out << static_cast(_type); + return _out; + } + + /// \brief Deserialization for `sdf::JointType`. + /// \param[in] _in Input stream. + /// \param[out] _type JointType to populate + /// \return The stream. + public: static std::istream &Deserialize(std::istream &_in, + sdf::JointType &_type) + { + int type; + _in >> type; + _type = sdf::JointType(type); + return _in; + } + }; +} +namespace components +{ + /// \brief A component that contains the joint type. This is a simple wrapper + /// around sdf::JointType + using JointType = Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.JointType", JointType) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/JointVelocity.hh b/include/gz/sim/components/JointVelocity.hh new file mode 100644 index 0000000000..bd523df3bd --- /dev/null +++ b/include/gz/sim/components/JointVelocity.hh @@ -0,0 +1,46 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_JOINTVELOCITY_HH_ +#define GZ_GAZEBO_COMPONENTS_JOINTVELOCITY_HH_ + +#include + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief Base class which can be extended to add serialization + using JointVelocity = Component, class JointVelocityTag, + serializers::VectorDoubleSerializer>; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.JointVelocity", JointVelocity) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/JointVelocityCmd.hh b/include/gz/sim/components/JointVelocityCmd.hh new file mode 100644 index 0000000000..dc7e158c87 --- /dev/null +++ b/include/gz/sim/components/JointVelocityCmd.hh @@ -0,0 +1,48 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_JOINTVELOCITYCMD_HH_ +#define GZ_GAZEBO_COMPONENTS_JOINTVELOCITYCMD_HH_ + +#include + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief Base class which can be extended to add serialization + using JointVelocityCmd = + Component, class JointVelocityCmdTag, + serializers::VectorDoubleSerializer>; + + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.JointVelocityCmd", JointVelocityCmd) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/JointVelocityLimitsCmd.hh b/include/gz/sim/components/JointVelocityLimitsCmd.hh new file mode 100644 index 0000000000..0dcd68c5d1 --- /dev/null +++ b/include/gz/sim/components/JointVelocityLimitsCmd.hh @@ -0,0 +1,58 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_JOINTVELOCITYLIMITSCMD_HH_ +#define GZ_GAZEBO_COMPONENTS_JOINTVELOCITYLIMITSCMD_HH_ + +#include +#include + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + +namespace components +{ +/// \brief Command for setting velocity limits of a joint. Data are a vector +/// with a Vector2 for each DOF. The X() component of the Vector2 specifies +/// the minimum velocity limit, the Y() component stands for maximum limit. +/// Set to +-infinity to disable the limits. +/// \note It is expected that the physics plugin reads this component and +/// sets the limit to the dynamics engine. After setting it, the data of this +/// component will be cleared (i.e. the vector will have length zero). +using JointVelocityLimitsCmd = Component< + std::vector, + class JointVelocityLimitsCmdTag, + serializers::VectorSerializer +>; + +IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.JointVelocityLimitsCmd", JointVelocityLimitsCmd) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/JointVelocityReset.hh b/include/gz/sim/components/JointVelocityReset.hh new file mode 100644 index 0000000000..ca81e3e87e --- /dev/null +++ b/include/gz/sim/components/JointVelocityReset.hh @@ -0,0 +1,50 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_JOINTVELOCITYRESET_HH_ +#define GZ_GAZEBO_COMPONENTS_JOINTVELOCITYRESET_HH_ + +#include + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief Joint velocities in SI units + /// (rad/s for revolute, m/s for prismatic). + /// + /// The component wraps a std::vector of size equal to the degrees of freedom + /// of the joint. + using JointVelocityReset = Component, + class JointVelocityResetTag, + serializers::VectorDoubleSerializer>; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.JointVelocityReset", JointVelocityReset) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/LaserRetro.hh b/include/gz/sim/components/LaserRetro.hh new file mode 100644 index 0000000000..81f505fb45 --- /dev/null +++ b/include/gz/sim/components/LaserRetro.hh @@ -0,0 +1,41 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_LASERRETRO_HH_ +#define GZ_GAZEBO_COMPONENTS_LASERRETRO_HH_ + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component used to indicate an lidar reflective value + using LaserRetro = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LaserRetro", + LaserRetro) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Level.hh b/include/gz/sim/components/Level.hh new file mode 100644 index 0000000000..8afa35f705 --- /dev/null +++ b/include/gz/sim/components/Level.hh @@ -0,0 +1,46 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_LEVEL_HH_ +#define GZ_GAZEBO_COMPONENTS_LEVEL_HH_ + +#include +#include + +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Component.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief This component identifies an entity as being a level. + using Level = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_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", + DefaultLevel) +} +} +} +} +#endif diff --git a/include/gz/sim/components/LevelBuffer.hh b/include/gz/sim/components/LevelBuffer.hh new file mode 100644 index 0000000000..07771a8859 --- /dev/null +++ b/include/gz/sim/components/LevelBuffer.hh @@ -0,0 +1,43 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_LEVELBUFFER_HH_ +#define GZ_GAZEBO_COMPONENTS_LEVELBUFFER_HH_ + +#include +#include + +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Component.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component that holds the buffer setting of a level's geometry + using LevelBuffer = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LevelBuffer", + LevelBuffer) +} +} +} +} +#endif + diff --git a/include/gz/sim/components/LevelEntityNames.hh b/include/gz/sim/components/LevelEntityNames.hh new file mode 100644 index 0000000000..6f30ce1378 --- /dev/null +++ b/include/gz/sim/components/LevelEntityNames.hh @@ -0,0 +1,89 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_LEVELENTITYNAMES_HH_ +#define GZ_GAZEBO_COMPONENTS_LEVELENTITYNAMES_HH_ + +#include +#include +#include +#include +#include + +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Component.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace serializers +{ + class LevelEntityNamesSerializer + { + /// \brief Serialization for `std::set`. + /// \param[in] _out Output stream. + /// \param[in] _set Set to stream + /// \return The stream. + public: static std::ostream &Serialize(std::ostream &_out, + const std::set &_set) + { + for (const auto &entity : _set) + { + _out << entity << " "; + } + return _out; + } + + /// \brief Deserialization for `std::set`. + /// \param[in] _in Input stream. + /// \param[out] _set Set to populate + /// \return The stream. + public: static std::istream &Deserialize(std::istream &_in, + std::set &_set) + { + _in.setf(std::ios_base::skipws); + + _set.clear(); + + for (auto it = std::istream_iterator(_in); + it != std::istream_iterator(); ++it) + { + _set.insert(*it); + } + return _in; + } + }; +} + +namespace components +{ + /// \brief A component that holds a list of names of entities to be loaded in + /// a level. + using LevelEntityNames = + Component, class LevelEntityNamesTag, + serializers::LevelEntityNamesSerializer>; + + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LevelEntityNames", + LevelEntityNames) +} +} +} +} +#endif + diff --git a/include/gz/sim/components/Lidar.hh b/include/gz/sim/components/Lidar.hh new file mode 100644 index 0000000000..21a8dd9aea --- /dev/null +++ b/include/gz/sim/components/Lidar.hh @@ -0,0 +1,43 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_LIDAR_HH_ +#define GZ_GAZEBO_COMPONENTS_LIDAR_HH_ + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains a Lidar sensor, + /// sdf::Lidar, information. + using Lidar = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Lidar", Lidar) +} +} +} +} +#endif diff --git a/include/gz/sim/components/Light.hh b/include/gz/sim/components/Light.hh new file mode 100644 index 0000000000..980181d9d7 --- /dev/null +++ b/include/gz/sim/components/Light.hh @@ -0,0 +1,55 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_LIGHT_HH_ +#define GZ_GAZEBO_COMPONENTS_LIGHT_HH_ + +#include + +#include + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace serializers +{ + using LightSerializer = + serializers::ComponentToMsgSerializer; +} + +namespace components +{ + /// \brief This component contains light source information. For more + /// information on lights, see [SDF's Light + /// element](http://sdformat.org/spec?ver=1.6&elem=light). + using Light = + Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Light", Light) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/LinearAcceleration.hh b/include/gz/sim/components/LinearAcceleration.hh new file mode 100644 index 0000000000..b71a3440b8 --- /dev/null +++ b/include/gz/sim/components/LinearAcceleration.hh @@ -0,0 +1,53 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_LINEARACCELERATION_HH_ +#define GZ_GAZEBO_COMPONENTS_LINEARACCELERATION_HH_ + +#include + +#include +#include + +#include +#include "gz/sim/components/Component.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains linear acceleration of an entity + /// represented by gz::math::Vector3d. + using LinearAcceleration = + Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LinearAcceleration", + LinearAcceleration) + + /// \brief A component type that contains linear acceleration of an entity + /// in the world frame represented by gz::math::Vector3d. + using WorldLinearAcceleration = + Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WorldLinearAcceleration", + WorldLinearAcceleration) +} +} +} +} +#endif diff --git a/include/gz/sim/components/LinearVelocity.hh b/include/gz/sim/components/LinearVelocity.hh new file mode 100644 index 0000000000..40c320a2ab --- /dev/null +++ b/include/gz/sim/components/LinearVelocity.hh @@ -0,0 +1,50 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_LINEARVELOCITY_HH_ +#define GZ_GAZEBO_COMPONENTS_LINEARVELOCITY_HH_ + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains linear velocity of an entity + /// represented by gz::math::Vector3d. + using LinearVelocity = Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.LinearVelocity", LinearVelocity) + + /// \brief A component type that contains linear velocity of an entity in the + /// world frame represented by gz::math::Vector3d. + using WorldLinearVelocity = + Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.WorldLinearVelocity", WorldLinearVelocity) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/LinearVelocityCmd.hh b/include/gz/sim/components/LinearVelocityCmd.hh new file mode 100644 index 0000000000..93d99c56e3 --- /dev/null +++ b/include/gz/sim/components/LinearVelocityCmd.hh @@ -0,0 +1,55 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_LINEARVELOCITYCMD_HH_ +#define GZ_GAZEBO_COMPONENTS_LINEARVELOCITYCMD_HH_ + +#include + +#include + +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + // \brief A component type that contains the commanded linear velocity of an + /// entity represented by gz::math::Vector3d, expressed in the entity's + /// frame. + using LinearVelocityCmd = Component< + math::Vector3d, class LinearVelocityCmdTag>; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.LinearVelocityCmd", LinearVelocityCmd) + + /// \brief A component type that contains the commanded linear velocity of an + /// entity represented by gz::math::Vector3d, expressed in the world + /// frame. + using WorldLinearVelocityCmd = + Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.WorldLinearVelocityCmd", WorldLinearVelocityCmd) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/LinearVelocitySeed.hh b/include/gz/sim/components/LinearVelocitySeed.hh new file mode 100644 index 0000000000..1e124b6f3e --- /dev/null +++ b/include/gz/sim/components/LinearVelocitySeed.hh @@ -0,0 +1,55 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_LINEARVELOCITYSEED_HH_ +#define GZ_GAZEBO_COMPONENTS_LINEARVELOCITYSEED_HH_ + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains linear velocity seed of an entity + /// expressed in the local frame of the entity and represented by + /// gz::math::Vector3d. This seed can used to generate linear velocities + /// by applying transformations and adding noise. + using LinearVelocitySeed = + Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LinearVelocitySeed", + LinearVelocitySeed) + + /// \brief A component type that contains linear velocity seed of an entity in + /// the world frame represented by gz::math::Vector3d. This seed can + /// used to generate linear velocities by applying transformations and adding + /// noise. + using WorldLinearVelocitySeed = + Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WorldLinearVelocitySeed", + WorldLinearVelocitySeed) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Link.hh b/include/gz/sim/components/Link.hh new file mode 100644 index 0000000000..74f7beb112 --- /dev/null +++ b/include/gz/sim/components/Link.hh @@ -0,0 +1,40 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_LINK_HH_ +#define GZ_GAZEBO_COMPONENTS_LINK_HH_ + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component that identifies an entity as being a link. + using Link = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Link", Link) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/LogPlaybackStatistics.hh b/include/gz/sim/components/LogPlaybackStatistics.hh new file mode 100644 index 0000000000..ef562b1a83 --- /dev/null +++ b/include/gz/sim/components/LogPlaybackStatistics.hh @@ -0,0 +1,48 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_LogPlaybackStatistics_HH_ +#define GZ_GAZEBO_COMPONENTS_LogPlaybackStatistics_HH_ + +#include +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains log playback, + /// systems::LogPlayback, information. + /// The log playback is created from world entity upon the playback plugin + /// being loaded + using LogPlaybackStatistics = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LogPlaybackStatistics", + LogPlaybackStatistics) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/LogicalAudio.hh b/include/gz/sim/components/LogicalAudio.hh new file mode 100644 index 0000000000..182f58bade --- /dev/null +++ b/include/gz/sim/components/LogicalAudio.hh @@ -0,0 +1,325 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_LOGICALAUDIO_HH_ +#define GZ_GAZEBO_COMPONENTS_LOGICALAUDIO_HH_ + +#include +#include +#include +#include +#include + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace logical_audio +{ + /// \brief Audio source attenuation functions. + /// AttenuationFunction::Undefined is used to indicate that an + /// attenuation function has not been defined yet. + enum class AttenuationFunction { LINEAR, UNDEFINED }; + + /// \brief Audio source attenuation shapes. + /// AttenuationShape::Undefined is used to indicate that an + /// attenuation shape has not been defined yet. + enum class AttenuationShape { SPHERE, UNDEFINED }; + + /// \brief Properties of a logical audio source. + /// A source also has a pose, which can be stored as a component of a + /// source entity via gz::sim::components::Pose + struct Source + { + /// \brief The source's id + unsigned int id; + + /// \brief The source's attenuation function + logical_audio::AttenuationFunction attFunc; + + /// \brief The source's attenuation shape + logical_audio::AttenuationShape attShape; + + /// \brief The source's inner radius, which should be >= 0 + double innerRadius; + + /// \brief The source's falloff distance, which should be + /// greater than Source::innerRadius + double falloffDistance; + + /// \brief The source's emission volume, which should be + /// between 0.0 (0% volume) and 1.0 (100% volume) + double emissionVolume; + + public: bool operator==(const Source &_source) const + { + return this->id == _source.id; + } + + public: bool operator!=(const Source &_source) const + { + return !(*this == _source); + } + }; + + /// \brief A source's playing information. + /// Useful for keeping track of when to start/stop playing a source. + struct SourcePlayInfo + { + /// \brief Constructor + SourcePlayInfo() : startTime() + { + } + + /// \brief Whether the source is currently playing or not + bool playing{false}; + + /// \brief How long the source should play for, in seconds. + /// Setting this to 0 means the source has a play duration of infinity + std::chrono::seconds playDuration; + + /// \brief The time at which the source most recently started playing + std::chrono::steady_clock::duration startTime; + + public: bool operator==(const SourcePlayInfo &_sourcePlayInfo) const + { + return (this->playing == _sourcePlayInfo.playing) && + (this->playDuration == _sourcePlayInfo.playDuration) && + (this->startTime == _sourcePlayInfo.startTime); + } + + public: bool operator!=(const SourcePlayInfo &_sourcePlayInfo) const + { + return !(*this == _sourcePlayInfo); + } + }; + + /// \brief Properties of a logical audio microphone. + /// A microphone also has a pose, which can be stored as a component of a + /// microphone entity via gz::sim::components::Pose + struct Microphone + { + /// \brief The microphone's id + unsigned int id; + + /// \brief The minimum volume this microphone can detect. + /// This should be a value between 0.0 (0% volume) and 1.0 (100% volume) + double volumeDetectionThreshold; + + public: bool operator==(const Microphone &_microphone) const + { + return this->id == _microphone.id; + } + + public: bool operator!=(const Microphone &_microphone) const + { + return !(*this == _microphone); + } + }; +} + +namespace serializers +{ + /// \brief Output stream overload for logical_audio::AttenuationFunction + inline std::ostream &operator<<(std::ostream &_out, + const logical_audio::AttenuationFunction &_func) + { + auto temp = static_cast(_func); + _out << temp; + return _out; + } + + /// \brief Input stream overload for logical_audio::AttenuationFunction + inline std::istream &operator>>(std::istream &_in, + logical_audio::AttenuationFunction &_func) + { + unsigned int temp = 0u; + if (_in >> temp) + _func = static_cast(temp); + return _in; + } + + /// \brief Output stream overload for logical_audio::AttenuationShape + inline std::ostream &operator<<(std::ostream &_out, + const logical_audio::AttenuationShape &_shape) + { + auto temp = static_cast(_shape); + _out << temp; + return _out; + } + + /// \brief Input stream overload for logical_audio::AttenuationShape + inline std::istream &operator>>(std::istream &_in, + logical_audio::AttenuationShape &_shape) + { + unsigned int temp = 0u; + if (_in >> temp) + _shape = static_cast(temp); + return _in; + } + + /// \brief Output stream overload for std::chrono::steady_clock::duration + inline std::ostream &operator<<(std::ostream &_out, + const std::chrono::steady_clock::duration &_dur) + { + _out << std::chrono::duration_cast( + _dur).count(); + return _out; + } + + /// \brief Input stream overload for std::chrono::steady_clock::duration + inline std::istream &operator>>(std::istream &_in, + std::chrono::steady_clock::duration &_dur) + { + int64_t time; + _in >> time; + _dur = std::chrono::duration(time); + return _in; + } + + /// \brief Serializer for components::LogicalAudioSource object + class LogicalAudioSourceSerializer + { + /// \brief Serialization for logical_audio::Source + /// \param[out] _out Output stream + /// \param[in] _source Object for the stream + /// \return The stream + public: static std::ostream &Serialize(std::ostream &_out, + const logical_audio::Source &_source) + { + _out << _source.id << " " << _source.attFunc << " " << _source.attShape + << " " << _source.innerRadius << " " << _source.falloffDistance + << " " << _source.emissionVolume; + return _out; + } + + /// \brief Deserialization for logical_audio::Source + /// \param[in] _in Input stream + /// \param[out] _source The object to populate + /// \return The stream + public: static std::istream &Deserialize(std::istream &_in, + logical_audio::Source &_source) + { + _in >> _source.id >> _source.attFunc >> _source.attShape + >> _source.innerRadius >> _source.falloffDistance + >> _source.emissionVolume; + return _in; + } + }; + + /// \brief Serializer for components::LogicalAudioSourcePlayInfo object + class LogicalAudioSourcePlayInfoSerializer + { + /// \brief Serialization for logical_audio::SourcePlayInfo + /// \param[out] _out Output stream + /// \param[in] _playInfo Object for the stream + /// \return The stream + public: static std::ostream &Serialize(std::ostream &_out, + const logical_audio::SourcePlayInfo &_playInfo) + { + _out << _playInfo.playing << " " << _playInfo.playDuration.count() << " " + << _playInfo.startTime; + return _out; + } + + /// \brief Deserialization for logical_audio::SourcePlayInfo + /// \param[in] _in Input stream + /// \param[out] _playInfo The object to populate + /// \return The stream + public: static std::istream &Deserialize(std::istream &_in, + logical_audio::SourcePlayInfo &_playInfo) + { + uint64_t count; + _in >> _playInfo.playing >> count >> _playInfo.startTime; + _playInfo.playDuration = std::chrono::seconds(count); + return _in; + } + }; + + /// \brief Serializer for components::LogicalMicrophone object + class LogicalMicrophoneSerializer + { + /// \brief Serialization for logical_audio::Microphone + /// \param[out] _out Output stream + /// \param[in] _mic Object for the stream + /// \return The stream + public: static std::ostream &Serialize(std::ostream &_out, + const logical_audio::Microphone &_mic) + { + _out << _mic.id << " " << _mic.volumeDetectionThreshold; + return _out; + } + + /// \brief Deserialization for logical_audio::Microphone + /// \param[in] _in Inout stream + /// \param[out] _mic The object to populate + public: static std::istream &Deserialize(std::istream &_in, + logical_audio::Microphone &_mic) + { + _in >> _mic.id >> _mic.volumeDetectionThreshold; + return _in; + } + }; +} + +// using separate namespace blocks so all components appear in Doxygen +// (appears as if Doxygen can't parse multiple components in a single +// namespace block since IGN_GAZEBO_REGISTER_COMPONENT doesn't have a +// trailing semicolon) +namespace components +{ + /// \brief A component that contains a logical audio source, which is + /// represented by logical_audio::Source + using LogicalAudioSource = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LogicalAudioSource", + LogicalAudioSource) +} + +namespace components +{ + /// \brief A component that contains a logical audio source's playing + /// information, which is represented by logical_audio::SourcePlayInfo + using LogicalAudioSourcePlayInfo = Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.LogicalAudioSourcePlayInfo", + LogicalAudioSourcePlayInfo) +} + +namespace components +{ + /// \brief A component that contains a logical microphone, which is + /// represented by logical_audio::Microphone + using LogicalMicrophone = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LogicalMicrophone", + LogicalMicrophone) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/LogicalCamera.hh b/include/gz/sim/components/LogicalCamera.hh new file mode 100644 index 0000000000..7e285b0bc4 --- /dev/null +++ b/include/gz/sim/components/LogicalCamera.hh @@ -0,0 +1,43 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_LOGICALCAMERA_HH_ +#define GZ_GAZEBO_COMPONENTS_LOGICALCAMERA_HH_ + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +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", + LogicalCamera) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/MagneticField.hh b/include/gz/sim/components/MagneticField.hh new file mode 100644 index 0000000000..05cd70fce0 --- /dev/null +++ b/include/gz/sim/components/MagneticField.hh @@ -0,0 +1,44 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_MAGNETICFIELD_HH_ +#define GZ_GAZEBO_COMPONENTS_MAGNETICFIELD_HH_ + +#include + +#include +#include + +#include +#include "gz/sim/components/Component.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief Stores the 3D magnetic field in teslas. + using MagneticField = Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.MagneticField", MagneticField) +} +} +} +} +#endif diff --git a/include/gz/sim/components/Magnetometer.hh b/include/gz/sim/components/Magnetometer.hh new file mode 100644 index 0000000000..c9b7a870cc --- /dev/null +++ b/include/gz/sim/components/Magnetometer.hh @@ -0,0 +1,48 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_MAGNETOMETER_HH_ +#define GZ_GAZEBO_COMPONENTS_MAGNETOMETER_HH_ + +#include + +#include +#include + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains a magnetometer sensor, + /// sdf::Magnetometer, information. + using Magnetometer = Component; + + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.Magnetometer", Magnetometer) +} +} +} +} +#endif diff --git a/include/gz/sim/components/Material.hh b/include/gz/sim/components/Material.hh new file mode 100644 index 0000000000..6c4a03cbf7 --- /dev/null +++ b/include/gz/sim/components/Material.hh @@ -0,0 +1,51 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_MATERIAL_HH_ +#define GZ_GAZEBO_COMPONENTS_MATERIAL_HH_ + +#include + +#include + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace serializers +{ + using MaterialSerializer = + serializers::ComponentToMsgSerializer; +} +namespace components +{ + /// \brief This component holds an entity's material. + using Material = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Material", Material) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Model.hh b/include/gz/sim/components/Model.hh new file mode 100644 index 0000000000..79b5b377b9 --- /dev/null +++ b/include/gz/sim/components/Model.hh @@ -0,0 +1,46 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_MODEL_HH_ +#define GZ_GAZEBO_COMPONENTS_MODEL_HH_ + +#include + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component that identifies an entity as being a model. + using Model = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_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) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Name.hh b/include/gz/sim/components/Name.hh new file mode 100644 index 0000000000..7b17201400 --- /dev/null +++ b/include/gz/sim/components/Name.hh @@ -0,0 +1,42 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_NAME_HH_ +#define GZ_GAZEBO_COMPONENTS_NAME_HH_ + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief This component holds an entity's name. The component has no concept + /// of scoped names nor does it care about uniqueness. + using Name = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Name", Name) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/ParentEntity.hh b/include/gz/sim/components/ParentEntity.hh new file mode 100644 index 0000000000..c53e4e1e62 --- /dev/null +++ b/include/gz/sim/components/ParentEntity.hh @@ -0,0 +1,49 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_PARENTENTITY_HH_ +#define GZ_GAZEBO_COMPONENTS_PARENTENTITY_HH_ + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief This component holds an entity's parent entity. + /// + /// Note that the EntityComponentManager also keeps the parent-child + /// relationship stored in a graph, and that information should be + /// kept in sync with the parent entity components. Therefore, + /// it is recommended that the `ParentEntity` component is never + /// edited by hand, and instead, entities should be created using + /// the `sim::SdfEntityCreator` class. + using ParentEntity = Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.ParentEntity", ParentEntity) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/ParentLinkName.hh b/include/gz/sim/components/ParentLinkName.hh new file mode 100644 index 0000000000..18fe3046f3 --- /dev/null +++ b/include/gz/sim/components/ParentLinkName.hh @@ -0,0 +1,42 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_PARENTLINKNAME_HH_ +#define GZ_GAZEBO_COMPONENTS_PARENTLINKNAME_HH_ + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief Holds the name of the entity's parent link. + using ParentLinkName = Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.ParentLinkName", ParentLinkName) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Performer.hh b/include/gz/sim/components/Performer.hh new file mode 100644 index 0000000000..7b3781fa39 --- /dev/null +++ b/include/gz/sim/components/Performer.hh @@ -0,0 +1,41 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_PERFORMER_HH_ +#define GZ_GAZEBO_COMPONENTS_PERFORMER_HH_ + +#include +#include + +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Component.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief This component identifies an entity as being a performer. + using Performer = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Performer", Performer) +} +} +} +} +#endif diff --git a/include/gz/sim/components/PerformerAffinity.hh b/include/gz/sim/components/PerformerAffinity.hh new file mode 100644 index 0000000000..d7b4eb3890 --- /dev/null +++ b/include/gz/sim/components/PerformerAffinity.hh @@ -0,0 +1,47 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_PERFORMERAFFINITY_HH_ +#define GZ_GAZEBO_COMPONENTS_PERFORMERAFFINITY_HH_ + +#include + +#include +#include + +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Component.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief This component holds the address of the distributed secondary that + /// this performer is associated with. + using PerformerAffinity = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.PerformerAffinity", + PerformerAffinity) +} +} +} +} + +#endif + diff --git a/include/gz/sim/components/PerformerLevels.hh b/include/gz/sim/components/PerformerLevels.hh new file mode 100644 index 0000000000..58b492cb25 --- /dev/null +++ b/include/gz/sim/components/PerformerLevels.hh @@ -0,0 +1,85 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_PERFORMERLEVELS_HH_ +#define GZ_GAZEBO_COMPONENTS_PERFORMERLEVELS_HH_ + +#include +#include +#include + +#include "gz/sim/Entity.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Component.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace serializers +{ + class PerformerLevelsSerializer + { + /// \brief Serialization for `std::set`. + /// \param[in] _out Output stream. + /// \param[in] _set Set to stream + /// \return The stream. + public: static std::ostream &Serialize(std::ostream &_out, + const std::set &_set) + { + for (const auto &level : _set) + { + _out << level << " "; + } + return _out; + } + + /// \brief Deserialization for `std::set`. + /// \param[in] _in Input stream. + /// \param[out] _set Set to populate + /// \return The stream. + public: static std::istream &Deserialize(std::istream &_in, + std::set &_set) + { + _in.setf(std::ios_base::skipws); + + _set.clear(); + + for (auto it = std::istream_iterator(_in); + it != std::istream_iterator(); ++it) + { + _set.insert(*it); + } + return _in; + } + }; +} + +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", + PerformerLevels) +} +} +} +} +#endif + diff --git a/include/gz/sim/components/Physics.hh b/include/gz/sim/components/Physics.hh new file mode 100644 index 0000000000..554e667918 --- /dev/null +++ b/include/gz/sim/components/Physics.hh @@ -0,0 +1,56 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_PHYSICS_HH_ +#define GZ_GAZEBO_COMPONENTS_PHYSICS_HH_ + +#include + +#include + +#include +#include + +#include +#include "gz/sim/components/Component.hh" +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace serializers +{ + using PhysicsSerializer = + serializers::ComponentToMsgSerializer; +} +namespace components +{ + /// \brief A component type that contains the physics properties of + /// the World entity. + using Physics = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Physics", + Physics) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/PhysicsCmd.hh b/include/gz/sim/components/PhysicsCmd.hh new file mode 100644 index 0000000000..2d992a4d5f --- /dev/null +++ b/include/gz/sim/components/PhysicsCmd.hh @@ -0,0 +1,46 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_PHYSICSCMD_HH_ +#define GZ_GAZEBO_COMPONENTS_PHYSICSCMD_HH_ + +#include + +#include +#include + +#include +#include "gz/sim/components/Component.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +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", + PhysicsCmd) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/PhysicsEnginePlugin.hh b/include/gz/sim/components/PhysicsEnginePlugin.hh new file mode 100644 index 0000000000..462e957dde --- /dev/null +++ b/include/gz/sim/components/PhysicsEnginePlugin.hh @@ -0,0 +1,43 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_PHYSICSENGINEPLUGIN_HH_ +#define GZ_GAZEBO_COMPONENTS_PHYSICSENGINEPLUGIN_HH_ + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief Holds the physics engine shared library. + using PhysicsEnginePlugin = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.PhysicsEnginePlugin", + PhysicsEnginePlugin) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Pose.hh b/include/gz/sim/components/Pose.hh new file mode 100644 index 0000000000..13ec568d58 --- /dev/null +++ b/include/gz/sim/components/Pose.hh @@ -0,0 +1,48 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_POSE_HH_ +#define GZ_GAZEBO_COMPONENTS_POSE_HH_ + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains pose, gz::math::Pose3d, + /// information. + using Pose = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Pose", Pose) + + /// \brief A component type that contains pose, gz::math::Pose3d, + /// information in world frame. + using WorldPose = Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.WorldPose", WorldPose) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/PoseCmd.hh b/include/gz/sim/components/PoseCmd.hh new file mode 100644 index 0000000000..cd1b2a49f6 --- /dev/null +++ b/include/gz/sim/components/PoseCmd.hh @@ -0,0 +1,45 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_POSECMD_HH_ +#define GZ_GAZEBO_COMPONENTS_POSECMD_HH_ + +#include + +#include +#include + +#include +#include "gz/sim/components/Component.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains commanded pose of an + /// entity in the world frame represented by gz::math::Pose3d. + using WorldPoseCmd = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WorldPoseCmd", + WorldPoseCmd) +} +} +} +} +#endif diff --git a/include/gz/sim/components/RenderEngineGuiPlugin.hh b/include/gz/sim/components/RenderEngineGuiPlugin.hh new file mode 100644 index 0000000000..0c7ed3e1bb --- /dev/null +++ b/include/gz/sim/components/RenderEngineGuiPlugin.hh @@ -0,0 +1,44 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_RENDERENGINEGUIPLUGIN_HH_ +#define GZ_GAZEBO_COMPONENTS_RENDERENGINEGUIPLUGIN_HH_ + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief Holds the render engine gui shared library. + using RenderEngineGuiPlugin = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.RenderEngineGuiPlugin", + RenderEngineGuiPlugin) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/RenderEngineServerPlugin.hh b/include/gz/sim/components/RenderEngineServerPlugin.hh new file mode 100644 index 0000000000..ca904f7cd3 --- /dev/null +++ b/include/gz/sim/components/RenderEngineServerPlugin.hh @@ -0,0 +1,45 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_RENDERENGINESERVERPLUGIN_HH_ +#define GZ_GAZEBO_COMPONENTS_RENDERENGINESERVERPLUGIN_HH_ + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief Holds the render engine server shared library. + using RenderEngineServerPlugin = Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.RenderEngineServerPlugin", + RenderEngineServerPlugin) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/RgbdCamera.hh b/include/gz/sim/components/RgbdCamera.hh new file mode 100644 index 0000000000..1f84ef40cd --- /dev/null +++ b/include/gz/sim/components/RgbdCamera.hh @@ -0,0 +1,44 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_RGBDCAMERA_HH_ +#define GZ_GAZEBO_COMPONENTS_RGBDCAMERA_HH_ + +#include + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains a RGBD camera sensor, + /// sdf::Camera, information. + using RgbdCamera = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.RgbdCamera", RgbdCamera) +} +} +} +} +#endif diff --git a/include/gz/sim/components/Scene.hh b/include/gz/sim/components/Scene.hh new file mode 100644 index 0000000000..ae03043366 --- /dev/null +++ b/include/gz/sim/components/Scene.hh @@ -0,0 +1,53 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_SCENE_HH_ +#define GZ_GAZEBO_COMPONENTS_SCENE_HH_ + +#include + +#include +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace serializers +{ + using SceneSerializer = + serializers::ComponentToMsgSerializer; +} + +namespace components +{ + /// \brief This component holds scene properties of the world. + using Scene = + Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.Scene", Scene) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/SelfCollide.hh b/include/gz/sim/components/SelfCollide.hh new file mode 100644 index 0000000000..e65b0918ca --- /dev/null +++ b/include/gz/sim/components/SelfCollide.hh @@ -0,0 +1,42 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_SELFCOLLIDE_HH_ +#define GZ_GAZEBO_COMPONENTS_SELFCOLLIDE_HH_ + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component used to hold a model's self collide property. + using SelfCollide = Component; + + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SelfCollide", + SelfCollide) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Sensor.hh b/include/gz/sim/components/Sensor.hh new file mode 100644 index 0000000000..349cb046da --- /dev/null +++ b/include/gz/sim/components/Sensor.hh @@ -0,0 +1,51 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_SENSOR_HH_ +#define GZ_GAZEBO_COMPONENTS_SENSOR_HH_ + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component that identifies an entity as being a sensor. + using Sensor = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Sensor", Sensor) + + /// \brief Name of the transport topic where a sensor is publishing its + /// data. + /// For sensors that publish on more than one topic, this will usually be the + /// prefix common to all topics of that sensor. + using SensorTopic = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SensorTopic", + SensorTopic) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Serialization.hh b/include/gz/sim/components/Serialization.hh new file mode 100644 index 0000000000..b3b254259b --- /dev/null +++ b/include/gz/sim/components/Serialization.hh @@ -0,0 +1,225 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_SERIALIZATION_HH_ +#define GZ_GAZEBO_COMPONENTS_SERIALIZATION_HH_ + +#include +#include + +#include +#include +#include + +#include + +// This header holds serialization operators which are shared among several +// components + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +/// \brief A Serializer class is used to serialize and deserialize a component. +/// It is passed in as the third template parameter to components::Component. +/// Eg. +/// \code +/// using Geometry = components::Component +/// \endcode +/// A serializer class implements two static functions: `Serialize` and +/// `Deserialize` with the following signatures +/// \code +/// class ExampleSerializer +/// { +/// public: static std::ostream &Serialize(std::ostream &_out, +/// const DataType &_data); +/// public: static std::istream &Deserialize(std::istream &_in, +/// DataType &_data) +/// }; +/// \endcode + +namespace serializers +{ + /// \brief Serialization for that converts components data types to + /// gz::msgs. This assumes that gz::sim::convert is + /// defined + /// \tparam DataType Underlying data type of the component + /// + /// This can be used for components that can be converted to gz::msg + /// types via gz::sim::convert. For example sdf::Geometry can be + /// converted to msgs::Geometry so the component can be defined as + /// \code + /// using Geometry = Component> + /// \endcode + template + class ComponentToMsgSerializer + { + /// \brief Serialization + /// \param[in] _out Output stream. + /// \param[in] _data data to stream + /// \return The stream. + public: static std::ostream &Serialize(std::ostream &_out, + const DataType &_data) + { + auto msg = gz::sim::convert(_data); + msg.SerializeToOstream(&_out); + return _out; + } + + /// \brief Deserialization + /// \param[in] _in Input stream. + /// \param[out] _data data to populate + /// \return The stream. + public: static std::istream &Deserialize(std::istream &_in, + DataType &_data) + { + MsgType msg; + msg.ParseFromIstream(&_in); + + _data = gz::sim::convert(msg); + return _in; + } + }; + + /// \brief Common serializer for sensors + using SensorSerializer = ComponentToMsgSerializer; + + /// \brief Serializer for components that hold `std::vector`. + class VectorDoubleSerializer + { + /// \brief Serialization + /// \param[in] _out Output stream. + /// \param[in] _vec Vector to stream + /// \return The stream. + public: static std::ostream &Serialize(std::ostream &_out, + const std::vector &_vec) + { + gz::msgs::Double_V msg; + *msg.mutable_data() = {_vec.begin(), _vec.end()}; + msg.SerializeToOstream(&_out); + return _out; + } + + /// \brief Deserialization + /// \param[in] _in Input stream. + /// \param[in] _vec Vector to populate + /// \return The stream. + public: static std::istream &Deserialize(std::istream &_in, + std::vector &_vec) + { + gz::msgs::Double_V msg; + msg.ParseFromIstream(&_in); + + _vec = {msg.data().begin(), msg.data().end()}; + return _in; + } + }; + + /// \brief Serializer for components that hold protobuf messages. + class MsgSerializer + { + /// \brief Serialization + /// \param[in] _out Output stream. + /// \param[in] _msg Message to stream + /// \return The stream. + public: static std::ostream &Serialize(std::ostream &_out, + const google::protobuf::Message &_msg) + { + _msg.SerializeToOstream(&_out); + return _out; + } + + /// \brief Deserialization + /// \param[in] _in Input stream. + /// \param[in] _msg Message to populate + /// \return The stream. + public: static std::istream &Deserialize(std::istream &_in, + google::protobuf::Message &_msg) + { + _msg.ParseFromIstream(&_in); + return _in; + } + }; + + /// \brief Serializer for components that hold std::string. + class StringSerializer + { + /// \brief Serialization + /// \param[in] _out Output stream. + /// \param[in] _data Data to serialize. + /// \return The stream. + public: static std::ostream &Serialize(std::ostream &_out, + const std::string &_data) + { + _out << _data; + return _out; + } + + /// \brief Deserialization + /// \param[in] _in Input stream. + /// \param[in] _data Data to populate. + /// \return The stream. + public: static std::istream &Deserialize(std::istream &_in, + std::string &_data) + { + _data = std::string(std::istreambuf_iterator(_in), {}); + return _in; + } + }; + + template + class VectorSerializer + { + /// \brief Serialization for `std::vector` with serializable T. + /// \param[in] _out Output stream. + /// \param[in] _data The data to stream. + /// \return The stream. + public: static std::ostream &Serialize(std::ostream &_out, + const std::vector &_data) + { + _out << _data.size(); + for (const auto& datum : _data) + _out << " " << datum; + return _out; + } + + /// \brief Deserialization for `std::vector` with serializable T. + /// \param[in] _in Input stream. + /// \param[out] _data The data to populate. + /// \return The stream. + public: static std::istream &Deserialize(std::istream &_in, + std::vector &_data) + { + size_t size; + _in >> size; + _data.resize(size); + for (size_t i = 0; i < size; ++i) + { + _in >> _data[i]; + } + return _in; + } + }; +} +} +} +} + +#endif diff --git a/include/gz/sim/components/SlipComplianceCmd.hh b/include/gz/sim/components/SlipComplianceCmd.hh new file mode 100644 index 0000000000..5b48feab10 --- /dev/null +++ b/include/gz/sim/components/SlipComplianceCmd.hh @@ -0,0 +1,49 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#ifndef GZ_GAZEBO_COMPONENTS_SLIPCOMPLIANCECMD_HH_ +#define GZ_GAZEBO_COMPONENTS_SLIPCOMPLIANCECMD_HH_ + +#include + +#include +#include + +#include +#include "gz/sim/components/Component.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains the slip compliance parameters to be + /// set on a collision. The 0 and 1 index values correspond to the slip + /// compliance parameters in friction direction 1 (fdir1) and friction + /// direction 2 (fdir2) respectively. + using SlipComplianceCmd = + Component, class SlipComplianceCmdTag>; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SlipComplianceCmd ", + SlipComplianceCmd) +} +} +} +} +#endif diff --git a/include/gz/sim/components/SourceFilePath.hh b/include/gz/sim/components/SourceFilePath.hh new file mode 100644 index 0000000000..a83a48fe6c --- /dev/null +++ b/include/gz/sim/components/SourceFilePath.hh @@ -0,0 +1,45 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_SOURCEFILEPATH_HH_ +#define GZ_GAZEBO_COMPONENTS_SOURCEFILEPATH_HH_ + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief This component holds the filepath to the source from which an + /// entity is created. For example, it can be used to store the file path of a + /// model's SDFormat file. + using SourceFilePath = Component; + + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SourceFilePath", + SourceFilePath) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Static.hh b/include/gz/sim/components/Static.hh new file mode 100644 index 0000000000..46b446203c --- /dev/null +++ b/include/gz/sim/components/Static.hh @@ -0,0 +1,41 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_STATIC_HH_ +#define GZ_GAZEBO_COMPONENTS_STATIC_HH_ + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component used to indicate that a model is static (i.e. not + /// moveable). + using Static = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Static", Static) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Temperature.hh b/include/gz/sim/components/Temperature.hh new file mode 100644 index 0000000000..168f429bb8 --- /dev/null +++ b/include/gz/sim/components/Temperature.hh @@ -0,0 +1,43 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_TEMPERATURE_HH_ +#define GZ_GAZEBO_COMPONENTS_TEMPERATURE_HH_ + +#include + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component that stores temperature data in Kelvin + using Temperature = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Temperature", + Temperature) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/ThermalCamera.hh b/include/gz/sim/components/ThermalCamera.hh new file mode 100644 index 0000000000..e8dbfd3ad0 --- /dev/null +++ b/include/gz/sim/components/ThermalCamera.hh @@ -0,0 +1,45 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_THERMALCAMERA_HH_ +#define GZ_GAZEBO_COMPONENTS_THERMALCAMERA_HH_ + +#include + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains a Thermal camera sensor, + /// sdf::Sensor, information. + using ThermalCamera = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ThermalCamera", + ThermalCamera) +} +} +} +} +#endif diff --git a/include/gz/sim/components/ThreadPitch.hh b/include/gz/sim/components/ThreadPitch.hh new file mode 100644 index 0000000000..7f37702d88 --- /dev/null +++ b/include/gz/sim/components/ThreadPitch.hh @@ -0,0 +1,41 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_THREADPITCH_HH_ +#define GZ_GAZEBO_COMPONENTS_THREADPITCH_HH_ + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component used to store the thread pitch of a screw joint + using ThreadPitch = Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.ThreadPitch", ThreadPitch) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Transparency.hh b/include/gz/sim/components/Transparency.hh new file mode 100644 index 0000000000..06e1acc7e4 --- /dev/null +++ b/include/gz/sim/components/Transparency.hh @@ -0,0 +1,43 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_TRANSPARENCY_HH_ +#define GZ_GAZEBO_COMPONENTS_TRANSPARENCY_HH_ + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component used to indicate an entity's transparency value + /// 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", + Transparency) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Visual.hh b/include/gz/sim/components/Visual.hh new file mode 100644 index 0000000000..897a0fc484 --- /dev/null +++ b/include/gz/sim/components/Visual.hh @@ -0,0 +1,40 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_VISUAL_HH_ +#define GZ_GAZEBO_COMPONENTS_VISUAL_HH_ + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component that identifies an entity as being a visual. + using Visual = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Visual", Visual) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Volume.hh b/include/gz/sim/components/Volume.hh new file mode 100644 index 0000000000..f30c76059c --- /dev/null +++ b/include/gz/sim/components/Volume.hh @@ -0,0 +1,41 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_VOLUME_HH_ +#define GZ_GAZEBO_COMPONENTS_VOLUME_HH_ + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +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) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/Wind.hh b/include/gz/sim/components/Wind.hh new file mode 100644 index 0000000000..b9c6d581e0 --- /dev/null +++ b/include/gz/sim/components/Wind.hh @@ -0,0 +1,40 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_WIND_HH_ +#define GZ_GAZEBO_COMPONENTS_WIND_HH_ + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component that identifies an entity as being a wind. + using Wind = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Wind", Wind) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/WindMode.hh b/include/gz/sim/components/WindMode.hh new file mode 100644 index 0000000000..9319c835cf --- /dev/null +++ b/include/gz/sim/components/WindMode.hh @@ -0,0 +1,40 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef GZ_GAZEBO_COMPONENTS_WINDMODE_HH_ +#define GZ_GAZEBO_COMPONENTS_WINDMODE_HH_ + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component used to indicate whether an entity is affected by wind. + using WindMode = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WindMode", WindMode) +} +} +} +} + +#endif diff --git a/include/gz/sim/components/World.hh b/include/gz/sim/components/World.hh new file mode 100644 index 0000000000..565caf1df1 --- /dev/null +++ b/include/gz/sim/components/World.hh @@ -0,0 +1,46 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_COMPONENTS_WORLD_HH_ +#define GZ_GAZEBO_COMPONENTS_WORLD_HH_ + +#include + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component that identifies an entity as being a world. + using World = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_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) +} +} +} +} + +#endif diff --git a/include/ignition/gazebo/components/components.hh.in b/include/gz/sim/components/components.hh.in similarity index 87% rename from include/ignition/gazebo/components/components.hh.in rename to include/gz/sim/components/components.hh.in index b08e73fb89..10688cb407 100644 --- a/include/ignition/gazebo/components/components.hh.in +++ b/include/gz/sim/components/components.hh.in @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_COMPONENTS_HH_ -#define IGNITION_GAZEBO_COMPONENTS_COMPONENTS_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_COMPONENTS_HH_ +#define GZ_GAZEBO_COMPONENTS_COMPONENTS_HH_ // Automatically generated ${component_includes} diff --git a/include/ignition/gazebo/config.hh.in b/include/gz/sim/config.hh.in similarity index 79% rename from include/ignition/gazebo/config.hh.in rename to include/gz/sim/config.hh.in index 8a817d1687..72249e5b0c 100644 --- a/include/ignition/gazebo/config.hh.in +++ b/include/gz/sim/config.hh.in @@ -11,7 +11,7 @@ #define IGNITION_GAZEBO_VERSION_NAMESPACE v${PROJECT_VERSION_MAJOR} -#define IGNITION_GAZEBO_VERSION_HEADER "Ignition Gazebo, version ${PROJECT_VERSION_FULL}\nCopyright (C) 2018 Open Source Robotics Foundation.\nReleased under the Apache 2.0 License.\n\n" +#define IGNITION_GAZEBO_VERSION_HEADER "Gazebo Sim, version ${PROJECT_VERSION_FULL}\nCopyright (C) 2018 Open Source Robotics Foundation.\nReleased under the Apache 2.0 License.\n\n" #define IGNITION_GAZEBO_GUI_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${IGN_DATA_INSTALL_DIR}/gui" #define IGNITION_GAZEBO_SYSTEM_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${IGN_DATA_INSTALL_DIR}/systems" @@ -24,3 +24,21 @@ #cmakedefine IGNITION_GAZEBO_BUILD_TYPE_PROFILE 1 #cmakedefine IGNITION_GAZEBO_BUILD_TYPE_DEBUG 1 #cmakedefine IGNITION_GAZEBO_BUILD_TYPE_RELEASE 1 + +namespace ignition +{ + namespace gazebo + { + } +} + +namespace gz +{ + using namespace ignition; + + namespace sim + { + using namespace gazebo; + using namespace ignition::gazebo; + } +} diff --git a/include/ignition/gazebo/detail/ComponentStorageBase.hh b/include/gz/sim/detail/ComponentStorageBase.hh similarity index 96% rename from include/ignition/gazebo/detail/ComponentStorageBase.hh rename to include/gz/sim/detail/ComponentStorageBase.hh index ca9e5e8960..c2b520d3cc 100644 --- a/include/ignition/gazebo/detail/ComponentStorageBase.hh +++ b/include/gz/sim/detail/ComponentStorageBase.hh @@ -14,15 +14,15 @@ * 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 #include #include -#include "ignition/gazebo/components/Component.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" +#include "gz/sim/components/Component.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Types.hh" namespace ignition { diff --git a/include/ignition/gazebo/detail/EntityComponentManager.hh b/include/gz/sim/detail/EntityComponentManager.hh similarity index 98% rename from include/ignition/gazebo/detail/EntityComponentManager.hh rename to include/gz/sim/detail/EntityComponentManager.hh index d08722ee80..9762052dee 100644 --- a/include/ignition/gazebo/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 @@ -25,9 +25,9 @@ #include #include -#include +#include -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/EntityComponentManager.hh" namespace ignition { @@ -62,7 +62,7 @@ namespace traits /// equality operator. /// If `DataType` doesn't have an equality operator defined, it will return /// false. -/// For doubles, `ignition::math::equal` will be used. +/// For doubles, `gz::math::equal` will be used. template auto CompareData = [](const DataType &_a, const DataType &_b) -> bool { diff --git a/include/ignition/gazebo/detail/View.hh b/include/gz/sim/detail/View.hh similarity index 95% rename from include/ignition/gazebo/detail/View.hh rename to include/gz/sim/detail/View.hh index 654a146291..f7daf8c11d 100644 --- a/include/ignition/gazebo/detail/View.hh +++ b/include/gz/sim/detail/View.hh @@ -14,17 +14,17 @@ * 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 #include #include -#include "ignition/gazebo/components/Component.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" +#include "gz/sim/components/Component.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Types.hh" namespace ignition { diff --git a/include/gz/sim/gui/Gui.hh b/include/gz/sim/gui/Gui.hh new file mode 100644 index 0000000000..aa682e372a --- /dev/null +++ b/include/gz/sim/gui/Gui.hh @@ -0,0 +1,114 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#ifndef GZ_GAZEBO_GUI_GUI_HH_ +#define GZ_GAZEBO_GUI_GUI_HH_ + +#include +#include +#include + +#include "gz/sim/config.hh" +#include "gz/sim/gui/Export.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace gui +{ + /// \brief Run GUI application + /// \param[in] _argc Number of command line arguments (Used when running + /// without ign-tools. Set to 1 if using ign-tools). Note: The object + /// referenced by this variable must continue to exist for the lifetime of the + /// application. + /// \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. + IGNITION_GAZEBO_GUI_VISIBLE int runGui(int &_argc, char **_argv, + const char *_guiConfig); + + /// \brief Run GUI application + /// \param[in] _argc Number of command line arguments (Used when running + /// without ign-tools. Set to 1 if using ign-tools). Note: The object + /// referenced by this variable must continue to exist for the lifetime of the + /// application. + /// \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. + /// \param[in] _sdfFile The world file path passed as a command line argument. + /// If set, QuickStart Dialog will not be shown. + /// \param[in] _waitGui Flag indicating whether the server waits until + /// it receives a world path from GUI. + IGNITION_GAZEBO_GUI_VISIBLE int runGui(int &_argc, char **_argv, + const char *_guiConfig, const char *_sdfFile, int _waitGui); + + /// \brief Create a Gazebo GUI application + /// \param[in] _argc Number of command line arguments (Used when running + /// without ign-tools. Set to 1 if using ign-tools). Note: The object + /// referenced by this variable must continue to exist for the lifetime of the + /// application. + /// \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. + /// \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. + /// \param[in] _loadPluginsFromSdf If true, plugins specified in the world + /// SDFormat file will get loaded. + IGNITION_GAZEBO_GUI_VISIBLE + std::unique_ptr createGui( + int &_argc, char **_argv, const char *_guiConfig, + const char *_defaultGuiConfig = nullptr, bool _loadPluginsFromSdf = true); + + /// \brief Create a Gazebo GUI application + /// \param[in] _argc Number of command line arguments (Used when running + /// without ign-tools. Set to 1 if using ign-tools). Note: The object + /// referenced by this variable must continue to exist for the lifetime of the + /// application. + /// \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. + /// \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. + /// \param[in] _loadPluginsFromSdf If true, plugins specified in the world + /// SDFormat file will get loaded. + /// \param[in] _sdfFile SDF world file, or nullptr if not set. + /// \param[in] _waitGui True if the server is waiting for the GUI to decide on + /// a starting world. + IGNITION_GAZEBO_GUI_VISIBLE + std::unique_ptr createGui( + int &_argc, char **_argv, const char *_guiConfig, + const char *_defaultGuiConfig, bool _loadPluginsFromSdf, + const char *_sdfFile, int _waitGui); +} // namespace gui +} // namespace IGNITION_GAZEBO_VERSION_NAMESPACE +} // namespace gazebo +} // namespace ignition + +#endif diff --git a/include/gz/sim/gui/GuiEvents.hh b/include/gz/sim/gui/GuiEvents.hh new file mode 100644 index 0000000000..b70b33508f --- /dev/null +++ b/include/gz/sim/gui/GuiEvents.hh @@ -0,0 +1,219 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_GUI_GUIEVENTS_HH_ +#define GZ_GAZEBO_GUI_GUIEVENTS_HH_ + +#include +#include +#include +#include +#include +#include "gz/sim/Entity.hh" +#include "gz/sim/config.hh" + +namespace ignition +{ +namespace gazebo +{ +namespace gui { +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +/// \brief Namespace for all events. Refer to the EventManager class for +/// more information about events. +namespace events +{ + /// \brief The class for sending and receiving custom snap value events. + class SnapIntervals : public QEvent + { + /// \brief Constructor + /// \param[in] _xyz XYZ snapping values. + /// \param[in] _rpy RPY snapping values. + /// \param[in] _scale Scale snapping values. + public: SnapIntervals( + const math::Vector3d &_xyz, + const math::Vector3d &_rpy, + const math::Vector3d &_scale) + : QEvent(kType), xyz(_xyz), rpy(_rpy), scale(_scale) + { + } + + /// \brief Get the XYZ snapping values. + /// \return The XYZ snapping values. + public: math::Vector3d XYZ() const + { + return this->xyz; + } + + /// \brief Get the RPY snapping values. + /// \return The RPY snapping values. + public: math::Vector3d RPY() const + { + return this->rpy; + } + + /// \brief Get the scale snapping values. + /// \return The scale snapping values. + public: math::Vector3d Scale() const + { + return this->scale; + } + + /// \brief The QEvent representing a snap event occurrence. + static const QEvent::Type kType = QEvent::Type(QEvent::User); + + /// \brief XYZ snapping values in meters, these values must be positive. + private: math::Vector3d xyz; + + /// \brief RPY snapping values in degrees, these values must be positive. + private: math::Vector3d rpy; + + /// \brief Scale snapping values - a multiplier of the current size, + /// these values must be positive. + private: math::Vector3d scale; + }; + + /// \brief Event that notifies when new entities have been selected. + class EntitiesSelected : public QEvent + { + /// \brief Constructor + /// \param[in] _entities All the selected entities + /// \param[in] _fromUser True if the event was directly generated by the + /// user, false in case it's been propagated through a different mechanism. + public: explicit EntitiesSelected( + const std::vector &_entities, // NOLINT + bool _fromUser = false) + : QEvent(kType), entities(_entities), fromUser(_fromUser) + { + } + + /// \brief Get the data sent with the event. + /// \return The entities being selected. + public: std::vector Data() const + { + return this->entities; + } + + /// \brief Get whether the event was generated by the user. + /// \return True for the user. + public: bool FromUser() const + { + return this->fromUser; + } + + /// \brief Unique type for this event. + static const QEvent::Type kType = QEvent::Type(QEvent::User + 1); + + /// \brief The selected entities. + private: std::vector entities; + + /// \brief Whether the event was generated by the user, + private: bool fromUser{false}; + }; + + /// \brief Event that notifies when all entities have been deselected. + class DeselectAllEntities : public QEvent + { + /// \brief Constructor + /// \param[in] _fromUser True if the event was directly generated by the + /// user, false in case it's been propagated through a different mechanism. + public: explicit DeselectAllEntities(bool _fromUser = false) + : QEvent(kType), fromUser(_fromUser) + { + } + + /// \brief Get whether the event was generated by the user. + /// \return True for the user. + public: bool FromUser() const + { + return this->fromUser; + } + + /// \brief Unique type for this event. + static const QEvent::Type kType = QEvent::Type(QEvent::User + 2); + + /// \brief Whether the event was generated by the user, + private: bool fromUser{false}; + }; + + /// \brief Event called in the render thread of a 3D scene. + /// It's safe to make rendering calls in this event's callback. + class Render : public QEvent + { + public: Render() + : QEvent(kType) + { + } + /// \brief Unique type for this event. + static const QEvent::Type kType = QEvent::Type(QEvent::User + 3); + }; + + /// \brief Event called to spawn a preview model. + /// Used by plugins that spawn models. + class SpawnPreviewModel : public QEvent + { + /// \brief Constructor + /// \param[in] _modelSdfString The model's SDF file as a string. + public: explicit SpawnPreviewModel(std::string &_modelSdfString) + : QEvent(kType), modelSdfString(_modelSdfString) + { + } + + /// \brief Unique type for this event. + static const QEvent::Type kType = QEvent::Type(QEvent::User + 4); + + /// \brief Get the sdf string of the model. + /// \return The model sdf string + public: std::string ModelSdfString() const + { + return this->modelSdfString; + } + + /// \brief The sdf string of the model to be previewed. + std::string modelSdfString; + }; + + /// \brief Event called to spawn a preview resource, which takes the path + /// to the SDF file. Used by plugins that spawn resources. + class SpawnPreviewPath : public QEvent + { + /// \brief Constructor + /// \param[in] _filePath The path to an SDF file. + public: explicit SpawnPreviewPath(const std::string &_filePath) + : QEvent(kType), filePath(_filePath) + { + } + + /// \brief Unique type for this event. + static const QEvent::Type kType = QEvent::Type(QEvent::User + 5); + + /// \brief Get the path of the SDF file. + /// \return The file path. + public: std::string FilePath() const + { + return this->filePath; + } + + /// \brief The path of SDF file to be previewed. + std::string filePath; + }; +} // namespace events +} +} // namespace gui +} // namespace gazebo +} // namespace ignition + +#endif // GZ_GAZEBO_GUI_GUIEVENTS_HH_ diff --git a/include/gz/sim/gui/GuiRunner.hh b/include/gz/sim/gui/GuiRunner.hh new file mode 100644 index 0000000000..2328bc614c --- /dev/null +++ b/include/gz/sim/gui/GuiRunner.hh @@ -0,0 +1,91 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_GUI_GUIRUNNER_HH_ +#define GZ_GAZEBO_GUI_GUIRUNNER_HH_ + +#include + +#include +#include +#include +#include + +#include + +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/gui/Export.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +/// \brief Responsible for running GUI systems as new states are received from +/// the backend. +class IGNITION_GAZEBO_GUI_VISIBLE GuiRunner : public QObject +{ + Q_OBJECT + + /// \brief Constructor + /// \param[in] _worldName World name. + public: explicit GuiRunner(const std::string &_worldName); + + /// \brief Destructor + public: ~GuiRunner() override; + + /// \brief Callback when a plugin has been added. + /// This function has no effect and is left here for ABI compatibility. + /// \param[in] _objectName Plugin's object name. + public slots: void OnPluginAdded(const QString &_objectName); + + /// \brief Make a new state request to the server. + public slots: void RequestState(); + + /// \brief Callback for the async state service. + /// \param[in] _res Response containing new state. + private: void OnStateAsyncService(const msgs::SerializedStepMap &_res); + + /// \brief Callback when a new state is received from the server. Actual + /// updating of the ECM is delegated to OnStateQt + /// \param[in] _msg New state message. + private: void OnState(const msgs::SerializedStepMap &_msg); + + /// \brief Called by the Qt thread to update the ECM with new state + /// \param[in] _msg New state message. + private: Q_INVOKABLE void OnStateQt(const msgs::SerializedStepMap &_msg); + + /// \brief Update the plugins. + /// \todo(anyone) Move to GuiRunner::Implementation when porting to v5 + private: Q_INVOKABLE void UpdatePlugins(); + + /// \brief Entity-component manager. + private: ignition::gazebo::EntityComponentManager ecm; + + /// \brief Transport node. + private: transport::Node node; + + /// \brief Topic to request state + private: std::string stateTopic; + + /// \brief Latest update info + private: UpdateInfo updateInfo; +}; +} +} +} +#endif diff --git a/include/gz/sim/gui/GuiSystem.hh b/include/gz/sim/gui/GuiSystem.hh new file mode 100644 index 0000000000..a1d46c6be9 --- /dev/null +++ b/include/gz/sim/gui/GuiSystem.hh @@ -0,0 +1,65 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_GUI_GUISYSTEM_HH_ +#define GZ_GAZEBO_GUI_GUISYSTEM_HH_ + +#include + +#include +#include +#include +#include + +#include + +namespace ignition +{ +namespace gazebo +{ + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + /// \brief Base class for a GUI System. + /// + /// A System operates on Entities that have certain Components. A System + /// will only operate on an Entity if it has all of the required + /// Components. + /// + /// GUI systems are different from `gz::sim::System`s because they + /// don't run in the same process as the physics. Instead, they run in a + /// separate process that is stepped by updates coming through the network + class IGNITION_GAZEBO_VISIBLE GuiSystem : public gz::gui::Plugin + { + Q_OBJECT + + /// \brief Update callback called every time the system is stepped. + /// This is called at an Ignition transport thread, so any interaction + /// with Qt should be done through signals and slots. + /// \param[in] _info Current simulation information, such as time. + /// \param[in] _ecm Mutable reference to the ECM, so the system can read + /// and write entities and their components. + public: virtual void Update(const UpdateInfo &_info, + EntityComponentManager &_ecm) + { + // This will avoid many doxygen warnings + (void)_info; + (void)_ecm; + } + }; +} +} +} +#endif diff --git a/include/gz/sim/gui/TmpIface.hh b/include/gz/sim/gui/TmpIface.hh new file mode 100644 index 0000000000..8709d3036d --- /dev/null +++ b/include/gz/sim/gui/TmpIface.hh @@ -0,0 +1,83 @@ +/* + * Copyright (C) 2018 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_GUI_TMPIFACE_HH_ +#define GZ_GAZEBO_GUI_TMPIFACE_HH_ + +#ifndef Q_MOC_RUN + #include +#endif + +#include +#include + +#include "gz/sim/Export.hh" + +namespace ignition +{ + namespace gazebo + { + /// \brief Temporary place to prototype transport interfaces while it's not + /// clear where they will live. + /// + /// Move API from here to their appropriate locations once that's known. + /// + /// This class should be removed before releasing! + class IGNITION_GAZEBO_VISIBLE TmpIface : public QObject + { + Q_OBJECT + + /// \brief Constructor: advertize services and topics + public: TmpIface(); + + /// \brief Destructor + public: ~TmpIface() override = default; + + /// \brief Callback when user asks to start a new world. + /// This is the client-side logic which requests the server_control + /// service. + public slots: void OnNewWorld(); + + /// \brief Callback when user asks to load a world file. + /// This is the client-side logic which requests the server_control + /// service. + /// \param[in] _path Path to world file. + public slots: void OnLoadWorld(const QString &_path); + + /// \brief Callback when user asks to save a world file providing a path. + /// This is the client-side logic which requests the server_control + /// service. + /// \param[in] _path Path to world file. + public slots: void OnSaveWorldAs(const QString &_path); + + /// \brief This function does nothing and is kept only for retaining ABI + /// compatibility. /server_control service handling was moved to + /// ServerPrivate. + /// \param[in] _req Request + /// \param[out] _res Response + /// \return False. + private: bool IGN_DEPRECATED(3) OnServerControl( + const msgs::ServerControl &_req, msgs::Boolean &_res); + + /// \brief Communication node + private: transport::Node node; + + /// \brief Publisher + private: transport::Node::Publisher worldStatsPub; + }; + } +} +#endif diff --git a/include/gz/sim/physics/Events.hh b/include/gz/sim/physics/Events.hh new file mode 100644 index 0000000000..c40a3ed2e2 --- /dev/null +++ b/include/gz/sim/physics/Events.hh @@ -0,0 +1,65 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_PHYSICS_EVENTS_HH_ +#define GZ_GAZEBO_PHYSICS_EVENTS_HH_ + +#include + +#include + +#include + +#include "gz/sim/config.hh" +#include "gz/sim/Entity.hh" + +#include + +namespace ignition +{ + namespace gazebo + { + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + + namespace events + { + using Policy = physics::FeaturePolicy3d; + + /// \brief This event is called when the physics engine needs to collect + /// what customizations it should do to the surface of a contact point. It + /// is called during the Update phase after collision checking has been + /// finished and before the physics update has happened. The event + /// subscribers are expected to change the `params` argument. + using CollectContactSurfaceProperties = gz::common::EventT< + void( + const Entity& /* collision1 */, + const Entity& /* collision2 */, + const math::Vector3d & /* point */, + const std::optional /* force */, + const std::optional /* normal */, + const std::optional /* depth */, + const size_t /* numContactsOnCollision */, + physics::SetContactPropertiesCallbackFeature:: + ContactSurfaceParams& /* params */ + ), + struct CollectContactSurfacePropertiesTag>; + } + } // namespace events + } // namespace gazebo +} // namespace ignition + +#endif // GZ_GAZEBO_PHYSICS_EVENTS_HH_ diff --git a/include/ignition/gazebo/playback_server.config b/include/gz/sim/playback_server.config similarity index 72% rename from include/ignition/gazebo/playback_server.config rename to include/gz/sim/playback_server.config index 2551fda3ea..17ac79c8d9 100644 --- a/include/ignition/gazebo/playback_server.config +++ b/include/gz/sim/playback_server.config @@ -3,12 +3,12 @@ + name="sim::systems::UserCommands"> + name="sim::systems::SceneBroadcaster"> diff --git a/include/gz/sim/rendering/Events.hh b/include/gz/sim/rendering/Events.hh new file mode 100644 index 0000000000..359ee6c338 --- /dev/null +++ b/include/gz/sim/rendering/Events.hh @@ -0,0 +1,61 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_RENDERING_EVENTS_HH_ +#define GZ_GAZEBO_RENDERING_EVENTS_HH_ + + +#include + +#include "gz/sim/config.hh" + +namespace ignition +{ + namespace gazebo + { + // Inline bracket to help doxygen filtering. + inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + /// \brief Namespace for all events. Refer to the EventManager class for + /// more information about events. + namespace events + { + /// \brief The render event is emitted before rendering updates. + /// The event is emitted in the rendering thread so rendering + /// calls can ben make in this event callback + /// + /// For example: + /// \code + /// eventManager.Emit(); + /// \endcode + using PreRender = gz::common::EventT; + + /// \brief The render event is emitted after rendering updates. + /// The event is emitted in the rendering thread so rendering + /// calls can ben make in this event callback + /// + /// For example: + /// \code + /// eventManager.Emit(); + /// \endcode + using PostRender = gz::common::EventT; + } + } // namespace events + } // namespace gazebo +} // namespace ignition + +#endif // GZ_GAZEBO_RENDEREVENTS_HH_ diff --git a/include/gz/sim/rendering/MarkerManager.hh b/include/gz/sim/rendering/MarkerManager.hh new file mode 100644 index 0000000000..5139505772 --- /dev/null +++ b/include/gz/sim/rendering/MarkerManager.hh @@ -0,0 +1,77 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_MARKERMANAGER_HH_ +#define GZ_GAZEBO_MARKERMANAGER_HH_ + +#include +#include + +#include + +#include "gz/rendering/RenderTypes.hh" + +namespace ignition +{ +namespace gazebo +{ +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +// Forward declare private data class. +class MarkerManagerPrivate; + +/// \brief Creates, deletes, and maintains marker visuals. Only the +/// Scene class should instantiate and use this class. +class IGNITION_GAZEBO_RENDERING_VISIBLE MarkerManager +{ + /// \brief Constructor + public: MarkerManager(); + + /// \brief Destructor + public: virtual ~MarkerManager(); + + /// \brief Set the simulation time. + /// \param[in] _time The provided time. + public: void SetSimTime(const std::chrono::steady_clock::duration &_time); + + /// \brief Set the scene to manage + /// \param[in] _scene Scene pointer. + public: void SetScene(rendering::ScenePtr _scene); + + /// \brief Get the scene + /// \return Pointer to scene + public: rendering::ScenePtr Scene() const; + + /// \brief Update MarkerManager + public: void Update(); + + /// \brief Initialize the marker manager. + /// \param[in] _scene Reference to the scene. + /// \return True on success + public: bool Init(const gz::rendering::ScenePtr &_scene); + + /// \brief Set the marker service topic name. + /// \param[in] _name Name of service + public: void SetTopic(const std::string &_name); + + /// \internal + /// \brief Private data pointer + private: std::unique_ptr dataPtr; +}; +} + +} +} +#endif diff --git a/include/gz/sim/rendering/RenderUtil.hh b/include/gz/sim/rendering/RenderUtil.hh new file mode 100644 index 0000000000..2dd575d3a1 --- /dev/null +++ b/include/gz/sim/rendering/RenderUtil.hh @@ -0,0 +1,167 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_GAZEBO_RENDERUTIL_HH_ +#define GZ_GAZEBO_RENDERUTIL_HH_ + +#include +#include +#include + +#include + +#include +#include +#include + +#include "gz/sim/rendering/SceneManager.hh" +#include "gz/sim/rendering/MarkerManager.hh" + + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + // forward declaration + class RenderUtilPrivate; + + /// \class RenderUtil RenderUtil.hh ignition/gazebo/gui/plugins/RenderUtil.hh + class IGNITION_GAZEBO_RENDERING_VISIBLE RenderUtil + { + /// \brief Constructor + public: explicit RenderUtil(); + + /// \brief Destructor + public: ~RenderUtil(); + + /// \brief Initialize the renderer. Must be called in the rendering thread. + public: void Init(); + + /// \brief Count of pending sensors. Must be called in the rendering thread. + /// \return Number of sensors to be added on the next `Update` call + /// + /// In the case that RenderUtil has not been initialized, this method + /// will return -1. + public: int PendingSensors() const; + + /// \brief Main update function. Must be called in the rendering thread. + public: void Update(); + + /// \brief Get a pointer to the scene + /// \return Pointer to the scene + public: rendering::ScenePtr Scene() const; + + /// \brief Helper PostUpdate function for updating the scene + public: void UpdateFromECM(const UpdateInfo &_info, + const EntityComponentManager &_ecm); + + /// \brief Set the rendering engine to use + /// \param[in] _engineName Name of the rendering engine. + public: void SetEngineName(const std::string &_engineName); + + /// \brief Get the name of the rendering engine used + /// \return Name of the rendering engine + public: std::string EngineName() const; + + /// \brief Set the scene to use + /// \param[in] _sceneName Name of the engine. + public: void SetSceneName(const std::string &_sceneName); + + /// \brief Get the name of the rendering scene used + /// \return Name of the rendering scene. + public: std::string SceneName() const; + + /// \brief Set background color of render window. This will override + /// other sources, such as from SDF. + /// \param[in] _color Color of render window background + public: void SetBackgroundColor(const math::Color &_color); + + /// \brief Set ambient light of render window. This will override + /// other sources, such as from SDF. + /// \param[in] _ambient Color of ambient light + public: void SetAmbientLight(const math::Color &_ambient); + + /// \brief Show grid view in the scene + public: void ShowGrid(); + + /// \brief Set whether to use the current GL context + /// \param[in] _enable True to use the current GL context + public: void SetUseCurrentGLContext(bool _enable); + + /// \brief Set whether to create rendering sensors + /// \param[in] _enable True to create rendering sensors + /// \param[in] _createSensorCb Callback function for creating the sensors + /// The callback function args are: sensor sdf, and parent name, and + /// returns the name of the rendering sensor created. + public: void SetEnableSensors(bool _enable, std::function< + std::string(const sdf::Sensor &, const std::string &)> + _createSensorCb = {}); + + /// \brief View collisions of specified entity which are shown in orange + /// \param[in] _entity Entity to view collisions + public: void ViewCollisions(const Entity &_entity); + + /// \brief Get the scene manager + /// Returns reference to the scene manager. + public: class SceneManager &SceneManager(); + + /// \brief Get the marker manager + /// Returns reference to the marker manager. + public: class MarkerManager &MarkerManager(); + + /// \brief Get simulation time that the current rendering state corresponds + /// to + /// \returns Simulation time. + public: std::chrono::steady_clock::duration SimTime() const; + + /// \brief Set the entity being selected + /// \param[in] _node Node representing the selected entity + /// TODO(anyone) Make const ref when merging forward + // NOLINTNEXTLINE + public: void SetSelectedEntity(rendering::NodePtr _node); + + /// \brief Get the entity for a given node. + /// \param[in] _node Node to get the entity for. + /// \return The entity for that node, or `kNullEntity` for no entity. + /// \deprecated Use `gz::rendering::Visual::UserData` instead. + public: Entity IGN_DEPRECATED(3) + EntityFromNode(const rendering::NodePtr &_node); + + /// \brief Get the entity being selected. This will only return the + /// last entity selected. + /// TODO(anyone) Deprecate in favour of SelectedEntities + public: rendering::NodePtr SelectedEntity() const; + + /// \brief Get the entities currently selected, in order of selection. + /// \return Vector of currently selected entities + public: std::vector SelectedEntities() const; + + /// \brief Clears the set of selected entities and lowlights all of them. + public: void DeselectAllEntities(); + + /// \brief Set whether the transform controls are currently being dragged. + /// \param[in] _active True if active. + public: void SetTransformActive(bool _active); + + /// \brief Private data pointer. + private: std::unique_ptr dataPtr; + }; +} +} +} +#endif diff --git a/include/gz/sim/rendering/SceneManager.hh b/include/gz/sim/rendering/SceneManager.hh new file mode 100644 index 0000000000..b133ca0b51 --- /dev/null +++ b/include/gz/sim/rendering/SceneManager.hh @@ -0,0 +1,212 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#ifndef GZ_GAZEBO_SCENEMANAGER_HH_ +#define GZ_GAZEBO_SCENEMANAGER_HH_ + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + // Forward declaration + class SceneManagerPrivate; + + /// \brief Scene manager class for loading and managing objects in the scene + class IGNITION_GAZEBO_RENDERING_VISIBLE SceneManager + { + /// \brief Constructor + public: SceneManager(); + + /// \brief Destructor + public: ~SceneManager(); + + /// \brief Set the scene to manage + /// \param[in] _scene Scene pointer. + public: void SetScene(rendering::ScenePtr _scene); + + /// \brief Get the scene + /// \return Pointer to scene + public: rendering::ScenePtr Scene() const; + + /// \brief Set the world's ID. + /// \param[in] _id World ID. + public: void SetWorldId(Entity _id); + + /// \brief Get the world's ID. + /// \return World ID + public: Entity WorldId() const; + + /// \brief Create a model + /// \param[in] _id Unique model id + /// \param[in] _model Model sdf dom + /// \param[in] _parentId Parent id + /// \return Model visual created from the sdf dom + public: rendering::VisualPtr CreateModel(Entity _id, + const sdf::Model &_model, Entity _parentId = 0); + + /// \brief Create a link + /// \param[in] _id Unique link id + /// \param[in] _link Link sdf dom + /// \param[in] _parentId Parent id + /// \return Link visual created from the sdf dom + public: rendering::VisualPtr CreateLink(Entity _id, + const sdf::Link &_link, Entity _parentId = 0); + + /// \brief Create a visual + /// \param[in] _id Unique visual id + /// \param[in] _visual Visual sdf dom + /// \param[in] _parentId Parent id + /// \return Visual object created from the sdf dom + public: rendering::VisualPtr CreateVisual(Entity _id, + const sdf::Visual &_visual, Entity _parentId = 0); + + /// \brief Create a collision visual + /// \param[in] _id Unique visual id + /// \param[in] _collision Collision sdf dom + /// \param[in] _parentId Parent id + /// \return Visual (collision) object created from the sdf dom + public: rendering::VisualPtr CreateCollision(Entity _id, + const sdf::Collision &_collision, Entity _parentId = 0); + + /// \brief Retrieve visual + /// \param[in] _id Unique visual (entity) id + /// \return Pointer to requested visual + public: rendering::VisualPtr VisualById(Entity _id); + + /// \brief Create an actor + /// \param[in] _id Unique actor id + /// \param[in] _actor Actor sdf dom + /// \param[in] _parentId Parent id + /// \return Actor object created from the sdf dom + public: rendering::VisualPtr CreateActor(Entity _id, + const sdf::Actor &_actor, Entity _parentId = 0); + + /// \brief Create a light + /// \param[in] _id Unique light id + /// \param[in] _light Light sdf dom + /// \param[in] _parentId Parent id + /// \return Light object created from the sdf dom + public: rendering::LightPtr CreateLight(Entity _id, + const sdf::Light &_light, Entity _parentId); + + /// \brief Ignition sensors is the one responsible for adding sensors + /// to the scene. Here we just keep track of it and make sure it has + /// the correct parent. + /// \param[in] _gazeboId Entity in Gazebo + /// \param[in] _sensorName Name of sensor node in Ignition Rendering. + /// \param[in] _parentGazeboId Parent Id on Gazebo. + /// \return True if sensor is successfully handled + public: bool AddSensor(Entity _gazeboId, const std::string &_sensorName, + Entity _parentGazeboId = 0); + + /// \brief Check if entity exists + /// \param[in] _id Unique entity id + /// \return true if exists, false otherwise + public: bool HasEntity(Entity _id) const; + + /// \brief Get a rendering node given an entity id + /// \param[in] _id Entity's unique id + /// \return Pointer to requested entity's node + public: rendering::NodePtr NodeById(Entity _id) const; + + /// \brief Get a rendering mesh given an id + /// \param[in] _id Actor entity's unique id + /// \return Pointer to requested entity's mesh + public: rendering::MeshPtr ActorMeshById(Entity _id) const; + + /// \brief Get the animation of actor mesh given an id + /// \param[in] _id Entity's unique id + /// \param[in] _time Timepoint for the animation + /// \return Map from the skeleton node name to transforms + public: std::map ActorMeshAnimationAt( + Entity _id, std::chrono::steady_clock::duration _time) const; + + /// \brief Remove an entity by id + /// \param[in] _id Entity's unique id + public: void RemoveEntity(Entity _id); + + /// \brief Get the entity for a given node. + /// \param[in] _node Node to get the entity for. + /// \return The entity for that node, or `kNullEntity` for no entity. + /// \todo(anyone) Deprecate in favour of + /// `gz::rendering::Node::UserData` once that's available. + public: Entity EntityFromNode(const rendering::NodePtr &_node) const; + + /// \brief Load a geometry + /// \param[in] _geom Geometry sdf dom + /// \param[out] _scale Geometry scale that will be set based on sdf + /// \param[out] _localPose Additional local pose to be applied after the + /// visual's pose + /// \return Geometry object loaded from the sdf dom + private: rendering::GeometryPtr LoadGeometry(const sdf::Geometry &_geom, + math::Vector3d &_scale, math::Pose3d &_localPose); + + /// \brief Load a material + /// \param[in] _material Material sdf dom + /// \return Material object loaded from the sdf dom + private: rendering::MaterialPtr LoadMaterial( + const sdf::Material &_material); + + /// \brief Get the top level visual for the given visual, which + /// is the ancestor which is a direct child to the root visual. + /// Usually, this will be a model or a light. + /// \param[in] _visual Child visual + /// \return Top level visual containining this visual + /// TODO(anyone) Make it const ref when merging forward + public: rendering::VisualPtr TopLevelVisual( + // NOLINTNEXTLINE + rendering::VisualPtr _visual) const; + + /// \brief Get the top level node for the given node, which + /// is the ancestor which is a direct child to the root visual. + /// Usually, this will be a model or a light. + /// \param[in] _node Child node + /// \return Top level node containining this node + public: rendering::NodePtr TopLevelNode( + const rendering::NodePtr &_node) const; + + /// \internal + /// \brief Pointer to private data class + private: std::unique_ptr dataPtr; + }; +} +} +} + +#endif diff --git a/include/ignition/gazebo/server.config b/include/gz/sim/server.config similarity index 71% rename from include/ignition/gazebo/server.config rename to include/gz/sim/server.config index 5de18a66fc..3a26dac6d6 100644 --- a/include/ignition/gazebo/server.config +++ b/include/gz/sim/server.config @@ -3,17 +3,17 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/include/ignition/CMakeLists.txt b/include/ignition/CMakeLists.txt deleted file mode 100644 index 024bcc273f..0000000000 --- a/include/ignition/CMakeLists.txt +++ /dev/null @@ -1 +0,0 @@ -add_subdirectory(gazebo) diff --git a/include/ignition/gazebo.hh b/include/ignition/gazebo.hh new file mode 100644 index 0000000000..38872bf922 --- /dev/null +++ b/include/ignition/gazebo.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/Conversions.hh b/include/ignition/gazebo/Conversions.hh index 13f079bff9..0f5add3d6c 100644 --- a/include/ignition/gazebo/Conversions.hh +++ b/include/ignition/gazebo/Conversions.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,653 +13,7 @@ * See the License for the specific language governing permissions and * 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 -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - /// \brief Helper function that sets a mutable msgs::SensorNoise object - /// to the values contained in a sdf::Noise object. - /// \param[out] _msg SensorNoise message to set. - /// \param[in] _sdf SDF Noise object. - void IGNITION_GAZEBO_VISIBLE - set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf); - - /// \brief Helper function that sets a mutable msgs::WorldStatistics object - /// to the values contained in a gazebo::UpdateInfo object. - /// \param[out] _msg WorldStatistics message to set. - /// \param[in] _in UpdateInfo object. - void IGNITION_GAZEBO_VISIBLE - set(msgs::WorldStatistics *_msg, const UpdateInfo &_in); - - /// \brief Helper function that sets a mutable msgs::Time object - /// to the values contained in a std::chrono::steady_clock::duration - /// object. - /// \param[out] _msg Time message to set. - /// \param[in] _in Chrono duration object. - void IGNITION_GAZEBO_VISIBLE - set(msgs::Time *_msg, const std::chrono::steady_clock::duration &_in); - - /// \brief Generic conversion from an SDF geometry to another type. - /// \param[in] _in SDF geometry. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const sdf::Geometry &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from an SDF geometry to a geometry - /// message. - /// \param[in] _in SDF geometry. - /// \return Geometry message. - template<> - msgs::Geometry convert(const sdf::Geometry &_in); - - /// \brief Generic conversion from a msgs Pose to another type. - /// \param[in] _in msgs Pose - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const msgs::Pose &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion for msgs Pose to math Pose - /// \param[in] _in msgs Pose - /// \return math Pose. - template<> - math::Pose3d convert(const msgs::Pose &_in); - - /// \brief Generic conversion from a geometry message to another type. - /// \param[in] _in Geometry message. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const msgs::Geometry &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from a geometry message to a geometry - /// SDF object. - /// \param[in] _in Geometry message. - /// \return SDF geometry. - template<> - sdf::Geometry convert(const msgs::Geometry &_in); - - /// \brief Generic conversion from an SDF material to another type. - /// \param[in] _in SDF material. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const sdf::Material &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from an SDF material to a material - /// message. - /// \param[in] _in SDF material. - /// \return Material message. - template<> - msgs::Material convert(const sdf::Material &_in); - - /// \brief Generic conversion from a material message to another type. - /// \param[in] _in Material message. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const msgs::Material &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from a material message to a material - /// SDF object. - /// \param[in] _in Material message. - /// \return SDF material. - template<> - sdf::Material convert(const msgs::Material &_in); - - /// \brief Generic conversion from an SDF actor to another type. - /// \param[in] _in SDF actor. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const sdf::Actor &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from an SDF actor to an actor - /// message. - /// \param[in] _in SDF actor. - /// \return Actor message. - template<> - msgs::Actor convert(const sdf::Actor &_in); - - /// \brief Generic conversion from an actor message to another type. - /// \param[in] _in Actor message. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const msgs::Actor& _in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from an actor message to an actor - /// SDF object. - /// \param[in] _in Actor message. - /// \return Actor SDF object. - template<> - sdf::Actor convert(const msgs::Actor &_in); - - /// \brief Generic conversion from an SDF light to another type. - /// \param[in] _in SDF light. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const sdf::Light &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from an SDF light to a light - /// message. - /// \param[in] _in SDF light. - /// \return Light message. - template<> - msgs::Light convert(const sdf::Light &_in); - - - /// \brief Generic conversion from a light message to another type. - /// \param[in] _in Light message. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const msgs::Light& _in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from a light message to a light - /// SDF object. - /// \param[in] _in Light message. - /// \return Light SDF object. - template<> - sdf::Light convert(const msgs::Light &_in); - - /// \brief Generic conversion from an SDF gui to another type. - /// \param[in] _in SDF gui. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const sdf::Gui &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from an SDF gui to a gui message. - /// \param[in] _in SDF gui. - /// \return Gui message. - template<> - msgs::GUI convert(const sdf::Gui &_in); - - /// \brief Generic conversion from a steady clock duration to another type. - /// \param[in] _in Steady clock duration. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const std::chrono::steady_clock::duration &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from a steady clock duration to a time - /// message. - /// \param[in] _in Steady clock duration. - /// \return Ignition time message. - template<> - msgs::Time convert(const std::chrono::steady_clock::duration &_in); - - /// \brief Generic conversion from a time message to another type. - /// \param[in] _in Time message. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const msgs::Time &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from a time message to a steady clock - /// duration. - /// \param[in] _in Time message. - /// \return Steady clock duration. - template<> - std::chrono::steady_clock::duration convert(const msgs::Time &_in); - - /// \brief Generic conversion from a math inertial to another type. - /// \param[in] _in Math inertial. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const math::Inertiald &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from a math inertial to an inertial - /// message. - /// \param[in] _in Math inertial. - /// \return Inertial message. - template<> - msgs::Inertial convert(const math::Inertiald &_in); - - /// \brief Generic conversion from an inertial message to another type. - /// \param[in] _in Inertial message. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const msgs::Inertial &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from an inertial message to an inertial - /// math object. - /// \param[in] _in Inertial message. - /// \return math inertial. - template<> - math::Inertiald convert(const msgs::Inertial &_in); - - /// \brief Generic conversion from an SDF joint axis to another type. - /// \param[in] _in SDF joint axis. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const sdf::JointAxis &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from an SDF joint axis to an axis - /// message. - /// \param[in] _in SDF joint axis. - /// \return Axis message. - template<> - msgs::Axis convert(const sdf::JointAxis &_in); - - /// \brief Generic conversion from an axis message to another type. - /// \param[in] _in Axis message. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const msgs::Axis &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from an axis message to a joint axis - /// SDF object. - /// \param[in] _in Axis message. - /// \return SDF joint axis. - template<> - sdf::JointAxis convert(const msgs::Axis &_in); - - /// \brief Generic conversion from an SDF scene to another type. - /// \param[in] _in SDF scene. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const sdf::Scene &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from an SDF scene to a scene message - /// \param[in] _in SDF scene. - /// \return Scene message. - template<> - msgs::Scene convert(const sdf::Scene &_in); - - /// \brief Generic conversion from a scene message to another type. - /// \param[in] _in Scene message. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const msgs::Scene &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from a scene message to a scene - /// SDF object. - /// \param[in] _in Scene message. - /// \return SDF scene. - template<> - sdf::Scene convert(const msgs::Scene &_in); - - /// \brief Generic conversion from an SDF atmosphere to another type. - /// \param[in] _in SDF atmosphere. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const sdf::Atmosphere &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from an SDF atmosphere to an atmosphere - /// message - /// \param[in] _in SDF atmosphere. - /// \return Atmosphere message. - template<> - msgs::Atmosphere convert(const sdf::Atmosphere &_in); - - /// \brief Generic conversion from an atmosphere message to another type. - /// \param[in] _in Atmosphere message. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const msgs::Atmosphere &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from an atmosphere message to an - /// atmosphere SDF object. - /// \param[in] _in Atmosphere message. - /// \return SDF scene. - template<> - sdf::Atmosphere convert(const msgs::Atmosphere &_in); - - - /// \brief Generic conversion from an SDF Physics to another type. - /// \param[in] _in SDF Physics. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const sdf::Physics &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from an SDF physics to a physics - /// message. - /// \param[in] _in SDF physics. - /// \return Physics message. - template<> - msgs::Physics convert(const sdf::Physics &_in); - - /// \brief Generic conversion from a physics message to another type. - /// \param[in] _in Physics message. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const msgs::Physics &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from a physics message to a physics - /// SDF object. - /// \param[in] _in Physics message. - /// \return SDF physics. - template<> - sdf::Physics convert(const msgs::Physics &_in); - - - /// \brief Generic conversion from an SDF Sensor to another type. - /// \param[in] _in SDF Sensor. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const sdf::Sensor &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from an SDF sensor to a sensor - /// message. - /// \param[in] _in SDF sensor. - /// \return Sensor message. - template<> - msgs::Sensor convert(const sdf::Sensor &_in); - - /// \brief Generic conversion from a sensor message to another type. - /// \param[in] _in Sensor message. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const msgs::Sensor &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from a sensor message to a sensor - /// SDF object. - /// \param[in] _in Sensor message. - /// \return SDF sensor. - template<> - sdf::Sensor convert(const msgs::Sensor &_in); - - /// \brief Generic conversion from a sensor noise message to another type. - /// \param[in] _in SensorNoise message. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const msgs::SensorNoise &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from a sensor noise message to a noise - /// SDF object. - /// \param[in] _in Sensor noise message. - /// \return SDF noise. - template<> - sdf::Noise convert(const msgs::SensorNoise &_in); - - /// \brief Generic conversion from a world statistics message to another - /// type. - /// \param[in] _in WorldStatistics message. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const msgs::WorldStatistics &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from a world statistics message to an - /// `ignition::gazebo::UpdateInfo` object. - /// \param[in] _in WorldStatistics message. - /// \return Update info. - template<> - UpdateInfo convert(const msgs::WorldStatistics &_in); - - /// \brief Generic conversion from update info to another type. - /// \param[in] _in Update info. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const UpdateInfo &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from update info to a world statistics - /// message. - /// \param[in] _in Update info. - /// \return World statistics message. - template<> - msgs::WorldStatistics convert(const UpdateInfo &_in); - - /// \brief Generic conversion from an SDF collision to another type. - /// \param[in] _in SDF collision. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const sdf::Collision &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from an SDF collision to a collision - /// message. - /// \param[in] _in SDF collision. - /// \return Collision message. - template<> - msgs::Collision convert(const sdf::Collision &_in); - - /// \brief Generic conversion from a collision message to another type. - /// \param[in] _in Collision message. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const msgs::Collision &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from a collision message to a collision - /// SDF object. - /// \param[in] _in Collision message. - /// \return SDF collision. - template<> - sdf::Collision convert(const msgs::Collision &_in); - - /// \brief Generic conversion from a string to another type. - /// \param[in] _in string. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const std::string &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from a string to an Entity_Type msg. - /// \param[in] _in string message. - /// \return Entity_Type. - template<> - msgs::Entity_Type convert(const std::string &_in); - - /// \brief Generic conversion from axis aligned box object to another type. - /// \param[in] _in Axis aligned box object. - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const math::AxisAlignedBox &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from a math axis aligned box object to an - /// axis aligned box message - /// \param[in] _in Axis aligned box message - /// \return Axis aligned box message. - template<> - msgs::AxisAlignedBox convert(const math::AxisAlignedBox &_in); - - /// \brief Generic conversion from an axis aligned box message to another - /// type. - /// \param[in] _in Axis aligned box message - /// \return Conversion result. - /// \tparam Out Output type. - template - Out convert(const msgs::AxisAlignedBox &_in) - { - (void)_in; - Out::ConversionNotImplemented; - } - - /// \brief Specialized conversion from an math axis aligned box message to - /// an axis aligned box object. - /// \param[in] _in Axis aligned box object - /// \return Axis aligned box object. - template<> - math::AxisAlignedBox convert(const msgs::AxisAlignedBox &_in); - } - } -} -#endif +#include +#include diff --git a/include/ignition/gazebo/Entity.hh b/include/ignition/gazebo/Entity.hh index 0db6365417..30af5993ff 100644 --- a/include/ignition/gazebo/Entity.hh +++ b/include/ignition/gazebo/Entity.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,53 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_ENTITY_HH_ -#define IGNITION_GAZEBO_ENTITY_HH_ + */ -#include +#include #include -#include - -/// \brief This library is part of the [Gazebo](https://gazebosim.org) project. -namespace ignition -{ - /// \brief Gazebo is a leading open source robotics simulator, that - /// provides high fidelity physics, rendering, and sensor simulation. - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // Adding component namespace information here because there is - // currently no one component class that seems like a good place to hold - // this documentation. - /// \brief Components represent data, such as position information. An - /// Entity usually has one or more associated components. - /// - /// The set of Components assigned to an Entity also act as a key. - /// Systems process Entities based on their key. For example, a physics - /// system may process only entities that have pose and inertia - /// components. - namespace components {} - - /// \brief An Entity identifies a single object in simulation such as - /// a model, link, or light. At its core, an Entity is just an identifier. - /// - /// An Entity usually has one or more associated Components. Components - /// represent data, such as position information. - /// - /// The set of Components assigned to an Entity also act as a key. - /// Systems process Entities based on their key. For example, a physics - /// system may process only entities that have pose and inertia - /// components. - /// - /// An Entity that needs to be identified and used by Systems should be - /// created through the EntityComponentManager. - using Entity = uint64_t; - - /// \brief Indicates a non-existant or invalid Entity. - const Entity kNullEntity{0}; - } - } -} -#endif diff --git a/include/ignition/gazebo/EntityComponentManager.hh b/include/ignition/gazebo/EntityComponentManager.hh index 167fe8e30a..5066b76d60 100644 --- a/include/ignition/gazebo/EntityComponentManager.hh +++ b/include/ignition/gazebo/EntityComponentManager.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,766 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_ENTITYCOMPONENTMANAGER_HH_ -#define IGNITION_GAZEBO_ENTITYCOMPONENTMANAGER_HH_ + */ -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" - -#include "ignition/gazebo/components/Component.hh" -#include "ignition/gazebo/detail/View.hh" - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // Forward declarations. - class IGNITION_GAZEBO_HIDDEN EntityComponentManagerPrivate; - - /// \brief Type alias for the graph that holds entities. - /// Each vertex is an entity, and the direction points from the parent to - /// its children. - /// All edges are positive booleans. - using EntityGraph = math::graph::DirectedGraph; - - /** \class EntityComponentManager EntityComponentManager.hh \ - * ignition/gazebo/EntityComponentManager.hh - **/ - /// \brief The EntityComponentManager constructs, deletes, and returns - /// components and entities. - /// A component can be of any class which inherits from - /// `components::BaseComponent`. - class IGNITION_GAZEBO_VISIBLE EntityComponentManager - { - /// \brief Constructor - public: EntityComponentManager(); - - /// \brief Destructor - public: ~EntityComponentManager(); - - /// \brief Creates a new Entity. - /// \return An id for the Entity, or kNullEntity on failure. - public: Entity CreateEntity(); - - /// \brief Get the number of entities on the server. - /// \return Entity count. - public: size_t EntityCount() const; - - /// \brief Request an entity deletion. This will insert the request - /// into a queue. The queue is processed toward the end of a simulation - /// update step. - /// - /// \details It is recommended that systems don't call this function - /// directly, and instead use the `gazebo::SdfEntityCreator` class to - /// remove entities. - /// - /// \param[in] _entity Entity to be removed. - /// \param[in] _recursive Whether to recursively delete all child - /// entities. True by default. - public: void RequestRemoveEntity(const Entity _entity, - bool _recursive = true); - - /// \brief Request to remove all entities. This will insert the request - /// into a queue. The queue is processed toward the end of a simulation - /// update step. - public: void RequestRemoveEntities(); - - /// \brief Get whether an Entity exists. - /// \param[in] _entity Entity to confirm. - /// \return True if the Entity exists. - public: bool HasEntity(const Entity _entity) const; - - /// \brief Get the first parent of the given entity. - /// \details Entities are not expected to have multiple parents. - /// TODO(louise) Either prevent multiple parents or provide full support - /// for multiple parents. - /// \param[in] _entity Entity. - /// \return The parent entity or kNullEntity if there's none. - public: Entity ParentEntity(const Entity _entity) const; - - /// \brief Set the parent of an entity. - /// - /// \details It is recommended that systems don't call this function - /// directly, and instead use the `gazebo::SdfEntityCreator` class to - /// create entities that have the correct parent-child relationship. - /// - /// \param[in] _child Entity to set the parent - /// \param[in] _parent Entity which should be an immediate parent _child - /// entity. - /// \return True if successful. Will fail if entities don't exist. - public: bool SetParentEntity(const Entity _child, const Entity _parent); - - /// \brief Get whether a component type has ever been created. - /// \param[in] _typeId ID of the component type to check. - /// \return True if the provided _typeId has been created. - public: bool HasComponentType(const ComponentTypeId _typeId) const; - - /// \brief Check whether an entity has a specific component. - /// \param[in] _entity The entity to check. - /// \param[in] _key The component to check. - /// \return True if the component key belongs to the entity. - public: bool EntityHasComponent(const Entity _entity, - const ComponentKey &_key) const; - - /// \brief Check whether an entity has a specific component type. - /// \param[in] _entity The entity to check. - /// \param[in] _typeId Component type id to check. - /// \return True if the entity exists and has at least one component - /// with the provided type. - public: bool EntityHasComponentType(const Entity _entity, - const ComponentTypeId &_typeId) const; - - /// \brief Get whether an entity has all the given component types. - /// \param[in] _entity The entity to check. - /// \param[in] _types Component types to check that the Entity has. - /// \return True if the given entity has all the given types. - public: bool EntityMatches(Entity _entity, - const std::set &_types) const; - - /// \brief Remove a component from an entity based on a key. - /// \param[in] _entity The entity. - /// \param[in] _key A key that uniquely identifies a component. - /// \return True if the entity and component existed and the component was - /// removed. - public: bool RemoveComponent( - const Entity _entity, const ComponentKey &_key); - - /// \brief Remove a component from an entity based on a type id. - /// \param[in] _entity The entity. - /// \param[in] _typeId Component's type Id. - /// \return True if the entity and component existed and the component was - /// removed. - public: bool RemoveComponent( - const Entity _entity, const ComponentTypeId &_typeId); - - /// \brief Remove a component from an entity based on a type. - /// \param[in] _entity The entity. - /// \tparam Component type. - /// \return True if the entity and component existed and the component was - /// removed. - public: template - bool RemoveComponent(Entity _entity); - - /// \brief Rebuild all the views. This could be an expensive - /// operation. - public: void RebuildViews(); - - /// \brief Create a component of a particular type. This will copy the - /// _data parameter. - /// \param[in] _entity The entity that will be associated with - /// the component. - /// \param[in] _data Data used to construct the component. - /// \return Key that uniquely identifies the component. - public: template - ComponentKey CreateComponent(const Entity _entity, - const ComponentTypeT &_data); - - /// \brief Get a component assigned to an entity based on a - /// component type. - /// \param[in] _entity The entity. - /// \return The component of the specified type assigned to specified - /// Entity, or nullptr if the component could not be found. - public: template - const ComponentTypeT *Component(const Entity _entity) const; - - /// \brief Get a mutable component assigned to an entity based on a - /// component type. - /// \param[in] _entity The entity. - /// \return The component of the specified type assigned to specified - /// Entity, or nullptr if the component could not be found. - public: template - ComponentTypeT *Component(const Entity _entity); - - /// \brief Get a component based on a key. - /// \param[in] _key A key that uniquely identifies a component. - /// \return The component associated with the key, or nullptr if the - /// component could not be found. - public: template - const ComponentTypeT *Component(const ComponentKey &_key) const; - - /// \brief Get a mutable component based on a key. - /// \param[in] _key A key that uniquely identifies a component. - /// \return The component associated with the key, or nullptr if the - /// component could not be found. - public: template - ComponentTypeT *Component(const ComponentKey &_key); - - /// \brief Get a mutable component assigned to an entity based on a - /// component type. If the component doesn't exist, create it and - /// initialize with the given default value. - /// \param[in] _entity The entity. - /// \param[in] _default The value that should be used to construct - /// the component in case the component doesn't exist. - /// \return The component of the specified type assigned to the specified - /// entity. - public: template - ComponentTypeT *ComponentDefault(Entity _entity, - const typename ComponentTypeT::Type &_default = - typename ComponentTypeT::Type()); - - /// \brief Get the data from a component. - /// * If the component type doesn't hold any data, this won't compile. - /// * If the entity doesn't have that component, it will return nullopt. - /// * If the entity has the component, return its data. - /// \param[in] _entity The entity. - /// \tparam ComponentTypeT Component type - /// \return The data of the component of the specified type assigned to - /// specified Entity, or nullptr if the component could not be found. - public: template - std::optional ComponentData( - const Entity _entity) const; - - /// \brief Set the data from a component. - /// * If the component type doesn't hold any data, this won't compile. - /// * If the entity doesn't have that component, the component will be - /// created. - /// * If the entity has the component, its data will be updated. - /// \param[in] _entity The entity. - /// \param[in] _data New component data - /// \tparam ComponentTypeT Component type - /// \return True if data has changed. It will always be true if the data - /// type doesn't have an equality operator. - public: template - bool SetComponentData(const Entity _entity, - const typename ComponentTypeT::Type &_data); - - /// \brief Get the type IDs of all components attached to an entity. - /// \param[in] _entity Entity to check. - /// \return All the component type IDs. - public: std::unordered_set ComponentTypes( - Entity _entity) const; - - /// \brief The first component instance of the specified type. - /// \return First component instance of the specified type, or nullptr - /// if the type does not exist. - public: template - const ComponentTypeT *First() const; - - /// \brief The first component instance of the specified type. - /// \return First component instance of the specified type, or nullptr - /// if the type does not exist. - public: template - ComponentTypeT *First(); - - /// \brief Get an entity which matches the value of all the given - /// components. For example, the following will return the entity which - /// has an name component equal to "name" and has a model component: - /// - /// auto entity = EntityByComponents(components::Name("name"), - /// components::Model()); - /// - /// \details Component type must have inequality operator. - /// - /// \param[in] _desiredComponents All the components which must match. - /// \return Entity or kNullEntity if no entity has the exact components. - public: template - Entity EntityByComponents( - const ComponentTypeTs &..._desiredComponents) const; - - /// \brief Get all entities which match the value of all the given - /// components. For example, the following will return the entities which - /// have a name component equal to "camera" and a sensor component: - /// - /// auto entities = EntitiesByComponents(components::Name("camera"), - /// components::Sensor()); - /// - /// \details Component type must have inequality operator. - /// - /// \param[in] _desiredComponents All the components which must match. - /// \return All matching entities, or an empty vector if no child entity - /// has the exact components. - public: template - std::vector EntitiesByComponents( - const ComponentTypeTs &..._desiredComponents) const; - - /// \brief Get all entities which match the value of all the given - /// components and are immediate children of a given parent entity. - /// For example, the following will return a child of entity `parent` - /// which has an int component equal to 123, and a string component - /// equal to "name": - /// - /// auto entity = ChildrenByComponents(parent, 123, std::string("name")); - /// - /// \details Component type must have inequality operator. - /// - /// \param[in] _parent Entity which should be an immediate parent of the - /// returned entity. - /// \param[in] _desiredComponents All the components which must match. - /// \return All matching entities, or an empty vector if no child entity - /// has the exact components. - public: template - std::vector ChildrenByComponents(Entity _parent, - const ComponentTypeTs &..._desiredComponents) const; - - /// why is this required? - private: template - struct identity; // NOLINT - - /// \brief A version of Each() that doesn't use a cache. The cached - /// version, Each(), is preferred. - /// Get all entities which contain given component types, as well - /// as the components. - /// \param[in] _f Callback function to be called for each matching entity. - /// The function parameter are all the desired component types, in the - /// order they're listed on the template. The callback function can - /// return false to stop subsequent calls to the callback, otherwise - /// a true value should be returned. - /// \tparam ComponentTypeTs All the desired component types. - /// \warning This function should not be called outside of System's - /// PreUpdate, Update, or PostUpdate callbacks. - public: template - void EachNoCache(typename identity>::type _f) const; - - /// \brief A version of Each() that doesn't use a cache. The cached - /// version, Each(), is preferred. - /// Get all entities which contain given component types, as well - /// as the mutable components. - /// \param[in] _f Callback function to be called for each matching entity. - /// The function parameter are all the desired component types, in the - /// order they're listed on the template. The callback function can - /// return false to stop subsequent calls to the callback, otherwise - /// a true value should be returned. - /// \tparam ComponentTypeTs All the desired mutable component types. - /// \warning This function should not be called outside of System's - /// PreUpdate, Update, or PostUpdate callbacks. - public: template - void EachNoCache(typename identity>::type _f); - - /// \brief Get all entities which contain given component types, as well - /// as the components. Note that an entity marked for removal (but not - /// processed yet) will be included in the list of entities iterated by - /// this call. - /// \param[in] _f Callback function to be called for each matching entity. - /// The function parameter are all the desired component types, in the - /// order they're listed on the template. The callback function can - /// return false to stop subsequent calls to the callback, otherwise - /// a true value should be returned. - /// \tparam ComponentTypeTs All the desired component types. - /// \warning This function should not be called outside of System's - /// PreUpdate, Update, or PostUpdate callbacks. - public: template - void Each(typename identity>::type _f) const; - - /// \brief Get all entities which contain given component types, as well - /// as the mutable components. Note that an entity marked for removal (but - /// not processed yet) will be included in the list of entities iterated - /// by this call. - /// \param[in] _f Callback function to be called for each matching entity. - /// The function parameter are all the desired component types, in the - /// order they're listed on the template. The callback function can - /// return false to stop subsequent calls to the callback, otherwise - /// a true value should be returned. - /// \tparam ComponentTypeTs All the desired mutable component types. - /// \warning This function should not be called outside of System's - /// PreUpdate, Update, or PostUpdate callbacks. - public: template - void Each(typename identity>::type _f); - - /// \brief Call a function for each parameter in a pack. - /// \param[in] _f Function to be called. - /// \param[in] _components Parameters which should be passed to the - /// function. - public: template - static void ForEach(Function _f, const ComponentTypeTs &... _components); - - /// \brief Get all newly created entities which contain given component - /// types, as well as the components. This "newness" is cleared at the end - /// of a simulation step. - /// \param[in] _f Callback function to be called for each matching entity. - /// The function parameter are all the desired component types, in the - /// order they're listed on the template. The callback function can - /// return false to stop subsequent calls to the callback, otherwise - /// a true value should be returned. - /// \tparam ComponentTypeTs All the desired component types. - /// \warning Since entity creation occurs during PreUpdate, this function - /// should not be called in a System's PreUpdate callback (it's okay to - /// call this function in the Update callback). If you need to call this - /// function in a system's PostUpdate callback, you should use the const - /// version of this method. - public: template - void EachNew(typename identity>::type _f); - - /// \brief Get all newly created entities which contain given component - /// types, as well as the components. This "newness" is cleared at the end - /// of a simulation step. This is the const version. - /// \param[in] _f Callback function to be called for each matching entity. - /// The function parameter are all the desired component types, in the - /// order they're listed on the template. The callback function can - /// return false to stop subsequent calls to the callback, otherwise - /// a true value should be returned. - /// \tparam ComponentTypeTs All the desired component types. - /// \warning Since entity creation occurs during PreUpdate, this function - /// should not be called in a System's PreUpdate callback (it's okay to - /// call this function in the Update or PostUpdate callback). - public: template - void EachNew(typename identity>::type _f) const; - - /// \brief Get all entities which contain given component types and are - /// about to be removed, as well as the components. - /// \param[in] _f Callback function to be called for each matching entity. - /// The function parameter are all the desired component types, in the - /// order they're listed on the template. The callback function can - /// return false to stop subsequent calls to the callback, otherwise - /// a true value should be returned. - /// \tparam ComponentTypeTs All the desired component types. - /// \warning This function should not be called outside of System's - /// PostUpdate callback. - public: template - void EachRemoved(typename identity>::type _f) const; - - /// \brief Get a graph with all the entities. Entities are vertices and - /// edges point from parent to children. - /// \return Entity graph. - public: const EntityGraph &Entities() const; - - /// \brief Get all entities which are descendants of a given entity, - /// including the entity itself. - /// \param[in] _entity Entity whose descendants we want. - /// \return All child entities recursively, including _entity. It will be - /// empty if the entity doesn't exist. - public: std::unordered_set Descendants(Entity _entity) const; - - /// \brief Get a message with the serialized state of the given entities - /// and components. - /// \details The header of the message will not be populated, it is the - /// responsibility of the caller to timestamp it before use. - /// \param[in] _entities Entities to be serialized. Leave empty to get - /// all entities. - /// \param[in] _types Type ID of components to be serialized. Leave empty - /// to get all components. - public: msgs::SerializedState State( - const std::unordered_set &_entities = {}, - const std::unordered_set &_types = {}) const; - - /// \brief Get a message with the serialized state of all entities and - /// components that are changing in the current iteration - /// - /// Currently supported: - /// * New entities and all of their components - /// * Removed entities and all of their components - /// - /// Future work: - /// * Entities which had a component added - /// * Entities which had a component removed - /// * Entities which had a component modified - /// - /// \details The header of the message will not be populated, it is the - /// responsibility of the caller to timestamp it before use. - public: msgs::SerializedState ChangedState() const; - - /// \brief Get whether there are new entities. - /// \return True if there are new entities. - public: bool HasNewEntities() const; - - /// \brief Get whether there are any entities marked to be removed. - /// \return True if there are entities marked to be removed. - public: bool HasEntitiesMarkedForRemoval() const; - - /// \brief Get whether there are one-time component changes. These changes - /// do not happen frequently and should be processed immediately. - /// \return True if there are any components with one-time changes. - public: bool HasOneTimeComponentChanges() const; - - /// \brief Get the components types that are marked as periodic changes. - /// \return All the components that at least one entity marked as - /// periodic changes. - public: std::unordered_set - ComponentTypesWithPeriodicChanges() const; - - /// \brief Set the absolute state of the ECM from a serialized message. - /// Entities / components that are in the new state but not in the old - /// one will be created. - /// Entities / components that are marked as removed will be removed, but - /// they won't be removed if they're not present in the state. - /// \details The header of the message will not be handled, it is the - /// responsibility of the caller to use the timestamp. - /// \param[in] _stateMsg Message containing state to be set. - public: void SetState(const msgs::SerializedState &_stateMsg); - - /// \brief Get a message with the serialized state of the given entities - /// and components. - /// \details The header of the message will not be populated, it is the - /// responsibility of the caller to timestamp it before use. - /// \param[in] _state serialized state - /// \param[in] _entities Entities to be serialized. Leave empty to get - /// all entities. - /// \param[in] _types Type ID of components to be serialized. Leave empty - /// to get all components. - /// \param[in] _full True to get all the entities and components. - /// False will get only components and entities that have changed. - public: void State( - msgs::SerializedStateMap &_state, - const std::unordered_set &_entities = {}, - const std::unordered_set &_types = {}, - bool _full = false) const; - - /// \brief Get a message with the serialized state of all entities and - /// components that are changing in the current iteration - /// - /// Currently supported: - /// * New entities and all of their components - /// * Removed entities and all of their components - /// - /// Future work: - /// * Entities which had a component added - /// * Entities which had a component removed - /// * Entities which had a component modified - /// - /// \param[in] _state New serialized state. - /// \details The header of the message will not be populated, it is the - /// responsibility of the caller to timestamp it before use. - public: void ChangedState(msgs::SerializedStateMap &_state) const; - - /// \brief Set the absolute state of the ECM from a serialized message. - /// Entities / components that are in the new state but not in the old - /// one will be created. - /// Entities / components that are marked as removed will be removed, but - /// they won't be removed if they're not present in the state. - /// \details The header of the message will not be handled, it is the - /// responsibility of the caller to use the timestamp. - /// \param[in] _stateMsg Message containing state to be set. - public: void SetState(const msgs::SerializedStateMap &_stateMsg); - - /// \brief Set the changed state of a component. - /// \param[in] _entity The entity. - /// \param[in] _type Type of the component. - /// \param[in] _c Changed state value, defaults to one-time-change. - public: void SetChanged( - const Entity _entity, const ComponentTypeId _type, - gazebo::ComponentState _c = ComponentState::OneTimeChange); - - /// \brief Get a component's state. - /// \param[in] _entity Entity that contains the component. - /// \param[in] _typeId Component type ID. - /// \return Component's current state - public: gazebo::ComponentState ComponentState(const Entity _entity, - const ComponentTypeId _typeId) const; - - /// \brief All future entities will have an id that starts at _offset. - /// This can be used to avoid entity id collisions, such as during log - /// playback. - /// \param[in] _offset Offset value. - public: void SetEntityCreateOffset(uint64_t _offset); - - /// \brief Clear the list of newly added entities so that a call to - /// EachAdded after this will have no entities to iterate. This function - /// is protected to facilitate testing. - protected: void ClearNewlyCreatedEntities(); - - /// \brief Process all entity remove requests. This will remove - /// entities and their components. This function is protected to - /// facilitate testing. - protected: void ProcessRemoveEntityRequests(); - - /// \brief Mark all components as not changed. - protected: void SetAllComponentsUnchanged(); - - /// \brief Get whether an Entity exists and is new. - /// - /// Entities are considered new in the time between their creation and a - /// call to ClearNewlyCreatedEntities - /// \param[in] _entity Entity id to check. - /// \return True if the Entity is new. - private: bool IsNewEntity(const Entity _entity) const; - - /// \brief Get whether an Entity has been marked to be removed. - /// \param[in] _entity Entity id to check. - /// \return True if the Entity has been marked to be removed. - private: bool IsMarkedForRemoval(const Entity _entity) const; - - /// \brief Delete an existing Entity. - /// \param[in] _entity The entity to remove. - /// \returns True if the Entity existed and was deleted. - private: bool RemoveEntity(const Entity _entity); - - /// \brief The first component instance of the specified type. - /// \return First component instance of the specified type, or nullptr - /// if the type does not exist. - private: components::BaseComponent *First( - const ComponentTypeId _componentTypeId); - - /// \brief Implementation of CreateComponent. - /// \param[in] _entity The entity that will be associated with - /// the component. - /// \param[in] _componentTypeId Id of the component type. - /// \param[in] _data Data used to construct the component. - /// \return Key that uniquely identifies the component. - private: ComponentKey CreateComponentImplementation( - const Entity _entity, - const ComponentTypeId _componentTypeId, - const components::BaseComponent *_data); - - /// \brief Get a component based on a component type. - /// \param[in] _entity The entity. - /// \param[in] _type Id of the component type. - /// \return The component of the specified type assigned to specified - /// Entity, or nullptr if the component could not be found. - private: const components::BaseComponent *ComponentImplementation( - const Entity _entity, - const ComponentTypeId _type) const; - - /// \brief Get a mutable component based on a component type. - /// \param[in] _entity The entity. - /// \param[in] _type Id of the component type. - /// \return The component of the specified type assigned to specified - /// Entity, or nullptr if the component could not be found. - private: components::BaseComponent *ComponentImplementation( - const Entity _entity, - const ComponentTypeId _type); - - /// \brief Get a component based on a key. - /// \param[in] _key A key that uniquely identifies a component. - /// \return The component associated with the key, or nullptr if the - /// component could not be found. - private: const components::BaseComponent *ComponentImplementation( - const ComponentKey &_key) const; - - /// \brief Get a mutable component based on a key. - /// \param[in] _key A key that uniquely identifies a component. - /// \return The component associated with the key, or nullptr if the - /// component could not be found. - private: components::BaseComponent *ComponentImplementation( - const ComponentKey &_key); - - /// \brief End of the AddComponentToView recursion. This function is - /// called when Rest is empty. - /// \param[in, out] _view The FirstComponent will be added to the - /// _view. - /// \param[in] _entity The entity. - private: template::type = 0> - void AddComponentsToView(detail::View &_view, - const Entity _entity) const; - - /// \brief Recursively add components to a view. This function is - /// called when Rest is NOT empty. - /// \param[in, out] _view The FirstComponent will be added to the - /// _view. - /// \param[in] _entity The entity. - private: template::type = 0> - void AddComponentsToView(detail::View &_view, - const Entity _entity) const; - - /// \brief Find a View that matches the set of ComponentTypeIds. If - /// a match is not found, then a new view is created. - /// \tparam ComponentTypeTs All the component types that define a view. - /// \return A reference to the view. - private: template - detail::View &FindView() const; - - /// \brief Find a view based on the provided component type ids. - /// \param[in] _types The component type ids that serve as a key into - /// a map of views. - /// \param[out] _iter Iterator to the found element in the view map. - /// Check the return value to see if this iterator is valid. - /// \return True if the view was found, false otherwise. - private: bool FindView(const std::set &_types, - std::map::iterator &_iter) const; // NOLINT - - /// \brief Add a new view to the set of stored views. - /// \param[in] _types The set of component type ids that is the key - /// for the view. - /// \param[in] _view The view to add. - /// \return An iterator to the view. - private: std::map::iterator - AddView(const std::set &_types, - detail::View &&_view) const; - - /// \brief Update views that contain the provided entity. - /// \param[in] _entity The entity. - private: void UpdateViews(const Entity _entity); - - /// \brief Get a component ID based on an entity and the component's type. - /// \param[in] _entity The entity. - /// \param[in] _type Component type ID. - private: ComponentId EntityComponentIdFromType( - const Entity _entity, const ComponentTypeId _type) const; - - /// \brief Add an entity and its components to a serialized state message. - /// \param[out] _msg The state message. - /// \param[in] _entity The entity to be added. - /// \param[in] _types Component types to be added. Leave empty for all - /// components. - private: void AddEntityToMessage(msgs::SerializedState &_msg, - Entity _entity, - const std::unordered_set &_types = {}) const; - - /// \brief Private data pointer. - private: std::unique_ptr dataPtr; - - /// \brief Add an entity and its components to a serialized state message. - /// \param[out] _msg The state message. - /// \param[in] _entity The entity to be added. - /// \param[in] _types Component types to be added. Leave empty for all - /// components. - /// \param[in] _full True to get all the entities and components. - /// False will get only components and entities that have changed. - /// \note This function will mark `Changed` components as not changed. - /// See the todo in the implementation. - private: void AddEntityToMessage(msgs::SerializedStateMap &_msg, - Entity _entity, - const std::unordered_set &_types = {}, - bool _full = false) const; - - // Make runners friends so that they can manage entity creation and - // removal. This should be safe since runners are internal - // to Gazebo. - friend class GuiRunner; - friend class SimulationRunner; - - // Make network managers friends so they have control over component - // states. Like the runners, the managers are internal. - friend class NetworkManagerPrimary; - friend class NetworkManagerSecondary; - - // Make View a friend so that it can access components. - // This should be safe since View is internal to Gazebo. - friend class detail::View; - }; - } - } -} - -#include "ignition/gazebo/detail/EntityComponentManager.hh" - -#endif +#include +#include diff --git a/include/ignition/gazebo/EventManager.hh b/include/ignition/gazebo/EventManager.hh index 7d466c5b09..cc99c75b80 100644 --- a/include/ignition/gazebo/EventManager.hh +++ b/include/ignition/gazebo/EventManager.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,136 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_EVENTMANAGER_HH_ -#define IGNITION_GAZEBO_EVENTMANAGER_HH_ - -#include -#include -#include -#include -#include - -#include -#include + */ +#include #include -#include -#include - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // Forward declarations. - class IGNITION_GAZEBO_HIDDEN EventManagerPrivate; - - /// \brief The EventManager is used to send/receive notifications of - /// simulator events. - /// - /// The simulator environment and corresponding systems can either connect - /// to an Event or emit an Event as needed to signal actions that need to - /// occur. - /// - /// See \ref ignition::gazebo::events for a complete list of events. - class IGNITION_GAZEBO_VISIBLE EventManager - { - /// \brief Constructor - public: EventManager(); - - /// \brief Destructor - public: ~EventManager(); - - /// \brief Add a connection to an event. - /// \param[in] _subscriber A std::function callback function. The function - /// signature must match that of the event (template parameter E). - /// \return A Connection pointer, which will automatically call - /// Disconnect when it goes out of scope. - public: template - ignition::common::ConnectionPtr - Connect(const typename E::CallbackT &_subscriber) - { - if (this->events.find(typeid(E)) == this->events.end()) { - this->events[typeid(E)] = std::make_unique(); - } - - E *eventPtr = dynamic_cast(this->events[typeid(E)].get()); - // All values in the map should be derived from Event, - // so this shouldn't be an issue, but it doesn't hurt to check. - if (eventPtr != nullptr) - { - return eventPtr->Connect(_subscriber); - } - else - { - ignerr << "Failed to connect event: " - << typeid(E).name() << std::endl; - return nullptr; - } - } - - /// \brief Emit an event signal to connected subscribers. - /// \param[in] _args function arguments to be passed to the event - /// callbacks. Must match the signature of the event type E. - public: template - void Emit(Args && ... _args) - { - if (this->events.find(typeid(E)) == this->events.end()) - { - // If there are no events of type E in the map, create it. - // But it also means there is nothing to signal. - // - // This is also needed to suppress unused function warnings - // for Events that are purely emitted, with no connections. - this->events[typeid(E)] = std::make_unique(); - return; - } - - E *eventPtr = dynamic_cast(this->events[typeid(E)].get()); - // All values in the map should be derived from Event, - // so this shouldn't be an issue, but it doesn't hurt to check. - if (eventPtr != nullptr) - { - eventPtr->Signal(std::forward(_args) ...); - } - else - { - ignerr << "Failed to signal event: " - << typeid(E).name() << std::endl; - } - } - - - /// \brief Convenience type for storing typeinfo references. - private: using TypeInfoRef = std::reference_wrapper; - - /// \brief Hash functor for TypeInfoRef - private: struct Hasher - { - std::size_t operator()(TypeInfoRef _code) const - { - return _code.get().hash_code(); - } - }; - - /// \brief Equality functor for TypeInfoRef - private: struct EqualTo - { - bool operator()(TypeInfoRef _lhs, TypeInfoRef _rhs) const - { - return _lhs.get() == _rhs.get(); - } - }; - - /// \brief Container of used signals. - private: std::unordered_map, - Hasher, EqualTo> events; - }; - } - } -} - -#endif // IGNITION_GAZEBO_EVENTMANAGER_HH_ diff --git a/include/ignition/gazebo/Events.hh b/include/ignition/gazebo/Events.hh index 672c264c03..cc90c49edf 100644 --- a/include/ignition/gazebo/Events.hh +++ b/include/ignition/gazebo/Events.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,54 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_EVENTS_HH_ -#define IGNITION_GAZEBO_EVENTS_HH_ + */ -#include - -#include - -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Entity.hh" - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - /// \brief Namespace for all events. Refer to the EventManager class for - /// more information about events. - namespace events - { - /// \brief The pause event can be used to pause or unpause simulation. - /// Emit a value of true to pause simulation, and emit a value of false - /// to unpause simulation. - /// - /// For example, to pause simulation use: - /// \code - /// eventManager.Emit(true); - /// \endcode - using Pause = ignition::common::EventT; - - /// \brief The stop event can be used to terminate simulation. - /// Emit this signal to terminate an active simulation. - /// - /// For example: - /// \code - /// eventManager.Emit(); - /// \endcode - using Stop = ignition::common::EventT; - - /// \brief Event used to load plugins for an entity into simulation. - /// Pass in the entity which will own the plugins, and an SDF element for - /// the entity, which may contain multiple `` tags. - using LoadPlugins = common::EventT; - } - } // namespace events - } // namespace gazebo -} // namespace ignition - -#endif // IGNITION_GAZEBO_EVENTS_HH_ +#include +#include diff --git a/include/ignition/gazebo/Export.hh b/include/ignition/gazebo/Export.hh new file mode 100644 index 0000000000..290d7e16bd --- /dev/null +++ b/include/ignition/gazebo/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/Link.hh b/include/ignition/gazebo/Link.hh index 8d7f228417..3122dcda65 100644 --- a/include/ignition/gazebo/Link.hh +++ b/include/ignition/gazebo/Link.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,268 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_LINK_HH_ -#define IGNITION_GAZEBO_LINK_HH_ - -#include -#include -#include -#include - -#include -#include -#include +#include #include -#include -#include -#include -#include - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // Forward declarations. - class IGNITION_GAZEBO_HIDDEN LinkPrivate; - // - /// \class Link Link.hh ignition/gazebo/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. - /// All the functions provided here are meant to be used with a link - /// entity. - /// - /// For example, given a link's entity, to find the value of its - /// name component, one could use the entity-component manager (`ecm`) - /// directly as follows: - /// - /// std::string name = ecm.Component(entity)->Data(); - /// - /// Using this class however, the same information can be obtained with - /// a simpler function call: - /// - /// Link link(entity); - /// std::string name = link.Name(ecm); - /// - class IGNITION_GAZEBO_VISIBLE Link - { - /// \brief Constructor - /// \param[in] _entity Link entity - public: explicit Link(gazebo::Entity _entity = kNullEntity); - - /// \brief Copy constructor - /// \param[in] _link Link to copy. - public: Link(const Link &_link); - - /// \brief Move constructor - /// \param[in] _link Link to move. - public: Link(Link &&_link) noexcept; - - /// \brief Move assignment operator. - /// \param[in] _link Link component to move. - /// \return Reference to this. - public: Link &operator=(Link &&_link) noexcept; - - /// \brief Copy assignment operator. - /// \param[in] _link Link to copy. - /// \return Reference to this. - public: Link &operator=(const Link &_link); - - /// \brief Destructor - public: ~Link(); - - /// \brief Get the entity which this Link is related to. - /// \return Link entity. - public: gazebo::Entity Entity() const; - - /// \brief Reset Entity to a new one - /// \param[in] _newEntity New link entity. - public: void ResetEntity(gazebo::Entity _newEntity); - - /// \brief Check whether this link correctly refers to an entity that - /// has a components::Link. - /// \param[in] _ecm Entity-component manager. - /// \return True if it's a valid link in the manager. - public: bool Valid(const EntityComponentManager &_ecm) const; - - /// \brief Get the link's unscoped name. - /// \param[in] _ecm Entity-component manager. - /// \return Link's name or nullopt if the entity does not have a - /// components::Name component - public: std::optional Name( - const EntityComponentManager &_ecm) const; - - /// \brief Get the parent model - /// \param[in] _ecm Entity-component manager. - /// \return Parent Model or nullopt if the entity does not have a - /// components::ParentEntity component. - public: std::optional ParentModel( - const EntityComponentManager &_ecm) const; - - /// \brief Check if this is the canonical link. - /// \param[in] _ecm Entity-component manager. - /// \return True if it is the canonical link. - public: bool IsCanonical(const EntityComponentManager &_ecm) const; - - /// \brief Get whether this link has wind enabled. - /// \param[in] _ecm Entity-component manager. - /// \return True if wind mode is on. - public: bool WindMode(const EntityComponentManager &_ecm) const; - - /// \brief Get the ID of a collision entity which is an immediate child of - /// this link. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _name Collision name. - /// \return Collision entity. - public: gazebo::Entity CollisionByName(const EntityComponentManager &_ecm, - const std::string &_name) const; - - /// \brief Get the ID of a visual entity which is an immediate child of - /// this link. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _name Visual name. - /// \return Visual entity. - public: gazebo::Entity VisualByName(const EntityComponentManager &_ecm, - const std::string &_name) const; - - /// \brief Get all collisions which are immediate children of this link. - /// \param[in] _ecm Entity-component manager. - /// \return All collisions in this link. - public: std::vector Collisions( - const EntityComponentManager &_ecm) const; - - /// \brief Get all visuals which are immediate children of this link. - /// \param[in] _ecm Entity-component manager. - /// \return All visuals in this link. - public: std::vector Visuals( - const EntityComponentManager &_ecm) const; - - /// \brief Get the number of collisions which are immediate children of - /// this link. - /// \param[in] _ecm Entity-component manager. - /// \return Number of collisions in this link. - public: uint64_t CollisionCount(const EntityComponentManager &_ecm) const; - - /// \brief Get the number of visuals which are immediate children of this - /// link. - /// \param[in] _ecm Entity-component manager. - /// \return Number of visuals in this link. - public: uint64_t VisualCount(const EntityComponentManager &_ecm) const; - - /// \brief Get the pose of the link frame in the world coordinate frame. - /// \param[in] _ecm Entity-component manager. - /// \return Absolute Pose of the link or nullopt if the entity does not - /// have a components::WorldPose component. - public: std::optional WorldPose( - const EntityComponentManager &_ecm) const; - - /// \brief Get the world pose of the link inertia. - /// \param[in] _ecm Entity-component manager. - /// \return Inertial pose in world frame or nullopt if the - /// link does not have the components components::WorldPose and - /// components::Inertial. - public: std::optional WorldInertialPose( - const EntityComponentManager &_ecm) const; - - /// \brief Get the linear velocity at the origin of of the link frame - /// expressed in the world frame, using an offset expressed in a - /// body-fixed frame. If no offset is given, the velocity at the origin of - /// the Link frame will be returned. - /// \param[in] _ecm Entity-component manager. - /// \return Linear velocity of the link or nullopt if the velocity checks - /// aren't enabled. - /// \sa EnableVelocityChecks - public: std::optional WorldLinearVelocity( - const EntityComponentManager &_ecm) const; - - /// \brief Get the linear velocity of a point on the body in the world - /// frame, using an offset expressed in a body-fixed frame. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _offset Offset of the point from the origin of the Link - /// frame, expressed in the body-fixed frame. - /// \return Linear velocity of the point on the body or nullopt if - /// velocity checks aren't enabled. - /// \sa EnableVelocityChecks - public: std::optional WorldLinearVelocity( - const EntityComponentManager &_ecm, - const math::Vector3d &_offset) const; - - /// \brief Get the angular velocity of the link in the world frame - /// \param[in] _ecm Entity-component manager. - /// \return Angular velocity of the link or nullopt if velocity checks - /// aren't enabled. - /// \sa EnableVelocityChecks - public: std::optional WorldAngularVelocity( - const EntityComponentManager &_ecm) const; - - /// \brief By default, Gazebo will not report velocities for a link, so - /// functions like `WorldLinearVelocity` will return nullopt. This - /// function can be used to enable all velocity checks. - /// \param[in] _ecm Mutable reference to the ECM. - /// \param[in] _enable True to enable checks, false to disable. Defaults - /// to true. - public: void EnableVelocityChecks(EntityComponentManager &_ecm, - bool _enable = true) const; - - /// \brief Get the linear acceleration of the body in the world frame. - /// \param[in] _ecm Entity-component manager. - /// \return Linear acceleration of the body in the world frame or nullopt - /// if acceleration checks aren't enabled. - /// \sa EnableAccelerationChecks - public: std::optional WorldLinearAcceleration( - const EntityComponentManager &_ecm) const; - - /// \brief By default, Gazebo will not report accelerations for a link, so - /// functions like `WorldLinearAcceleration` will return nullopt. This - /// function can be used to enable all acceleration checks. - /// \param[in] _ecm Mutable reference to the ECM. - /// \param[in] _enable True to enable checks, false to disable. Defaults - /// to true. - public: void EnableAccelerationChecks(EntityComponentManager &_ecm, - bool _enable = true) const; - - /// \brief Get the inertia matrix in the world frame. - /// \param[in] _ecm Entity-component manager. - /// \return Inertia matrix in world frame, returns nullopt if link - /// does not have components components::Inertial and - /// components::WorldPose. - public: std::optional WorldInertiaMatrix( - const EntityComponentManager &_ecm) const; - - /// \brief Get the rotational and translational kinetic energy of the - /// link with respect to the world frame. - /// \param[in] _ecm Entity-component manager. - /// \return Kinetic energy in world frame, returns nullopt if link - /// does not have components components::Inertial, - /// components::WorldAngularVelocity, components::WorldLinearVelocity, - /// and components::WorldPose. - public: std::optional WorldKineticEnergy( - const EntityComponentManager &_ecm) const; - - /// \brief Add a force expressed in world coordinates and applied at the - /// center of mass of the link. - /// \param[in] _ecm Mutable Entity-component manager. - /// \param[in] _force Force to be applied expressed in world coordinates - public: void AddWorldForce(EntityComponentManager &_ecm, - const math::Vector3d &_force) const; - - /// \brief Add a wrench expressed in world coordinates and applied to - /// the link at the link's origin. This wrench is applied for one - /// simulation step. - /// \param[in] _ecm Mutable Entity-component manager. - /// \param[in] _force Force to be applied expressed in world coordinates - /// \param[in] _torque Torque to be applied expressed in world coordinates - public: void AddWorldWrench(EntityComponentManager &_ecm, - const math::Vector3d &_force, - const math::Vector3d &_torque) const; - - /// \brief Pointer to private data. - private: std::unique_ptr dataPtr; - }; - } - } -} -#endif diff --git a/include/ignition/gazebo/Model.hh b/include/ignition/gazebo/Model.hh index 172c7399ae..b309bc985e 100644 --- a/include/ignition/gazebo/Model.hh +++ b/include/ignition/gazebo/Model.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,172 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_MODEL_HH_ -#define IGNITION_GAZEBO_MODEL_HH_ - -#include -#include -#include - -#include + */ +#include #include -#include -#include -#include - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // Forward declarations. - class IGNITION_GAZEBO_HIDDEN ModelPrivate; - // - /// \class Model Model.hh ignition/gazebo/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. - /// All the functions provided here are meant to be used with a model - /// entity. - /// - /// For example, given a model's entity, to find the value of its - /// name component, one could use the entity-component manager (`ecm`) - /// directly as follows: - /// - /// std::string name = ecm.Component(entity)->Data(); - /// - /// Using this class however, the same information can be obtained with - /// a simpler function call: - /// - /// Model model(entity); - /// std::string name = model.Name(ecm); - /// - /// \todo(louise) Store the ecm instead of passing it at every API call. - class IGNITION_GAZEBO_VISIBLE Model { - /// \brief Constructor - /// \param[in] _entity Model entity - public: explicit Model(gazebo::Entity _entity = kNullEntity); - - /// \brief Copy constructor - /// \param[in] _model Model to copy. - public: Model(const Model &_model); - - /// \brief Move constructor - /// \param[in] _model Model to move. - public: Model(Model &&_model) noexcept; - - /// \brief Move assignment operator. - /// \param[in] _model Model component to move. - /// \return Reference to this. - public: Model &operator=(Model &&_model) noexcept; - - /// \brief Copy assignment operator. - /// \param[in] _model Model to copy. - /// \return Reference to this. - public: Model &operator=(const Model &_model); - - /// \brief Destructor - public: virtual ~Model(); - - /// \brief Get the entity which this Model is related to. - /// \return Model entity. - public: gazebo::Entity Entity() const; - - /// \brief Check whether this model correctly refers to an entity that - /// has a components::Model. - /// \param[in] _ecm Entity-component manager. - /// \return True if it's a valid model in the manager. - public: bool Valid(const EntityComponentManager &_ecm) const; - - /// \brief Get the model's unscoped name. - /// \param[in] _ecm Entity-component manager. - /// \return Model's name. - public: std::string Name(const EntityComponentManager &_ecm) const; - - /// \brief Get whether this model is static. - /// \param[in] _ecm Entity-component manager. - /// \return True if static. - public: bool Static(const EntityComponentManager &_ecm) const; - - /// \brief Get whether this model has self-collide enabled. - /// \param[in] _ecm Entity-component manager. - /// \return True if self-colliding. - public: bool SelfCollide(const EntityComponentManager &_ecm) const; - - /// \brief Get whether this model has wind enabled. - /// \param[in] _ecm Entity-component manager. - /// \return True if wind mode is on. - public: bool WindMode(const EntityComponentManager &_ecm) const; - - /// \brief Get the source file where this model came from. If empty, - /// the model wasn't loaded directly from a file, probably from an SDF - /// string. - /// \param[in] _ecm Entity-component manager. - /// \return Path to the source SDF file. - public: std::string SourceFilePath(const EntityComponentManager &_ecm) - const; - - /// \brief Get the ID of a joint entity which is an immediate child of - /// this model. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _name Joint name. - /// \return Joint entity. - /// \todo(anyone) Make const - public: gazebo::Entity JointByName(const EntityComponentManager &_ecm, - const std::string &_name); - - /// \brief Get the ID of a link entity which is an immediate child of - /// this model. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _name Link name. - /// \return Link entity. - /// \todo(anyone) Make const - public: gazebo::Entity LinkByName(const EntityComponentManager &_ecm, - const std::string &_name); - - /// \brief Get all joints which are immediate children of this model. - /// \param[in] _ecm Entity-component manager. - /// \return All joints in this model. - public: std::vector Joints( - const EntityComponentManager &_ecm) const; - - /// \brief Get all links which are immediate children of this model. - /// \param[in] _ecm Entity-component manager. - /// \return All links in this model. - public: std::vector Links( - const EntityComponentManager &_ecm) const; - - /// \brief Get the number of joints which are immediate children of this - /// model. - /// \param[in] _ecm Entity-component manager. - /// \return Number of joints in this model. - public: uint64_t JointCount(const EntityComponentManager &_ecm) const; - - /// \brief Get the number of links which are immediate children of this - /// model. - /// \param[in] _ecm Entity-component manager. - /// \return Number of links in this model. - public: uint64_t LinkCount(const EntityComponentManager &_ecm) const; - - /// \brief Set a command to change the model's pose. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _pose New model pose. - public: void SetWorldPoseCmd(EntityComponentManager &_ecm, - const math::Pose3d &_pose); - - /// \brief Get the model's canonical link entity. - /// \param[in] _ecm Entity-component manager. - /// \return Link entity. - public: gazebo::Entity CanonicalLink( - const EntityComponentManager &_ecm) const; - - /// \brief Pointer to private data. - private: std::unique_ptr dataPtr; - }; - } - } -} -#endif diff --git a/include/ignition/gazebo/SdfEntityCreator.hh b/include/ignition/gazebo/SdfEntityCreator.hh index 8ad31f32bb..d51dd3d976 100644 --- a/include/ignition/gazebo/SdfEntityCreator.hh +++ b/include/ignition/gazebo/SdfEntityCreator.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,164 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_CREATEREMOVE_HH_ -#define IGNITION_GAZEBO_CREATEREMOVE_HH_ + */ -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // Forward declarations. - class SdfEntityCreatorPrivate; - // - /// \class SdfEntityCreator SdfEntityCreator.hh - /// ignition/gazebo/SdfEntityCreator.hh - /// \brief Provides convenient functions to spawn entities and load their - /// plugins from SDF elements, to remove them, and to change their - /// hierarchy. - /// - /// This class provides wrappers around entities and components - /// which are more convenient and straight-forward to use than dealing - /// with the `EntityComponentManager` directly. - class IGNITION_GAZEBO_VISIBLE SdfEntityCreator - { - /// \brief Constructor - /// \param[in] _ecm Entity component manager. This class keeps a pointer - /// to it, but doesn't assume ownership. - /// \param[in] _eventManager Event manager. This class keeps a pointer - /// to it, but doesn't assume ownership. - public: explicit SdfEntityCreator(EntityComponentManager &_ecm, - EventManager &_eventManager); - - /// \brief Copy constructor - /// \param[in] _creator SdfEntityCreator to copy. - public: SdfEntityCreator(const SdfEntityCreator &_creator); - - /// \brief Move constructor - /// \param[in] _creator SdfEntityCreator to move. - public: SdfEntityCreator(SdfEntityCreator &&_creator) noexcept; - - /// \brief Move assignment operator. - /// \param[in] _creator SdfEntityCreator component to move. - /// \return Reference to this. - public: SdfEntityCreator &operator=(SdfEntityCreator &&_creator) noexcept; - - /// \brief Copy assignment operator. - /// \param[in] _creator SdfEntityCreator to copy. - /// \return Reference to this. - public: SdfEntityCreator &operator=(const SdfEntityCreator &_creator); - - /// \brief Destructor. - public: ~SdfEntityCreator(); - - /// \brief Create all entities that exist in the sdf::World object and - /// load their plugins. - /// \param[in] _world SDF world object. - /// \return World entity. - public: Entity CreateEntities(const sdf::World *_world); - - /// \brief Create all entities that exist in the sdf::Model object and - /// load their plugins. Also loads plugins of child sensors. - /// \param[in] _model SDF model object. - /// \return Model entity. - public: Entity CreateEntities(const sdf::Model *_model); - - /// \brief Create all entities that exist in the sdf::Actor object and - /// load their plugins. - /// \param[in] _actor SDF actor object. - /// \return Actor entity. - public: Entity CreateEntities(const sdf::Actor *_actor); - - /// \brief Create all entities that exist in the sdf::Light object and - /// load their plugins. - /// \param[in] _light SDF light object. - /// \return Light entity. - public: Entity CreateEntities(const sdf::Light *_light); - - /// \brief Create all entities that exist in the sdf::Link object and - /// load their plugins. - /// \param[in] _link SDF link object. - /// \return Link entity. - public: Entity CreateEntities(const sdf::Link *_link); - - /// \brief Create all entities that exist in the sdf::Joint object and - /// load their plugins. - /// \param[in] _joint SDF joint object. - /// \return Joint entity. - public: Entity CreateEntities(const sdf::Joint *_joint); - - /// \brief Create all entities that exist in the sdf::Visual object and - /// load their plugins. - /// \param[in] _visual SDF visual object. - /// \return Visual entity. - public: Entity CreateEntities(const sdf::Visual *_visual); - - /// \brief Create all entities that exist in the sdf::Collision object and - /// load their plugins. - /// \param[in] _collision SDF collision object. - /// \return Collision entity. - public: Entity CreateEntities(const sdf::Collision *_collision); - - /// \brief Create all entities that exist in the sdf::Sensor object. - /// Sensor plugins won't be directly loaded by this function. - /// \param[in] _sensor SDF sensor object. - /// \return Sensor entity. - /// \sa CreateEntities(const sdf::Model *) - public: Entity CreateEntities(const sdf::Sensor *_sensor); - - /// \brief Request an entity deletion. This will insert the request - /// into a queue. The queue is processed toward the end of a simulation - /// update step. - /// \param[in] _entity Entity to be removed. - /// \param[in] _recursive Whether to recursively delete all child - /// entities. True by default. - public: void RequestRemoveEntity(const Entity _entity, - bool _recursive = true); - - /// \brief Set an entity's parent entity. This function takes care of - /// updating the `EntityComponentManager` and necessary components. - /// \param[in] _child Entity which should be parented. - /// \param[in] _parent Entity which should be _child's parent. - public: void SetParent(Entity _child, Entity _parent); - - /// \brief Overloaded function to recursively create model entities - /// and make sure a) only one canonical link is created per model tree, - /// and b) we override the nested model's static property to true if - /// its parent is static - /// \param[in] _model SDF model object. - /// \param[in] _createCanonicalLink True to create a canonical link - /// component and attach to its child link entity - /// \param[in] _staticParent True if parent is static, false otherwise. - /// \return Model entity. - private: Entity CreateEntities(const sdf::Model *_model, - bool _createCanonicalLink, bool _staticParent); - - /// \brief Pointer to private data. - private: std::unique_ptr dataPtr; - }; - } - } -} -#endif +#include +#include diff --git a/include/ignition/gazebo/Server.hh b/include/ignition/gazebo/Server.hh index 088fda99d8..df05ba03b3 100644 --- a/include/ignition/gazebo/Server.hh +++ b/include/ignition/gazebo/Server.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,283 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_SERVER_HH_ -#define IGNITION_GAZEBO_SERVER_HH_ + */ -#include -#include -#include -#include +#include #include -#include -#include -#include -#include - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // Forware declarations - class ServerPrivate; - - /// \class Server Server.hh ignition/gazebo/Server.hh - /// \brief The server instantiates and controls simulation. - /// - /// ## Example Usage - /// - /// A basic simulation server can be instantiated and run using - /// - /// ``` - /// ignition::gazebo::Server server; - /// server.Run(); - /// ``` - /// - /// An SDF File can be passed into the server via a ServerConfig object. - /// The server will parse the SDF file and create entities for the - /// elements contained in the file. - /// - /// ``` - /// ignition::gazebo::ServerConfig config; - /// config.SetSdfFile("path_to_file.sdf"); - /// ignition::gazebo::Server server(config); - /// server.Run(); - /// ``` - /// - /// The Run() function accepts a few arguments, one of which is whether - /// simulation should start in a paused state. The default value of this - /// argument is true, which starts simulation paused. This means that by - /// default, running the server will cause systems to update but some - /// systems may not update because paused == true. For example, - /// a physics system will not update its state when paused is - /// true. So, while a Server can be Running, simulation itself can be - /// paused. - /// - /// Simulation is paused by default because a common use case is to load - /// a world from the command line. If simulation starts running, the - /// GUI client may miss the first few simulation iterations. - /// - /// ## Services - /// - /// The following are services provided by the Server. - /// The `` in the service list is the name of the - /// simulated world. - /// - /// List syntax: *service_name(request_msg_type) : response_msg_type* - /// - /// 1. `/world//scene/info(none)` : ignition::msgs::Scene - /// + Returns the current scene information. - /// - /// 2. `/gazebo/resource_paths/get` : ignition::msgs::StringMsg_V - /// + Get list of resource paths. - /// - /// 3. `/gazebo/resource_paths/add` : ignition::msgs::Empty - /// + Add new resource paths. - /// - /// 4. `/server_control`(ignition::msgs::ServerControl) : - /// ignition::msgs::Boolean - /// + Control the simulation server. - /// - /// ## Topics - /// - /// The following are topics provided by the Server. - /// The `` in the service list is the name of the - /// simulated world. - /// - /// List syntax: *topic_name : published_msg_type* - /// - /// 1. `/world//clock` : ignition::msgs::Clock - /// - /// 2. `/world//stats` : ignition::msgs::WorldStatistics - /// + This topic is throttled to 5Hz. - /// - /// 3. `/gazebo/resource_paths` : ignition::msgs::StringMsg_V - /// + Updated list of resource paths. - /// - class IGNITION_GAZEBO_VISIBLE Server - { - /// \brief Construct the server using the parameters specified in a - /// ServerConfig. - /// \param[in] _config Server configuration parameters. If this - /// parameter is omitted, then an empty world is loaded. - public: explicit Server(const ServerConfig &_config = ServerConfig()); - - /// \brief Destructor - public: ~Server(); - - /// \brief Set the update period. The update period is the wall-clock time - /// between ECS updates. - /// Note that this is different from the simulation update rate. ECS - /// systems will be updated even while sim time is paused. - /// \param[in] _updatePeriod Duration between updates. - /// \param[in] _worldIndex Index of the world to query. - public: void SetUpdatePeriod( - const std::chrono::steady_clock::duration &_updatePeriod, - const unsigned int _worldIndex = 0); - - /// \brief Run the server. By default this is a non-blocking call, - /// which means the server runs simulation in a separate thread. Pass - /// in true to the _blocking argument to run the server in the current - /// thread. - /// \param[in] _blocking False to run the server in a new thread. True - /// to run the server in the current thread. - /// \param[in] _iterations Number of steps to perform. A value of - /// zero will run indefinitely. - /// \param[in] _paused True to start simulation in a paused state, - /// false, to start simulation unpaused. - /// \return In non-blocking mode, the return value is true if a thread - /// was successfully created. In blocking mode, true will be returned - /// if the Server ran for the specified number of iterations or was - /// terminated. False will always be returned if signal handlers could - /// not be initialized, and if the server is already running. - public: bool Run(const bool _blocking = false, - const uint64_t _iterations = 0, - const bool _paused = true); - - /// \brief Run the server once, all systems will be updated once and - /// then this returns. This is a blocking call. - /// \param[in] _paused True to run the simulation in a paused state, - /// false to run simulation unpaused. The simulation iterations will - /// be increased by 1. - /// \return False if the server was terminated before completing, - /// not being initialized, or if the server is already running. - public: bool RunOnce(const bool _paused = true); - - /// \brief Get whether the server is running. The server can have zero - /// or more simulation worlds, each of which may or may not be - /// running. See Running(const unsigned int) to get the running status - /// of a world. - /// \return True if the server is running. - public: bool Running() const; - - /// \brief Get whether a world simulation instance is running. When - /// running is true, then systems are being updated but simulation may - /// or may not be stepping forward. Check the value of Paused() to - /// determine if a world simulation instance is stepping forward. - /// If Paused() returns true, then simulation is not stepping foward. - /// \param[in] _worldIndex Index of the world to query. - /// \return True if the server is running, or std::nullopt - /// if _worldIndex is invalid. - public: std::optional Running(const unsigned int _worldIndex) const; - - /// \brief Set whether a world simulation instance is paused. - /// When paused is true, then simulation for the world is not stepping - /// forward. - /// \param[in] _paused True to pause the world, false to unpause. - /// \param[in] _worldIndex Index of the world to query. - /// \return True if the world referenced by _worldIndex exists, false - /// otherwise. - public: bool SetPaused(const bool _paused, - const unsigned int _worldIndex = 0) const; - - /// \brief Get whether a world simulation instance is paused. - /// When paused is true, then simulation for the world is not stepping - /// forward. - /// \param[in] _worldIndex Index of the world to query. - /// \return True if the world simulation instance is paused, false if - /// stepping forward, or std::nullopt if _worldIndex is invalid. - public: std::optional Paused( - const unsigned int _worldIndex = 0) const; - - /// \brief Get the number of iterations the server has executed. - /// \param[in] _worldIndex Index of the world to query. - /// \return The current iteration count, - /// or std::nullopt if _worldIndex is invalid. - public: std::optional IterationCount( - const unsigned int _worldIndex = 0) const; - - /// \brief Get the number of entities on the server. - /// \param[in] _worldIndex Index of the world to query. - /// \return Entity count, or std::nullopt if _worldIndex is invalid. - public: std::optional EntityCount( - const unsigned int _worldIndex = 0) const; - - /// \brief Get the number of systems on the server. - /// \param[in] _worldIndex Index of the world to query. - /// \return System count, or std::nullopt if _worldIndex is invalid. - public: std::optional SystemCount( - const unsigned int _worldIndex = 0) const; - - /// \brief Add a System to the server. The server must not be running when - /// calling this. - /// \param[in] _system system to be added - /// \param[in] _worldIndex Index of the world to query. - /// \return Whether the system was added successfully, or std::nullopt - /// if _worldIndex is invalid. - public: std::optional AddSystem( - const SystemPluginPtr &_system, - const unsigned int _worldIndex = 0); - - /// \brief Add a System to the server. The server must not be running when - /// calling this. - /// \param[in] _system System to be added - /// \param[in] _worldIndex Index of the world to add to. - /// \return Whether the system was added successfully, or std::nullopt - /// if _worldIndex is invalid. - public: std::optional AddSystem( - const std::shared_ptr &_system, - const unsigned int _worldIndex = 0); - - /// \brief Get an Entity based on a name. - /// \details If multiple entities with the same name exist, the first - /// entity found will be returned. - /// \param [in] _name Name of the entity to get from the specified - /// world. - /// \param[in] _worldIndex Index of the world to query. - /// \return The entity, or std::nullopt if the entity or world - /// doesn't exist. - public: std::optional EntityByName(const std::string &_name, - const unsigned int _worldIndex = 0) const; - - /// \brief Return true if the specified world has an entity with the - /// provided name. - /// \param[in] _name Name of the entity. - /// \param[in] _worldIndex Index of the world. - /// \return True if the _worldIndex is valid and the - /// entity exists in the world. - public: bool HasEntity(const std::string &_name, - const unsigned int _worldIndex = 0) const; - - /// \brief Return true if the specified world has an entity with the - /// provided name and the entity was queued for deletion. Note that - /// the entity is not removed immediately. Entity deletion happens at - /// the end of the next (or current depending on when this function is - /// called) simulation step. - /// \details If multiple entities with the same name exist, only the - /// first entity found will be deleted. - /// \param[in] _name Name of the entity to delete. - /// \param[in] _recursive Whether to recursively delete all child - /// entities. True by default. - /// \param[in] _worldIndex Index of the world. - /// \return True if the entity exists in the world and it was queued - /// for deletion. - public: bool RequestRemoveEntity(const std::string &_name, - bool _recursive = true, - const unsigned int _worldIndex = 0); - - /// \brief Return true if the specified world has an entity with the - /// provided id and the entity was queued for deletion. Note that - /// the entity is not removed immediately. Entity deletion happens at - /// the end of the next (or current depending on when this function is - /// called) simulation step. - /// \param[in] _entity The entity to delete. - /// \param[in] _recursive Whether to recursively delete all child - /// entities. True by default. - /// \param[in] _worldIndex Index of the world. - /// \return True if the entity exists in the world and it was queued - /// for deletion. - public: bool RequestRemoveEntity(const Entity _entity, - bool _recursive = true, - const unsigned int _worldIndex = 0); - - /// \brief Private data - private: std::unique_ptr dataPtr; - }; - } - } -} - -#endif diff --git a/include/ignition/gazebo/ServerConfig.hh b/include/ignition/gazebo/ServerConfig.hh index 185aed2d1e..7a0cea51c2 100644 --- a/include/ignition/gazebo/ServerConfig.hh +++ b/include/ignition/gazebo/ServerConfig.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,424 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_SERVERCONFIG_HH_ -#define IGNITION_GAZEBO_SERVERCONFIG_HH_ + */ -#include -#include -#include -#include // NOLINT(*) -#include -#include -#include +#include #include -#include - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // Forward declarations. - class ServerConfigPrivate; - - /// \class ServerConfig ServerConfig.hh ignition/gazebo/ServerConfig.hh - /// \brief Configuration parameters for a Server. An instance of this - /// object can be used to construct a Server with a particular - /// configuration. - class IGNITION_GAZEBO_VISIBLE ServerConfig - { - class PluginInfoPrivate; - /// \brief Information about a plugin that should be loaded by the - /// server. - /// \details Currently supports attaching a plugin to an entity given its - /// type and name, but it can't tell apart multiple entities with the same - /// name in different parts of the entity tree. - /// \sa const std::list &Plugins() const - public: class IGNITION_GAZEBO_VISIBLE PluginInfo - { - /// \brief Default constructor. - public: PluginInfo(); - - /// \brief Destructor. - public: ~PluginInfo(); - - /// \brief Constructor with plugin information specified. - /// \param[in] _entityName Name of the entity which should receive - /// this plugin. The name is used in conjuction with _entityType to - /// uniquely identify an entity. - /// \param[in] _entityType Entity type which should receive this - /// plugin. The type is used in conjuction with _entityName to - /// uniquely identify an entity. - /// \param[in] _filename Plugin library filename. - /// \param[in] _name Name of the interface within the plugin library - /// to load. - /// \param[in] _sdf Plugin XML elements associated with this plugin. - public: PluginInfo(const std::string &_entityName, - const std::string &_entityType, - const std::string &_filename, - const std::string &_name, - const sdf::ElementPtr &_sdf); - - /// \brief Copy constructor. - /// \param[in] _info Plugin to copy. - public: PluginInfo(const PluginInfo &_info); - - /// \brief Equal operator. - /// \param[in] _info PluginInfo to copy. - /// \return Reference to this class. - public: PluginInfo &operator=(const PluginInfo &_info); - - /// \brief Get the name of the entity which should receive - /// this plugin. The name is used in conjuction with _entityType to - /// uniquely identify an entity. - /// \return Entity name. - public: const std::string &EntityName() const; - - /// \brief Set the name of the entity which should receive - /// this plugin. The name is used in conjuction with _entityType to - /// uniquely identify an entity. - /// \param[in] _entityName Entity name. - public: void SetEntityName(const std::string &_entityName); - - /// \brief Get the entity type which should receive this - /// plugin. The type is used in conjuction with EntityName to - /// uniquely identify an entity. - /// \return Entity type string. - public: const std::string &EntityType() const; - - /// \brief Set the type of the entity which should receive this - /// plugin. The type is used in conjuction with EntityName to - /// uniquely identify an entity. - /// \param[in] _entityType Entity type string. - public: void SetEntityType(const std::string &_entityType); - - /// \brief Get the plugin library filename. - /// \return Plugin library filename. - public: const std::string &Filename() const; - - /// \brief Set the type of the entity which should receive this - /// plugin. The type is used in conjuction with EntityName to - /// uniquely identify an entity. - /// \param[in] _filename Entity type string. - public: void SetFilename(const std::string &_filename); - - /// \brief Name of the interface within the plugin library - /// to load. - /// \return Interface name. - public: const std::string &Name() const; - - /// \brief Set the name of the interface within the plugin library - /// to load. - /// \param[in] _name Interface name. - public: void SetName(const std::string &_name); - - /// \brief Plugin XML elements associated with this plugin. - /// \return SDF pointer. - public: const sdf::ElementPtr &Sdf() const; - - /// \brief Set the plugin XML elements associated with this plugin. - /// \param[in] _sdf SDF pointer, it will be cloned. - public: void SetSdf(const sdf::ElementPtr &_sdf); - - /// \brief Private data pointer - private: std::unique_ptr dataPtr; - }; - - /// \brief Constructor - public: ServerConfig(); - - /// \brief Copy constructor. - /// \param[in] _config ServerConfig to copy. - public: ServerConfig(const ServerConfig &_config); - - /// \brief Destructor - public: ~ServerConfig(); - - /// \brief Set an SDF file to be used with the server. - /// - /// Setting the SDF file will override any value set by `SetSdfString`. - /// - /// \param[in] _file Full path to an SDF file. - /// \return (reserved for future use) - public: bool SetSdfFile(const std::string &_file); - - /// \brief Get the SDF file that has been set. An empty string will be - /// returned if an SDF file has not been set. - /// \return The full path to the SDF file, or empty string. - public: std::string SdfFile() const; - - /// \brief Set an SDF string to be used by the server. - /// - /// Setting the SDF string will override any value set by `SetSdfFile`. - /// - /// \param[in] _sdfString Full path to an SDF file. - /// \return (reserved for future use) - public: bool SetSdfString(const std::string &_sdfString); - - /// \brief Get the SDF String that has been set. An empty string will - /// be returned if an SDF string has not been set. - /// \return The full contents of the SDF string, or empty string. - public: std::string SdfString() const; - - /// \brief Set the update rate in Hertz. Value <=0 are ignored. - /// \param[in] _hz The desired update rate of the server in Hertz. - public: void SetUpdateRate(const double &_hz); - - /// \brief Get the update rate in Hertz. - /// \return The desired update rate of the server in Hertz, or nullopt if - /// an UpdateRate has not been set. - public: std::optional UpdateRate() const; - - /// \brief Get whether the server is using the level system - /// \return True if the server is set to use the level system - public: bool UseLevels() const; - - /// \brief Get whether the server is using the level system. - /// \param[in] _levels Value to set. - public: void SetUseLevels(const bool _levels); - - /// \brief Get whether the server is using the distributed sim system - /// \return True if the server is set to use the distributed simulation - /// system - /// \sa SetNetworkRole(const std::string &_role) - public: bool UseDistributedSimulation() const; - - /// \brief Set the number of network secondary servers that the - /// primary server should expect. This value is valid only when - /// SetNetworkRole("primary") is also used. - /// \param[in] _secondaries Number of secondary servers. - /// \sa SetNetworkRole(const std::string &_role) - /// \sa NetworkRole() const - public: void SetNetworkSecondaries(unsigned int _secondaries); - - /// \brief Get the number of secondary servers that a primary server - /// should expect. - /// \return Number of secondary servers. - /// \sa SetNetworkSecondaries(unsigned int _secondaries) - public: unsigned int NetworkSecondaries() const; - - /// \brief Set the network role, which is one of [primary, secondary]. - /// If primary is used, then make sure to also set the numer of - /// network secondaries via - /// SetNetworkSecondaries(unsigned int _secondaries). - /// \param[in] _role Network role, one of [primary, secondary]. - /// \note Setting a network role enables distributed simulation. - /// \sa SetNetworkSecondaries(unsigned int _secondaries) - public: void SetNetworkRole(const std::string &_role); - - /// \brief Get the network role. See - /// SetNetworkRole(const std::string &_role) for more information - /// about distributed simulation and network roles. - /// \return The network role. - /// \sa SetNetworkRole(const std::string &_role) - public: std::string NetworkRole() const; - - /// \brief Get whether the server is recording states - /// \return True if the server is set to record states - public: bool UseLogRecord() const; - - /// \brief Set whether the server is recording states - /// \param[in] _record Value to set - public: void SetUseLogRecord(const bool _record); - - /// \brief Get path to place recorded states - /// \return Path to place recorded states - public: const std::string LogRecordPath() const; - - /// \brief Set path to place recorded states - /// \param[in] _recordPath Path to place recorded states - public: void SetLogRecordPath(const std::string &_recordPath); - - /// \brief Get whether to ignore the path specified in SDF. - /// \return Whether to ignore the path specified in SDF - /// TODO(anyone) Deprecate on Dome, SDF path will always be ignored. - public: bool LogIgnoreSdfPath() const; - - /// \brief Set whether to ignore the path specified in SDF. Path in SDF - /// should be ignored if a record path is specified on the command line, - /// for example. - /// \param[in] _ignore Whether to ignore the path specified in SDF - /// TODO(anyone) Deprecate on Dome, SDF path will always be ignored. - public: void SetLogIgnoreSdfPath(bool _ignore); - - /// \brief Add a topic to record. - /// \param[in] _topic Topic name, which can include wildcards. - public: void AddLogRecordTopic(const std::string &_topic); - - /// \brief Clear topics to record. This will remove all topics set - /// using AddLogRecordTopic. - public: void ClearLogRecordTopics(); - - /// \brief Get the topics to record that were added using - /// AddLogRecordTopic. - /// \return The topics to record. - public: const std::vector &LogRecordTopics() const; - - /// \brief Get path to recorded states to play back - /// \return Path to recorded states - public: const std::string LogPlaybackPath() const; - - /// \brief Set path to recorded states to play back - /// \param[in] _playbackPath Path to recorded states - public: void SetLogPlaybackPath(const std::string &_playbackPath); - - /// \brief Get whether meshes and material files are recorded - /// \return True if resources should be recorded. - public: bool LogRecordResources() const; - - /// \brief Set whether meshes and material files are recorded - /// \param[in] _recordResources Value to set - public: void SetLogRecordResources(bool _recordResources); - - /// \brief Get file path to compress log files to - /// \return File path to compress log files to - public: std::string LogRecordCompressPath() const; - - /// \brief Set file path to compress log files to - /// \param[in] _path File path to compress log files to - public: void SetLogRecordCompressPath(const std::string &_path); - - /// \brief The given random seed. - /// \return The random seed or 0 if not specified. - public: unsigned int Seed() const; - - /// \brief Set the random seed. - /// \param[in] _seed The seed. - public: void SetSeed(unsigned int _seed); - - /// \brief Get the update period duration. - /// \return The desired update period, or nullopt if - /// an UpdateRate has not been set. - public: std::optional - UpdatePeriod() const; - - /// \brief Path to where simulation resources, such as models downloaded - /// from fuel.gazebosim.org, should be stored. - /// \return Path to a location on disk. An empty string indicates that - /// the default value will be used, which is currently - /// ~/.ignition/fuel. - public: const std::string &ResourceCache() const; - - /// \brief Set the path to where simulation resources, such as models - /// downloaded from fuel.gazebosim.org, should be stored. - /// \param[in] _path Path to a location on disk. An empty string - /// indicates that the default value will be used, which is currently - /// ~/.ignition/fuel. - public: void SetResourceCache(const std::string &_path); - - /// \brief Physics engine plugin library to load. - /// \return File containing physics engine library. - public: const std::string &PhysicsEngine() const; - - /// \brief Set the physics engine plugin library. - /// \param[in] _physicsEngine File containing physics engine library. - public: void SetPhysicsEngine(const std::string &_physicsEngine); - - /// \brief Render engine plugin library to load. - /// \return File containing render engine library. - public: const std::string &RenderEngineServer() const; - - /// \brief Render engine plugin library to load. - /// \return File containing render engine library. - public: const std::string &RenderEngineGui() const; - - /// \brief Set the render engine server plugin library. - /// \param[in] _renderEngineServer File containing render engine library. - public: void SetRenderEngineServer( - const std::string &_renderEngineServer); - - /// \brief Set the render engine gui plugin library. - /// \param[in] _renderEngineGui File containing render engine library. - public: void SetRenderEngineGui(const std::string &_renderEngineGui); - - /// \brief Instruct simulation to attach a plugin to a specific - /// entity when simulation starts. - /// \param[in] _info Information about the plugin to load. - public: void AddPlugin(const PluginInfo &_info); - - /// \brief Add multiple plugins to the simulation - /// \param[in] _plugins List of Information about the plugin to load. - public: void AddPlugins(const std::list &_plugins); - - /// \brief Generate PluginInfo for Log recording based on the - /// internal state of this ServerConfig object: - /// \sa UseLogRecord - /// \sa LogRecordPath - /// \sa LogRecordResources - /// \sa LogRecordCompressPath - /// \sa LogRecordTopics - public: PluginInfo LogRecordPlugin() const; - - /// \brief Generate PluginInfo for Log playback based on the - /// internal state of this ServerConfig object: - /// \sa LogPlaybackPath - public: PluginInfo LogPlaybackPlugin() const; - - /// \brief Get all the plugins that should be loaded. - /// \return A list of all the plugins specified via - /// AddPlugin(const PluginInfo &). - public: const std::list &Plugins() const; - - /// \brief Equal operator. - /// \param[in] _cfg ServerConfig to copy. - /// \return Reference to this class. - public: ServerConfig &operator=(const ServerConfig &_cfg); - - /// \brief Get the timestamp of this ServerConfig. This is the system - /// time when this ServerConfig was created. The timestamp is used - /// internally to create log file paths so that both state and console - /// logs are co-located. - /// \return Time when this ServerConfig was created. - public: const std::chrono::time_point & - Timestamp() const; - - /// \brief Private data pointer - private: std::unique_ptr dataPtr; - }; - - /// \brief Parse plugins from XML configuration file. - /// \param[in] _fname Absolute path to the configuration file to parse. - /// \return A list of all of the plugins found in the configuration file - std::list - IGNITION_GAZEBO_VISIBLE - parsePluginsFromFile(const std::string &_fname); - - /// \brief Parse plugins from XML configuration string. - /// \param[in] _str XML configuration content to parse - /// \return A list of all of the plugins found in the configuration string. - std::list - IGNITION_GAZEBO_VISIBLE - parsePluginsFromString(const std::string &_str); - - /// \brief Load plugin information, following ordering. - /// - /// This method is used when no plugins are found in an SDF - /// file to load either a default or custom set of plugins. - /// - /// The following order is used to resolve: - /// 1. Config file located at IGN_GAZEBO_SERVER_CONFIG_PATH environment - /// variable. - /// * If IGN_GAZEBO_SERVER_CONFIG_PATH is set but empty, no plugins - /// are loaded. - /// 2. File at ${IGN_HOMEDIR}/.ignition/gazebo/server.config - /// 3. File at ${IGN_DATA_INSTALL_DIR}/server.config - /// - /// If any of the above files exist but are empty, resolution - /// stops and the plugin list will be empty. - /// - // - /// \param[in] _isPlayback Is the server in playback mode. If so, fallback - /// to playback_server.config. - // - /// \return A list of plugins to load, based on above ordering - std::list - IGNITION_GAZEBO_VISIBLE - loadPluginInfo(bool _isPlayback = false); - } - } -} - -#endif diff --git a/include/ignition/gazebo/System.hh b/include/ignition/gazebo/System.hh index f8ef47ed01..fe4601549e 100644 --- a/include/ignition/gazebo/System.hh +++ b/include/ignition/gazebo/System.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,114 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_SYSTEM_HH_ -#define IGNITION_GAZEBO_SYSTEM_HH_ - -#include + */ +#include #include -#include -#include -#include -#include - -#include - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - /// \brief Namespace for all System plugins. Refer to the System class for - /// more information about systems. - namespace systems {} - - /// \class System System.hh ignition/gazebo/System.hh - /// \brief Base class for a System. - /// - /// A System operates on Entities that have certain Components. A System - /// will only operate on an Entity if it has all of the required - /// Components. - /// - /// Systems are executed in three phases, with each phase for a given step - /// corresponding to the entities at time UpdateInfo::simTime: - /// * PreUpdate - /// * Has read-write access to world entities and components. - /// * This is where systems say what they'd like to happen at time - /// UpdateInfo::simTime. - /// * Can be used to modify state before physics runs, for example for - /// applying control signals or performing network syncronization. - /// * Update - /// * Has read-write access to world entities and components. - /// * Used for physics simulation step (i.e., simulates what happens at - /// time UpdateInfo::simTime). - /// * PostUpdate - /// * Has read-only access to world entities and components. - /// * Captures everything that happened at time UpdateInfo::simTime. - /// * Used to read out results at the end of a simulation step to be used - /// for sensor or controller updates. - /// - /// It's important to note that UpdateInfo::simTime does not refer to the - /// current time, but the time reached after the PreUpdate and Update calls - /// have finished. So, if any of the *Update functions are called with - /// simulation paused, time does not advance, which means the time reached - /// after PreUpdate and Update is the same as the starting time. This - /// explains why UpdateInfo::simTime is initially 0 if simulation is started - /// paused, while UpdateInfo::simTime is initially UpdateInfo::dt if - /// simulation is started un-paused. - class IGNITION_GAZEBO_VISIBLE System - { - /// \brief Constructor - public: System(); - - /// \brief Destructor - public: virtual ~System(); - }; - - /// \class ISystemConfigure ISystem.hh ignition/gazebo/System.hh - /// \brief Interface for a system that implements optional configuration - /// - /// Configure is called after the system is instatiated and all entities - /// and components are loaded from the corresponding SDF world, and before - /// simulation begins exectution. - class IGNITION_GAZEBO_VISIBLE ISystemConfigure { - /// \brief Configure the system - /// \param[in] _entity The entity this plugin is attached to. - /// \param[in] _sdf The SDF Element associated with this system plugin. - /// \param[in] _ecm The EntityComponentManager of the given simulation - /// instance. - /// \param[in] _eventMgr The EventManager of the given simulation - /// instance. - public: virtual void Configure( - const Entity &_entity, - const std::shared_ptr &_sdf, - EntityComponentManager &_ecm, - EventManager &_eventMgr) = 0; - }; - - /// \class ISystemPreUpdate ISystem.hh ignition/gazebo/System.hh - /// \brief Interface for a system that uses the PreUpdate phase - class IGNITION_GAZEBO_VISIBLE ISystemPreUpdate { - public: virtual void PreUpdate(const UpdateInfo &_info, - EntityComponentManager &_ecm) = 0; - }; - - /// \class ISystemUpdate ISystem.hh ignition/gazebo/System.hh - /// \brief Interface for a system that uses the Update phase - class IGNITION_GAZEBO_VISIBLE ISystemUpdate { - public: virtual void Update(const UpdateInfo &_info, - EntityComponentManager &_ecm) = 0; - }; - - /// \class ISystemPostUpdate ISystem.hh ignition/gazebo/System.hh - /// \brief Interface for a system that uses the PostUpdate phase - class IGNITION_GAZEBO_VISIBLE ISystemPostUpdate{ - public: virtual void PostUpdate(const UpdateInfo &_info, - const EntityComponentManager &_ecm) = 0; - }; - } - } -} -#endif diff --git a/include/ignition/gazebo/SystemLoader.hh b/include/ignition/gazebo/SystemLoader.hh index 7b8537b061..91699610c6 100644 --- a/include/ignition/gazebo/SystemLoader.hh +++ b/include/ignition/gazebo/SystemLoader.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,69 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_SYSTEMLOADER_HH_ -#define IGNITION_GAZEBO_SYSTEMLOADER_HH_ - -#include -#include -#include - -#include - -#include -#include -#include - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // Forward declarations. - class IGNITION_GAZEBO_HIDDEN SystemLoaderPrivate; - - /// \class SystemLoader SystemLoader.hh ignition/gazebo/SystemLoader.hh - /// \brief Class for loading/unloading System plugins. - class IGNITION_GAZEBO_VISIBLE SystemLoader - { - /// \brief Constructor - public: explicit SystemLoader(); - - /// \brief Destructor - public: ~SystemLoader(); - - /// \brief Add path to search for plugins. - /// \param[in] _path New path to be added. - public: void AddSystemPluginPath(const std::string &_path); - - /// \brief Load and instantiate system plugin from an SDF element. - /// \param[in] _sdf SDF Element describing plugin instance to be loaded. - /// \returns Shared pointer to system instance or nullptr. - public: std::optional LoadPlugin( - const sdf::ElementPtr &_sdf); - - /// \brief Load and instantiate system plugin from name/filename. - /// \param[in] _filename Shared library filename to load plugin from. - /// \param[in] _name Class name to be instantiated. - /// \param[in] _sdf SDF Element describing plugin instance to be loaded. - /// \returns Shared pointer to system instance or nullptr. - public: std::optional LoadPlugin( - const std::string &_filename, - const std::string &_name, - const sdf::ElementPtr &_sdf); - - /// \brief Makes a printable string with info about systems - /// \returns A pretty string - public: std::string PrettyStr() const; - - /// \brief Pointer to private data. - private: std::unique_ptr dataPtr; - }; - } - using SystemLoaderPtr = std::shared_ptr; - } -} -#endif // IGNITION_GAZEBO_SYSTEMLOADER_HH_ + */ +#include +#include diff --git a/include/ignition/gazebo/SystemPluginPtr.hh b/include/ignition/gazebo/SystemPluginPtr.hh index f2170dcb50..81c88c19f7 100644 --- a/include/ignition/gazebo/SystemPluginPtr.hh +++ b/include/ignition/gazebo/SystemPluginPtr.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,25 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_SYSTEMPLUGINPTR_HH_ -#define IGNITION_GAZEBO_SYSTEMPLUGINPTR_HH_ + */ -#include -#include - -namespace ignition -{ - namespace gazebo - { - using SystemPluginPtr = ignition::plugin::SpecializedPluginPtr< - System, - ISystemConfigure, - ISystemPreUpdate, - ISystemUpdate, - ISystemPostUpdate - >; - } -} - -#endif +#include +#include diff --git a/include/ignition/gazebo/TestFixture.hh b/include/ignition/gazebo/TestFixture.hh index 75d371f437..6a6270ae85 100644 --- a/include/ignition/gazebo/TestFixture.hh +++ b/include/ignition/gazebo/TestFixture.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,101 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_TESTFIXTURE_HH_ -#define IGNITION_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" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -// -class IGNITION_GAZEBO_HIDDEN TestFixturePrivate; -/// \brief Helper class to write automated tests. It provides a convenient API -/// to load a world file, step simulation and check entities and components. -/// -/// ## Usage -/// -/// // Load a world with a fixture -/// ignition::gazebo::TestFixture fixture("path_to.sdf"); -/// -/// // Register callbacks, for example: -/// fixture.OnPostUpdate([&](const gazebo::UpdateInfo &, -/// const gazebo::EntityComponentManager &_ecm) -/// { -/// // Add expectations here -/// }).Finalize(); -/// // Be sure to call finalize before running the server. -/// -/// // Run the server -/// fixture.Server()->Run(true, 1000, false); -/// -class IGNITION_GAZEBO_VISIBLE TestFixture -{ - /// \brief Constructor - /// \param[in] _path Path to SDF file. - public: explicit TestFixture(const std::string &_path); - - /// \brief Constructor - /// \param[in] _config Server config file - public: explicit TestFixture(const ServerConfig &_config); - - /// \brief Destructor - public: virtual ~TestFixture(); - - /// \brief Wrapper around a system's pre-update callback - /// \param[in] _cb Function to be called every pre-update - /// The _entity and _sdf will correspond to the world entity. - /// \return Reference to self. - public: TestFixture &OnConfigure(std::function &_sdf, - EntityComponentManager &_ecm, - EventManager &_eventMgr)> _cb); - - /// \brief Wrapper around a system's pre-update callback - /// \param[in] _cb Function to be called every pre-update - /// \return Reference to self. - public: TestFixture &OnPreUpdate(std::function _cb); - - /// \brief Wrapper around a system's update callback - /// \param[in] _cb Function to be called every update - /// \return Reference to self. - public: TestFixture &OnUpdate(std::function _cb); - - /// \brief Wrapper around a system's post-update callback - /// \param[in] _cb Function to be called every post-update - /// \return Reference to self. - public: TestFixture &OnPostUpdate(std::function _cb); - - /// \brief Finalize all the functions and add fixture to server. - /// Finalize must be called before running the server, otherwise none of the - /// `On*` functions will be called. - /// The `OnConfigure` callback is called immediately on finalize. - public: TestFixture &Finalize(); - - /// \brief Get pointer to underlying server. - public: std::shared_ptr Server() const; - - /// \internal - /// \brief Pointer to private data. - // TODO(chapulina) Use IGN_UTILS_UNIQUE_IMPL_PTR(dataPtr) when porting to v6 - private: TestFixturePrivate *dataPtr; -}; -} -} -} -#endif +#include +#include diff --git a/include/ignition/gazebo/Types.hh b/include/ignition/gazebo/Types.hh index 7cc00b572e..3179ac04dd 100644 --- a/include/ignition/gazebo/Types.hh +++ b/include/ignition/gazebo/Types.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,93 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_TYPES_HH_ -#define IGNITION_GAZEBO_TYPES_HH_ + */ -#include -#include -#include -#include -#include - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // Forward declarations. - class EntityComponentManager; - - /// \brief Information passed to systems on the update callback. - /// \todo(louise) Update descriptions once reset is supported. - struct UpdateInfo - { - /// \brief Total time elapsed in simulation. This will not increase while - /// paused. - std::chrono::steady_clock::duration simTime{0}; - - /// \brief Total wall clock time elapsed while simulation is running. This - /// will not increase while paused. - std::chrono::steady_clock::duration realTime{0}; - - /// \brief Simulation time handled during a single update. - std::chrono::steady_clock::duration dt{0}; - - /// \brief Total number of elapsed simulation iterations. - // cppcheck-suppress unusedStructMember - uint64_t iterations{0}; - - /// \brief True if simulation is paused, which means the simulation - /// time is not currently running, but systems are still being updated. - /// It is the responsibilty of a system update appropriately based on - /// the status of paused. For example, a physics systems should not - /// update state when paused is true. - // cppcheck-suppress unusedStructMember - bool paused{true}; - }; - - /// \brief Possible states for a component. - enum class ComponentState - { - /// \brief Component value has not changed. - NoChange = 0, - - /// \brief Component value has changed, and is changing periodically. - /// This indicates to systems that it is ok to drop a few samples. - PeriodicChange = 1, - - /// \brief Component value has suffered a one-time change. - /// This indicates to systems that this change must be processed and - /// can't be dropped. - OneTimeChange = 2 - }; - - /// \brief A unique identifier for a component instance. The uniqueness - /// of a ComponentId is scoped to the component's type. - /// \sa ComponentKey. - using ComponentId = int; - - /// \brief A unique identifier for a component type. A component type - /// must be derived from `components::BaseComponent` and can contain plain - /// data or something more complex like `ignition::math::Pose3d`. - using ComponentTypeId = uint64_t; - - /// \brief A key that uniquely identifies, at the global scope, a component - /// instance - using ComponentKey = std::pair; - - /// \brief typedef for query callbacks - using EntityQueryCallback = std::function; - - /// \brief Id that indicates an invalid component. - static const ComponentId kComponentIdInvalid = -1; - - /// \brief Id that indicates an invalid component type. - static const ComponentTypeId kComponentTypeIdInvalid = UINT64_MAX; - } - } -} -#endif +#include +#include diff --git a/include/ignition/gazebo/Util.hh b/include/ignition/gazebo/Util.hh index 2ecfbe6d08..2a2fc349e7 100644 --- a/include/ignition/gazebo/Util.hh +++ b/include/ignition/gazebo/Util.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,246 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_UTIL_HH_ -#define IGNITION_GAZEBO_UTIL_HH_ + */ -#include - -#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" - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // - /// \brief Helper function to compute world pose of an entity - /// \param[in] _entity Entity to get the world pose for - /// \param[in] _ecm Immutable reference to ECM. - /// \return World pose of entity - math::Pose3d IGNITION_GAZEBO_VISIBLE worldPose(const Entity &_entity, - const EntityComponentManager &_ecm); - - /// \brief Helper function to generate scoped name for an entity. - /// \param[in] _entity Entity to get the name for. - /// \param[in] _ecm Immutable reference to ECM. - /// \param[in] _delim Delimiter to put between names, defaults to "/". - /// \param[in] _includePrefix True to include the type prefix before the - /// entity name - std::string IGNITION_GAZEBO_VISIBLE scopedName(const Entity &_entity, - const EntityComponentManager &_ecm, const std::string &_delim = "/", - bool _includePrefix = true); - - /// \brief Helper function to get an entity given its scoped name. - /// The scope may start at any level by default. For example, in this - /// hierarchy: - /// - /// world_name - /// model_name - /// link_name - /// - /// All these names will return the link entity: - /// - /// * world_name::model_name::link_name - /// * model_name::link_name - /// * link_name - /// - /// \param[in] _scopedName Entity's scoped name. - /// \param[in] _ecm Immutable reference to ECM. - /// \param[in] _relativeTo Entity that the scoped name is relative to. The - /// scoped name does not include the name of this entity. If not provided, - /// the scoped name could be relative to any entity. - /// \param[in] _delim Delimiter between names, defaults to "::", it can't - /// be empty. - /// \return All entities that match the scoped name and relative to - /// requirements, or an empty set otherwise. - std::unordered_set IGNITION_GAZEBO_VISIBLE entitiesFromScopedName( - const std::string &_scopedName, const EntityComponentManager &_ecm, - Entity _relativeTo = kNullEntity, - const std::string &_delim = "::"); - - /// \brief Generally, each entity will be of some specific high-level type, - /// such as World, Sensor, Collision, etc, and one type only. - /// The entity type is usually marked by having some component that - /// represents that type, such as `ignition::gazebo::components::Visual`. - /// - /// This function returns the type ID of the given entity's type, which - /// can be checked against different types. For example, if the - /// entity is a model, this will be true: - /// - /// `gazebo::components::Model::typeId == entityTypeId(entity, ecm)` - /// - /// In case the entity isn't of any known type, this will return - /// `ignition::gazebo::kComponentTypeIdInvalid`. - /// - /// In case the entity has more than one type, only one of them will be - /// returned. This is not standard usage. - /// - /// \param[in] _entity Entity to get the type for. - /// \param[in] _ecm Immutable reference to ECM. - /// \return ID of entity's type-defining components. - ComponentTypeId IGNITION_GAZEBO_VISIBLE entityTypeId(const Entity &_entity, - const EntityComponentManager &_ecm); - - /// \brief Generally, each entity will be of some specific high-level type, - /// such as "world", "sensor", "collision", etc, and one type only. - /// - /// This function returns a lowercase string for each type. For example, - /// "light", "actor", etc. - /// - /// In case the entity isn't of any known type, this will return an empty - /// string. - /// - /// In case the entity has more than one type, only one of them will be - /// returned. This is not standard usage. - /// - /// Note that this is different from component type names. - /// - /// \param[in] _entity Entity to get the type for. - /// \param[in] _ecm Immutable reference to ECM. - /// \return ID of entity's type-defining components. - std::string IGNITION_GAZEBO_VISIBLE entityTypeStr(const Entity &_entity, - const EntityComponentManager &_ecm); - - /// \brief Get the world to which the given entity belongs. - /// \param[in] _entity Entity to get the world for. - /// \param[in] _ecm Immutable reference to ECM. - /// \return World entity ID. - Entity IGNITION_GAZEBO_VISIBLE worldEntity(const Entity &_entity, - const EntityComponentManager &_ecm); - - /// \brief Get the first world entity that's found. - /// \param[in] _ecm Immutable reference to ECM. - /// \return World entity ID. - Entity IGNITION_GAZEBO_VISIBLE worldEntity( - const EntityComponentManager &_ecm); - - /// \brief Helper function to remove a parent scope from a given name. - /// This removes the first name found before the delimiter. - /// \param[in] _name Input name possibly generated by scopedName. - /// \param[in] _delim Delimiter between names. - /// \return A new string with the parent scope removed. - std::string IGNITION_GAZEBO_VISIBLE removeParentScope( - const std::string &_name, const std::string &_delim); - - /// \brief Combine a URI and a file path into a full path. - /// If the URI is already a full path or contains a scheme, it won't be - /// modified. - /// If the URI is a relative path, the file path will be prepended. - /// \param[in] _uri URI, which can have a scheme, or be full or relative - /// paths. - /// \param[in] _filePath The path to a file in disk. - /// \return The full path URI. - std::string IGNITION_GAZEBO_VISIBLE asFullPath(const std::string &_uri, - const std::string &_filePath); - - /// \brief Get resource paths based on latest environment variables. - /// \return All paths in the IGN_GAZEBO_RESOURCE_PATH variable. - std::vector IGNITION_GAZEBO_VISIBLE resourcePaths(); - - /// \brief Add resource paths based on latest environment variables. - /// This will update the SDF and Ignition environment variables, and - /// optionally add more paths to the list. - /// \param[in] _paths Optional paths to add. - void IGNITION_GAZEBO_VISIBLE addResourcePaths( - const std::vector &_paths = {}); - - /// \brief Get the top level model of an entity - /// \param[in] _entity Input entity - /// \param[in] _ecm Constant reference to ECM. - /// \return Entity of top level model. If _entity has no top level model, - /// kNullEntity is returned. - ignition::gazebo::Entity IGNITION_GAZEBO_VISIBLE topLevelModel( - const Entity &_entity, const EntityComponentManager &_ecm); - - /// \brief Helper function to generate a valid transport topic, given - /// a list of topics ordered by preference. The generated topic will be, - /// in this order: - /// - /// 1. The first topic unchanged, if valid. - /// 2. A valid version of the first topic, if possible. - /// 3. The second topic unchanged, if valid. - /// 4. A valid version of the second topic, if possible. - /// 5. ... - /// 6. If no valid topics could be generated, return an empty string. - /// - /// \param[in] _topics Topics ordered by preference. - std::string IGNITION_GAZEBO_VISIBLE validTopic( - const std::vector &_topics); - - /// \brief Helper function to "enable" a component (i.e. create it if it - /// doesn't exist) or "disable" a component (i.e. remove it if it exists). - /// \param[in] _ecm Mutable reference to the ECM - /// \param[in] _entity Entity whose component is being enabled - /// \param[in] _enable True to enable (create), false to disable (remove). - /// Defaults to true. - /// \return True if a component was created or removed, false if nothing - /// changed. - template - bool enableComponent(EntityComponentManager &_ecm, - Entity _entity, bool _enable = true) - { - bool changed{false}; - - auto exists = _ecm.Component(_entity); - if (_enable && !exists) - { - _ecm.CreateComponent(_entity, ComponentType()); - changed = true; - } - else if (!_enable && exists) - { - _ecm.RemoveComponent(_entity); - changed = true; - } - return changed; - } - - /// \brief Helper function to get an entity from an entity message. - /// The returned entity is not guaranteed to exist. - /// - /// The message is used as follows: - /// - /// if id not null - /// use id - /// else if name not null and type not null - /// use name + type - /// else - /// error - /// end - /// - /// \param[in] _ecm Entity component manager - /// \param[in] _msg Entity message - /// \return Entity ID, or kNullEntity if a matching entity couldn't be - /// found. - Entity IGNITION_GAZEBO_VISIBLE entityFromMsg( - const EntityComponentManager &_ecm, const msgs::Entity &_msg); - - /// \brief Environment variable holding resource paths. - const std::string kResourcePathEnv{"IGN_GAZEBO_RESOURCE_PATH"}; - - /// \brief Environment variable used by SDFormat to find URIs inside - /// `` - const std::string kSdfPathEnv{"SDF_PATH"}; - - /// \brief Environment variable holding server config paths. - const std::string kServerConfigPathEnv{"IGN_GAZEBO_SERVER_CONFIG_PATH"}; - - /// \brief Environment variable holding paths to custom rendering engine - /// plugins. - const std::string kRenderPluginPathEnv{"IGN_GAZEBO_RENDER_ENGINE_PATH"}; - } - } -} -#endif +#include +#include diff --git a/include/ignition/gazebo/World.hh b/include/ignition/gazebo/World.hh index 1e902ef169..39d9872c0e 100644 --- a/include/ignition/gazebo/World.hh +++ b/include/ignition/gazebo/World.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,177 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_WORLD_HH_ -#define IGNITION_GAZEBO_WORLD_HH_ + */ -#include -#include -#include - -#include -#include - -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // Forward declarations. - class IGNITION_GAZEBO_HIDDEN WorldPrivate; - // - /// \class World World.hh ignition/gazebo/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. - /// All the functions provided here are meant to be used with a world - /// entity. - /// - /// For example, given a world's entity, to find the value of its - /// name component, one could use the entity-component manager (`ecm`) - /// directly as follows: - /// - /// std::string name = ecm.Component(entity)->Data(); - /// - /// Using this class however, the same information can be obtained with - /// a simpler function call: - /// - /// World world(entity); - /// std::string name = world.Name(ecm); - class IGNITION_GAZEBO_VISIBLE World { - /// \brief Constructor - /// \param[in] _entity World entity - public: explicit World(gazebo::Entity _entity = kNullEntity); - - /// \brief Copy constructor - /// \param[in] _world World to copy. - public: World(const World &_world); - - /// \brief Move constructor - /// \param[in] _world World to move. - public: World(World &&_world) noexcept; - - /// \brief Move assignment operator. - /// \param[in] _world World component to move. - /// \return Reference to this. - public: World &operator=(World &&_world) noexcept; - - /// \brief Copy assignment operator. - /// \param[in] _world World to copy. - /// \return Reference to this. - public: World &operator=(const World &_world); - - /// \brief Destructor - public: virtual ~World(); - - /// \brief Get the entity which this World is related to. - /// \return World entity. - public: gazebo::Entity Entity() const; - - /// \brief Check whether this world correctly refers to an entity that - /// has a components::World. - /// \param[in] _ecm Entity-component manager. - /// \return True if it's a valid world in the manager. - public: bool Valid(const EntityComponentManager &_ecm) const; - - /// \brief Get the world's unscoped name. - /// \param[in] _ecm Entity-component manager. - /// \return World's name or nullopt if the entity does not have a - /// components::Name component - public: std::optional Name( - const EntityComponentManager &_ecm) const; - - /// \brief Get the gravity in m/s^2. - /// \param[in] _ecm Entity-component manager. - /// \return Gravity vector or nullopt if the entity does not - /// have a components::Gravity component. - public: std::optional Gravity( - const EntityComponentManager &_ecm) const; - - /// \brief Get the magnetic field in Tesla. - /// \param[in] _ecm Entity-component manager. - /// \return Magnetic field vector or nullopt if the entity does not - /// have a components::MagneticField component. - public: std::optional MagneticField( - const EntityComponentManager &_ecm) const; - - /// \brief Get atmosphere information. - /// \param[in] _ecm Entity-component manager. - /// \return Magnetic field vector or nullopt if the entity does not - /// have a components::Atmosphere component. - public: std::optional Atmosphere( - const EntityComponentManager &_ecm) const; - - /// \brief Get the ID of a light entity which is an immediate child of - /// this world. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _name Light name. - /// \return Light entity. - public: gazebo::Entity LightByName(const EntityComponentManager &_ecm, - const std::string &_name) const; - - /// \brief Get the ID of a actor entity which is an immediate child of - /// this world. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _name Actor name. - /// \return Actor entity. - public: gazebo::Entity ActorByName(const EntityComponentManager &_ecm, - const std::string &_name) const; - - /// \brief Get the ID of a model entity which is an immediate child of - /// this world. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _name Model name. - /// \return Model entity. - public: gazebo::Entity ModelByName(const EntityComponentManager &_ecm, - const std::string &_name) const; - - /// \brief Get all lights which are immediate children of this world. - /// \param[in] _ecm Entity-component manager. - /// \return All lights in this world. - public: std::vector Lights( - const EntityComponentManager &_ecm) const; - - /// \brief Get all actors which are immediate children of this world. - /// \param[in] _ecm Entity-component manager. - /// \return All actors in this world. - public: std::vector Actors( - const EntityComponentManager &_ecm) const; - - /// \brief Get all models which are immediate children of this world. - /// \param[in] _ecm Entity-component manager. - /// \return All models in this world. - public: std::vector Models( - const EntityComponentManager &_ecm) const; - - /// \brief Get the number of lights which are immediate children of this - /// world. - /// \param[in] _ecm Entity-component manager. - /// \return Number of lights in this world. - public: uint64_t LightCount(const EntityComponentManager &_ecm) const; - - /// \brief Get the number of actors which are immediate children of this - /// world. - /// \param[in] _ecm Entity-component manager. - /// \return Number of actors in this world. - public: uint64_t ActorCount(const EntityComponentManager &_ecm) const; - - /// \brief Get the number of models which are immediate children of this - /// world. - /// \param[in] _ecm Entity-component manager. - /// \return Number of models in this world. - public: uint64_t ModelCount(const EntityComponentManager &_ecm) const; - - /// \brief Pointer to private data. - private: std::unique_ptr dataPtr; - }; - } - } -} -#endif +#include +#include diff --git a/include/ignition/gazebo/ackermann-steering-system/Export.hh b/include/ignition/gazebo/ackermann-steering-system/Export.hh new file mode 100644 index 0000000000..94aa7daaca --- /dev/null +++ b/include/ignition/gazebo/ackermann-steering-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/air-pressure-system/Export.hh b/include/ignition/gazebo/air-pressure-system/Export.hh new file mode 100644 index 0000000000..1f404f8f37 --- /dev/null +++ b/include/ignition/gazebo/air-pressure-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/altimeter-system/Export.hh b/include/ignition/gazebo/altimeter-system/Export.hh new file mode 100644 index 0000000000..c276900862 --- /dev/null +++ b/include/ignition/gazebo/altimeter-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/apply-joint-force-system/Export.hh b/include/ignition/gazebo/apply-joint-force-system/Export.hh new file mode 100644 index 0000000000..f572c7f3c1 --- /dev/null +++ b/include/ignition/gazebo/apply-joint-force-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/apply-link-wrench-system/Export.hh b/include/ignition/gazebo/apply-link-wrench-system/Export.hh new file mode 100644 index 0000000000..271c690afb --- /dev/null +++ b/include/ignition/gazebo/apply-link-wrench-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/breadcrumbs-system/Export.hh b/include/ignition/gazebo/breadcrumbs-system/Export.hh new file mode 100644 index 0000000000..62736ea5ee --- /dev/null +++ b/include/ignition/gazebo/breadcrumbs-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/buoyancy-system/Export.hh b/include/ignition/gazebo/buoyancy-system/Export.hh new file mode 100644 index 0000000000..bcb60f30ef --- /dev/null +++ b/include/ignition/gazebo/buoyancy-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/camera-video-recorder-system/Export.hh b/include/ignition/gazebo/camera-video-recorder-system/Export.hh new file mode 100644 index 0000000000..3796fbf62e --- /dev/null +++ b/include/ignition/gazebo/camera-video-recorder-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/collada-world-exporter-system/Export.hh b/include/ignition/gazebo/collada-world-exporter-system/Export.hh new file mode 100644 index 0000000000..6f24741d53 --- /dev/null +++ b/include/ignition/gazebo/collada-world-exporter-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/components.hh b/include/ignition/gazebo/components.hh new file mode 100644 index 0000000000..2e08f047bb --- /dev/null +++ b/include/ignition/gazebo/components.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/components/Actor.hh b/include/ignition/gazebo/components/Actor.hh index aeca817612..9e9a563b79 100644 --- a/include/ignition/gazebo/components/Actor.hh +++ b/include/ignition/gazebo/components/Actor.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,43 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_ACTOR_HH_ -#define IGNITION_GAZEBO_COMPONENTS_ACTOR_HH_ + */ -#include - -#include - -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace serializers -{ - using ActorSerializer = - serializers::ComponentToMsgSerializer; -} - -namespace components -{ - /// \brief This component contains actor source information. For more - /// information on actors, see [SDF's Actor - /// element](http://sdformat.org/spec?ver=1.6&elem=actor). - using Actor = - Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Actor", Actor) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Actuators.hh b/include/ignition/gazebo/components/Actuators.hh index 987e63feca..78be04a165 100644 --- a/include/ignition/gazebo/components/Actuators.hh +++ b/include/ignition/gazebo/components/Actuators.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,33 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_ACTUATORS_HH_ -#define IGNITION_GAZEBO_COMPONENTS_ACTUATORS_HH_ -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains a msgs::Actuators message. This is - /// used for example, to communicate between the MulticopterMotorModel and - /// MulticopterVelocityControl systems - using Actuators = Component; - - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Actuators", Actuators) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/AirPressureSensor.hh b/include/ignition/gazebo/components/AirPressureSensor.hh index 02f825ffd5..0d7d40f7e9 100644 --- a/include/ignition/gazebo/components/AirPressureSensor.hh +++ b/include/ignition/gazebo/components/AirPressureSensor.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,34 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_AIRPRESSURE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_AIRPRESSURE_HH_ + */ -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains an air pressure sensor, - /// sdf::AirPressure, information. - using AirPressureSensor = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.AirPressureSensor", - AirPressureSensor) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Altimeter.hh b/include/ignition/gazebo/components/Altimeter.hh index 2aa05827f0..f4a431429e 100644 --- a/include/ignition/gazebo/components/Altimeter.hh +++ b/include/ignition/gazebo/components/Altimeter.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,33 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_ALTIMETER_HH_ -#define IGNITION_GAZEBO_COMPONENTS_ALTIMETER_HH_ + */ -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains an altimeter sensor, - /// sdf::Altimeter, information. - using Altimeter = - Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Altimeter", Altimeter) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/AngularAcceleration.hh b/include/ignition/gazebo/components/AngularAcceleration.hh index 71c9be1b89..aa01292837 100644 --- a/include/ignition/gazebo/components/AngularAcceleration.hh +++ b/include/ignition/gazebo/components/AngularAcceleration.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,41 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_ANGULARACCELERATION_HH_ -#define IGNITION_GAZEBO_COMPONENTS_ANGULARACCELERATION_HH_ - -#include +#include #include -#include - -#include -#include "ignition/gazebo/components/Component.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains angular acceleration of an entity - /// represented by ignition::math::Vector3d. - using AngularAcceleration = - Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.AngularAcceleration", - AngularAcceleration) - - /// \brief A component type that contains angular acceleration of an entity in - /// the world frame represented by ignition::math::Vector3d. - using WorldAngularAcceleration = - Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.WorldAngularAcceleration", - WorldAngularAcceleration) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/AngularVelocity.hh b/include/ignition/gazebo/components/AngularVelocity.hh index 1005c2a899..1585256c35 100644 --- a/include/ignition/gazebo/components/AngularVelocity.hh +++ b/include/ignition/gazebo/components/AngularVelocity.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,40 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_ANGULARVELOCITY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_ANGULARVELOCITY_HH_ - -#include +#include #include -#include - -#include -#include "ignition/gazebo/components/Component.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains angular velocity of an entity - /// represented by ignition::math::Vector3d. - using AngularVelocity = - Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_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", - WorldAngularVelocity) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/AngularVelocityCmd.hh b/include/ignition/gazebo/components/AngularVelocityCmd.hh index 1a22171456..9f0a95ff71 100644 --- a/include/ignition/gazebo/components/AngularVelocityCmd.hh +++ b/include/ignition/gazebo/components/AngularVelocityCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,40 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_ANGULARVELOCITYCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_ANGULARVELOCITYCMD_HH_ - -#include +#include #include - -#include -#include "ignition/gazebo/components/Component.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains the commanded angular velocity of - /// an entity, in its own frame, represented by ignition::math::Vector3d. - using AngularVelocityCmd = - Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_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) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Atmosphere.hh b/include/ignition/gazebo/components/Atmosphere.hh index dd66848b7a..8f739b8181 100644 --- a/include/ignition/gazebo/components/Atmosphere.hh +++ b/include/ignition/gazebo/components/Atmosphere.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,40 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_ATMOSPHERE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_ATMOSPHERE_HH_ + */ -#include -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace serializers -{ - using AtmosphereSerializer = - serializers::ComponentToMsgSerializer; -} - -namespace components -{ - /// \brief This component holds atmosphere properties of the world. - using Atmosphere = - Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.Atmosphere", Atmosphere) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/AxisAlignedBox.hh b/include/ignition/gazebo/components/AxisAlignedBox.hh index 24226895bb..b33b0957e7 100644 --- a/include/ignition/gazebo/components/AxisAlignedBox.hh +++ b/include/ignition/gazebo/components/AxisAlignedBox.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,43 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_AxisAlignedBox_HH_ -#define IGNITION_GAZEBO_COMPONENTS_AxisAlignedBox_HH_ + */ -#include -#include -#include -#include -#include +#include #include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace serializers -{ - using AxisAlignedBoxSerializer = - serializers::ComponentToMsgSerializer; -} - -namespace components -{ - /// \brief A component type that contains axis aligned box, - /// ignition::math::AxisAlignedBox, information. - /// The axis aligned box is created from collisions in the entity - using AxisAlignedBox = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.AxisAlignedBox", - AxisAlignedBox) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/BatterySoC.hh b/include/ignition/gazebo/components/BatterySoC.hh index 0a384f6f7b..4f2b0d3038 100644 --- a/include/ignition/gazebo/components/BatterySoC.hh +++ b/include/ignition/gazebo/components/BatterySoC.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,29 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_BATTERY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_BATTERY_HH_ + */ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -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) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Camera.hh b/include/ignition/gazebo/components/Camera.hh index b964988692..05a08fac47 100644 --- a/include/ignition/gazebo/components/Camera.hh +++ b/include/ignition/gazebo/components/Camera.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,33 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_CAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CAMERA_HH_ + */ -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains a camera sensor, - /// sdf::Camera, information. - using Camera = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Camera", Camera) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/CanonicalLink.hh b/include/ignition/gazebo/components/CanonicalLink.hh index d2ed5869eb..6dcf94c4a8 100644 --- a/include/ignition/gazebo/components/CanonicalLink.hh +++ b/include/ignition/gazebo/components/CanonicalLink.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,29 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_CANONICALLINK_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CANONICALLINK_HH_ + */ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that identifies an entity as being a canonical link. - using CanonicalLink = Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.CanonicalLink", CanonicalLink) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/CastShadows.hh b/include/ignition/gazebo/components/CastShadows.hh index d5e0f7ce09..6c8c6e4ee3 100644 --- a/include/ignition/gazebo/components/CastShadows.hh +++ b/include/ignition/gazebo/components/CastShadows.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,29 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_CASTSHADOWS_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CASTSHADOWS_HH_ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component used to indicate that an entity casts shadows - /// e.g. visual entities - using CastShadows = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.CastShadows", - CastShadows) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/CenterOfVolume.hh b/include/ignition/gazebo/components/CenterOfVolume.hh index 2096d2d5d0..9ec4f6bd33 100644 --- a/include/ignition/gazebo/components/CenterOfVolume.hh +++ b/include/ignition/gazebo/components/CenterOfVolume.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,33 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_CENTEROFVOLUME_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CENTEROFVOLUME_HH_ + */ -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component for an entity's center of volume. Units are in meters. - /// The Vector3 value indicates center of volume of an entity. The - /// 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", - CenterOfVolume) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/ChildLinkName.hh b/include/ignition/gazebo/components/ChildLinkName.hh index d9e2ff25b6..0c69cbcea8 100644 --- a/include/ignition/gazebo/components/ChildLinkName.hh +++ b/include/ignition/gazebo/components/ChildLinkName.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,30 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_CHILDLINKNAME_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CHILDLINKNAME_HH_ -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component used to indicate that a model is childlinkname (i.e. - /// not moveable). - using ChildLinkName = Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.ChildLinkName", ChildLinkName) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Collision.hh b/include/ignition/gazebo/components/Collision.hh index f35f0e95d9..1acd2f98b3 100644 --- a/include/ignition/gazebo/components/Collision.hh +++ b/include/ignition/gazebo/components/Collision.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,56 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_COLLISION_HH_ -#define IGNITION_GAZEBO_COMPONENTS_COLLISION_HH_ + */ -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace serializers -{ - using CollisionElementSerializer = - serializers::ComponentToMsgSerializer; -} - -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) - - // TODO(anyone) The sdf::Collision DOM object does not yet contain - // surface information. - /// \brief A component that holds the sdf::Collision object. - using CollisionElement = - Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.CollisionElement", - CollisionElement) - - /// \brief A component used to enable customization of contact surface for a - /// collision. The customization itself is done in callback of event - /// CollectContactSurfaceProperties from PhysicsEvents. - using EnableContactSurfaceCustomization = - Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.EnableContactSurfaceCustomization", - EnableContactSurfaceCustomization) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Component.hh b/include/ignition/gazebo/components/Component.hh index bbee6d34c5..cbf751e92e 100644 --- a/include/ignition/gazebo/components/Component.hh +++ b/include/ignition/gazebo/components/Component.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,529 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_COMPONENT_HH_ -#define IGNITION_GAZEBO_COMPONENTS_COMPONENT_HH_ - -#include -#include -#include -#include -#include - -#include +#include #include -#include -#include - -namespace ignition -{ -namespace gazebo -{ -// namespace ignition -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace traits -{ - /// \brief Helper trait to determine if a type is shared_ptr or not - template - struct IsSharedPtr : std::false_type - { - }; - - /// \brief Helper trait to determine if a type is shared_ptr or not - template - struct IsSharedPtr> : std::true_type - { - }; - - /// \brief Type trait that determines if a operator<< is defined on `Stream` - /// and `DataType`, i.e, it checks if the function - /// `Stream& operator<<(Stream&, const DataType&)` exists. - /// Example: - /// \code - /// constexpr bool isDoubleOutStreamable = - /// IsOutStreamable::value - /// \endcode - template - class IsOutStreamable - { - private: template - static auto Test(int _test) - -> decltype(std::declval() - << std::declval(), std::true_type()); - - private: template - static auto Test(...) -> std::false_type; - - public: static constexpr bool value = // NOLINT - decltype(Test(true))::value; - }; - - /// \brief Type trait that determines if a operator>> is defined on `Stream` - /// and `DataType`, i.e, it checks if the function - /// `Stream& operator>>(Stream&, DataType&)` exists. - /// Example: - /// \code - /// constexpr bool isDoubleInStreamable = - /// IsInStreamable::value - /// \endcode - /// - template - class IsInStreamable - { - private: template - static auto Test(int _test) - -> decltype(std::declval() >> std::declval(), - std::true_type()); - - private: template - static auto Test(...) -> std::false_type; - - public: static constexpr bool value = // NOLINT - decltype(Test(0))::value; - }; -} - -namespace serializers -{ - /// \brief Default serializer template to call stream operators only on types - /// that support them. If the stream operator is not available, a warning - /// message is printed. - /// \tparam DataType Type on which the operator will be called. - template - class DefaultSerializer - { - /// Serialization - public: static std::ostream &Serialize(std::ostream &_out, - const DataType &_data) - { - // cppcheck-suppress syntaxError - if constexpr (traits::IsSharedPtr::value) // NOLINT - { - if constexpr (traits::IsOutStreamable::value) - { - _out << *_data; - } - else - { - static bool warned{false}; - if (!warned) - { - ignwarn << "Trying to serialize component with data type [" - << typeid(DataType).name() << "], which doesn't have " - << "`operator<<`. Component will not be serialized." - << std::endl; - warned = true; - } - } - } - else if constexpr (traits::IsOutStreamable::value) - { - _out << _data; - } - else - { - static bool warned{false}; - if (!warned) - { - ignwarn << "Trying to serialize component with data type [" - << typeid(DataType).name() << "], which doesn't have " - << "`operator<<`. Component will not be serialized." - << std::endl; - warned = true; - } - } - return _out; - } - - /// \brief Deserialization - /// \param[in] _in In stream. - /// \param[in] _data Data resulting from deserialization. - public: static std::istream &Deserialize(std::istream &_in, - DataType &_data) - { - if constexpr (traits::IsSharedPtr::value) - { - if constexpr (traits::IsInStreamable::value) - { - _in >> *_data; - } - else - { - static bool warned{false}; - if (!warned) - { - ignwarn << "Trying to deserialize component with data type [" - << typeid(DataType).name() << "], which doesn't have " - << "`operator>>`. Component will not be deserialized." - << std::endl; - warned = true; - } - } - } - else if constexpr (traits::IsInStreamable::value) - { - _in >> _data; - } - else - { - static bool warned{false}; - if (!warned) - { - ignwarn << "Trying to deserialize component with data type [" - << typeid(DataType).name() << "], which doesn't have " - << "`operator>>`. Component will not be deserialized." - << std::endl; - warned = true; - } - } - return _in; - } - }; -} - -namespace components -{ - /// \brief Convenient type to be used by components that don't wrap any data. - /// I.e. they act as tags and their presence is enough to infer something - /// about the entity. - using NoData = std::add_lvalue_reference; -} - -namespace serializers -{ - /// \brief Specialization of DefaultSerializer for NoData - template<> class DefaultSerializer - { - public: static std::ostream &Serialize(std::ostream &_out) - { - _out << "-"; - return _out; - } - - public: static std::istream &Deserialize(std::istream &_in) - { - return _in; - } - }; -} - -namespace components -{ - /// \brief Base class for all components. - class BaseComponent - { - /// \brief Default constructor. - public: BaseComponent() = default; - - /// \brief Default destructor. - public: virtual ~BaseComponent() = default; - - /// \brief Fills a stream with a serialized version of the component. - /// By default, it will leave the stream empty. Derived classes should - /// override this function to support serialization. - /// - /// \param[in] _out Out stream. - public: virtual void Serialize(std::ostream &_out) const - { - // This will avoid a doxygen warning - (void)_out; - static bool warned{false}; - if (!warned) - { - ignwarn << "Trying to serialize component of type [" << this->TypeId() - << "], which hasn't implemented the `Serialize` function. " - << "Component will not be serialized." << std::endl; - warned = true; - } - }; - - /// \brief Fills a component based on a stream with a serialized data. - /// By default, it will do nothing. Derived classes should - /// override this function to support deserialization. - /// - /// \param[in] _in In stream. - public: virtual void Deserialize(std::istream &_in) - { - // This will avoid a doxygen warning - (void)_in; - static bool warned{false}; - if (!warned) - { - ignwarn << "Trying to deserialize component of type [" - << this->TypeId() << "], which hasn't implemented the " - << "`Deserialize` function. Component will not be deserialized." - << std::endl; - warned = true; - } - }; - - /// \brief Returns the unique ID for the component's type. - /// The ID is derived from the name that is manually chosen during the - /// Factory registration and is guaranteed to be the same across compilers - /// and runs. - public: virtual ComponentTypeId TypeId() const = 0; - }; - - /// \brief A component type that wraps any data type. The intention is for - /// this class to be used to create simple components while avoiding a lot of - /// boilerplate code. The Identifier must be a unique type so that type - /// aliases can be used to create new components. However the type does not - /// need to be defined anywhere - /// eg. - /// \code - /// using Static = Component; - /// \endcode - /// - /// Note, however, that this scheme does not have a mechanism to stop someone - /// accidentally defining another component that wraps a bool as such: - /// \code - /// using AnotherComp = Component; - /// \endcode - /// In this case, Static and AnotherComp are exactly the same types and would - /// not be differentiable by the EntityComponentManager. - /// - /// A third template argument can be passed to Component to specify the - /// serializer class to use. If this argument is not provided, Component will - /// use DefaultSerializer where DataType is the first template - /// argument to Component. - /// eg. - /// \code - /// class BoolSerializer; // Defined elsewhere - /// using Static = Component; - /// \endcode - /// - /// \tparam DataType Type of the data being wrapped by this component. - /// \tparam Identifier Unique identifier for the component class, to avoid - /// collision. - /// \tparam Serializer A class that can serialize `DataType`. Defaults to a - /// serializer that uses stream operators `<<` and `>>` on the data if they - /// exist. - template > - class Component : public BaseComponent - { - /// \brief Alias for DataType - public: using Type = DataType; - - /// \brief Default constructor - public: Component() = default; - - /// \brief Constructor - /// \param[in] _data Data to copy - public: explicit Component(DataType _data); - - /// \brief Destructor. - public: ~Component() override = default; - - /// \brief Equality operator. - /// \param[in] _component Component to compare to. - /// \return True if equal. - public: bool operator==(const Component &_component) const; - - /// \brief Inequality operator. - /// \param[in] _component Component to compare to. - /// \return True if different. - public: bool operator!=(const Component &_component) const; - - // Documentation inherited - public: ComponentTypeId TypeId() const override; - - // Documentation inherited - public: void Serialize(std::ostream &_out) const override; - - // Documentation inherited - public: void Deserialize(std::istream &_in) override; - - /// \brief Get the mutable component data. This function will be - /// deprecated in Gazebo 3, replaced by const DataType &Data() const. - /// Use void SetData(const DataType &) to modify data. - /// \return Mutable reference to the actual component information. - /// \todo(nkoenig) Deprecate this function in version 3. - public: DataType &Data(); - - /// \brief Set the data of this component. - /// \param[in] _data New data for this component. - /// \param[in] _eql Equality comparison function. This function should - /// return true if two instances of DataType are equal. - /// \return True if the _eql function returns false. - public: bool SetData(const DataType &_data, - const std::function< - bool(const DataType &, const DataType &)> &_eql); - - /// \brief Get the immutable component data. - /// \return Immutable reference to the actual component information. - public: const DataType &Data() const; - - /// \brief Private data pointer. - private: DataType data; - - /// \brief Unique ID for this component type. This is set through the - /// Factory registration. - public: inline static ComponentTypeId typeId{0}; - - /// \brief Unique name for this component type. This is set through the - /// Factory registration. - public: inline static std::string typeName; - }; - - /// \brief Specialization for components that don't wrap any data. - /// This class to be used to create simple components that represent - /// just a "tag", while avoiding a lot of boilerplate code. The Identifier - /// must be a unique type so that type aliases can be used to create new - /// components. However the type does not need to be defined anywhere eg. - /// - /// using Joint = Component; - /// - template - class Component : public BaseComponent - { - /// \brief Components with no data are always equal to another instance of - /// the same type. - /// \param[in] _component Component to compare to - /// \return True. - public: bool operator==(const Component &_component) const; - - /// \brief Components with no data are always equal to another instance of - /// the same type. - /// \param[in] _component Component to compare to - /// \return False. - public: bool operator!=(const Component &_component) const; - - // Documentation inherited - public: ComponentTypeId TypeId() const override; - - // Documentation inherited - public: void Serialize(std::ostream &_out) const override; - - // Documentation inherited - public: void Deserialize(std::istream &_in) override; - - /// \brief Unique ID for this component type. This is set through the - /// Factory registration. - public: inline static ComponentTypeId typeId{0}; - - /// \brief Unique name for this component type. This is set through the - /// Factory registration. - public: inline static std::string typeName; - }; - - ////////////////////////////////////////////////// - template - Component::Component(DataType _data) - : data(std::move(_data)) - { - } - - ////////////////////////////////////////////////// - template - DataType &Component::Data() - { - return this->data; - } - - ////////////////////////////////////////////////// - template - bool Component::SetData( - const DataType &_data, - const std::function &_eql) - { - bool result = !_eql(_data, this->data); - this->data = _data; - return result; - } - - ////////////////////////////////////////////////// - template - const DataType &Component::Data() const - { - return this->data; - } - - ////////////////////////////////////////////////// - template - bool Component::operator==( - const Component &_component) const - { - return this->data == _component.Data(); - } - - ////////////////////////////////////////////////// - template - bool Component::operator!=( - const Component &_component) const - { - return this->data != _component.Data(); - } - - ////////////////////////////////////////////////// - template - void Component::Serialize( - std::ostream &_out) const - { - Serializer::Serialize(_out, this->Data()); - } - - ////////////////////////////////////////////////// - template - void Component::Deserialize( - std::istream &_in) - { - Serializer::Deserialize(_in, this->Data()); - } - - ////////////////////////////////////////////////// - template - ComponentTypeId Component::TypeId() const - { - return typeId; - } - - ////////////////////////////////////////////////// - template - bool Component::operator==( - const Component &) const - { - return true; - } - - ////////////////////////////////////////////////// - template - bool Component::operator!=( - const Component &) const - { - return false; - } - - ////////////////////////////////////////////////// - template - ComponentTypeId Component::TypeId() const - { - return typeId; - } - - ////////////////////////////////////////////////// - template - void Component::Serialize( - std::ostream &_out) const - { - Serializer::Serialize(_out); - } - - ////////////////////////////////////////////////// - template - void Component::Deserialize( - std::istream &_in) - { - Serializer::Deserialize(_in); - } -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/ContactSensor.hh b/include/ignition/gazebo/components/ContactSensor.hh index f772101579..82ecedef1d 100644 --- a/include/ignition/gazebo/components/ContactSensor.hh +++ b/include/ignition/gazebo/components/ContactSensor.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,30 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_CONTACTSENSOR_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CONTACTSENSOR_HH_ -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief 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", - ContactSensor) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/ContactSensorData.hh b/include/ignition/gazebo/components/ContactSensorData.hh index 29a43a160e..0e55e45f3b 100644 --- a/include/ignition/gazebo/components/ContactSensorData.hh +++ b/include/ignition/gazebo/components/ContactSensorData.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,33 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_CONTACTDATASENSOR_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CONTACTDATASENSOR_HH_ -#include -#include -#include -#include +#include #include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains a list of contacts. - using ContactSensorData = - Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ContactSensorData", - ContactSensorData) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/DepthCamera.hh b/include/ignition/gazebo/components/DepthCamera.hh index c5962964c1..a9ae0f7049 100644 --- a/include/ignition/gazebo/components/DepthCamera.hh +++ b/include/ignition/gazebo/components/DepthCamera.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,33 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_DEPTHCAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_DEPTHCAMERA_HH_ + */ -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains a depth camera sensor, - /// sdf::Camera, information. - using DepthCamera = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.DepthCamera", - DepthCamera) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/DetachableJoint.hh b/include/ignition/gazebo/components/DetachableJoint.hh index 0c4b6ec59d..f27304ace4 100644 --- a/include/ignition/gazebo/components/DetachableJoint.hh +++ b/include/ignition/gazebo/components/DetachableJoint.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,92 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_DETACHABLE_JOINT_HH_ -#define IGNITION_GAZEBO_COMPONENTS_DETACHABLE_JOINT_HH_ -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Data structure to hold information about the parent and child links - /// connected by a detachable joint - struct DetachableJointInfo - { - /// \brief Entity of the parent link - Entity parentLink; - /// \brief Entity of the echild link - Entity childLink; - // \brief Type of joint. Only the "fixed" joint type is currently supported. - std::string jointType = {"fixed"}; - - public: bool operator==(const DetachableJointInfo &_info) const - { - return (this->parentLink == _info.parentLink) && - (this->childLink == _info.childLink) && - (this->jointType == _info.jointType); - } - - public: bool operator!=(const DetachableJointInfo &_info) const - { - return !(*this == _info); - } - }; -} - -namespace serializers -{ - /// \brief Serializer for DetachableJointInfo object - class DetachableJointInfoSerializer - { - /// \brief Serialization for `DetachableJointInfo`. - /// \param[in] _out Output stream. - /// \param[in] _info DetachableJointInfo object to stream - /// \return The stream. - public: static std::ostream &Serialize( - std::ostream &_out, - const components::DetachableJointInfo &_info) - { - _out << _info.parentLink << " " << _info.childLink << " " - << _info.jointType; - return _out; - } - - /// \brief Deserialization for `std::set`. - /// \param[in] _in Input stream. - /// \param[in] _info DetachableJointInfo object to populate - /// \return The stream. - public: static std::istream &Deserialize( - std::istream &_in, components::DetachableJointInfo &_info) - { - _in >> _info.parentLink >> _info.childLink >> _info.jointType; - return _in; - } - }; -} - -namespace components -{ - /// \brief A component that identifies an entity as being a detachable joint. - /// It also contains additional information about the joint. - using DetachableJoint = - Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.DetachableJoint", - DetachableJoint) -} -} -} -} - -#endif - diff --git a/include/ignition/gazebo/components/ExternalWorldWrenchCmd.hh b/include/ignition/gazebo/components/ExternalWorldWrenchCmd.hh index 018ed4fd51..b93046b043 100644 --- a/include/ignition/gazebo/components/ExternalWorldWrenchCmd.hh +++ b/include/ignition/gazebo/components/ExternalWorldWrenchCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,39 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_EXTERNALWORLDWRENCHCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_EXTERNALWORLDWRENCHCMD_HH_ -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains the external wrench to be applied on - /// an entity expressed in the world frame and represented by - /// ignition::msgs::Wrench. - /// Currently this is used for applying wrenches on links. Although the - /// msg::Wrench type has a force_offset member, the value is currently - /// ignored. Instead, the force is applied at the link origin. - /// The wrench uses SI units (N for force and Nâ‹…m for torque). - using ExternalWorldWrenchCmd = - Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ExternalWorldWrenchCmd", - ExternalWorldWrenchCmd) -} -} -} -} - -#endif - diff --git a/include/ignition/gazebo/components/Factory.hh b/include/ignition/gazebo/components/Factory.hh index 01ef49694d..61236250bb 100644 --- a/include/ignition/gazebo/components/Factory.hh +++ b/include/ignition/gazebo/components/Factory.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,340 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_FACTORY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_FACTORY_HH_ + */ -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include +#include #include -#include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A base class for an object responsible for creating components. - class IGNITION_GAZEBO_VISIBLE ComponentDescriptorBase - { - /// \brief Destructor - public: virtual ~ComponentDescriptorBase() = default; - - /// \brief Create an instance of a Component. - /// \return Pointer to a component. - public: virtual std::unique_ptr Create() const = 0; - }; - - /// \brief A class for an object responsible for creating components. - /// \tparam ComponentTypeT type of component to describe. - template - class IGNITION_GAZEBO_VISIBLE ComponentDescriptor - : public ComponentDescriptorBase - { - /// \brief Create an instance of a ComponentTypeT Component. - /// \return Pointer to a component. - public: std::unique_ptr Create() const override - { - return std::make_unique(); - } - }; - - /// \brief A base class for an object responsible for creating storages. - class IGNITION_GAZEBO_VISIBLE StorageDescriptorBase - { - /// \brief Destructor - public: virtual ~StorageDescriptorBase() = default; - - /// \brief Create an instance of a storage. - /// \return Pointer to a storage. - public: virtual std::unique_ptr Create() const = 0; - }; - - /// \brief A class for an object responsible for creating storages. - /// \tparam ComponentTypeT type of component that the storage will hold. - template - class IGNITION_GAZEBO_VISIBLE StorageDescriptor - : public StorageDescriptorBase - { - /// \brief Create an instance of a storage that holds ComponentTypeT - /// components. - /// \return Pointer to a component. - public: std::unique_ptr Create() const override - { - return std::make_unique>(); - } - }; - - /// \brief A factory that generates a component based on a string type. - class IGNITION_GAZEBO_VISIBLE Factory - : public ignition::common::SingletonT - { - /// \brief Register a component so that the factory can create instances - /// of the component and its storage based on an ID. - /// \param[in] _type Type of component to register. - /// \param[in] _compDesc Object to manage the creation of ComponentTypeT - /// objects. - /// \param[in] _storageDesc Object to manage the creation of storages for - /// objects of type ComponentTypeT. - /// \tparam ComponentTypeT Type of component to register. - public: template - void Register(const std::string &_type, ComponentDescriptorBase *_compDesc, - StorageDescriptorBase *_storageDesc) - { - // Every time a plugin which uses a component type is loaded, it attempts - // to register it again, so we skip it. - if (ComponentTypeT::typeId != 0) - { - return; - } - - auto typeHash = ignition::common::hash64(_type); - - // Initialize static member variable - we need to set these - // static members for every shared lib that uses the component, but we - // only add them to the maps below once. - ComponentTypeT::typeId = typeHash; - ComponentTypeT::typeName = _type; - - // Check if component has already been registered by another library - auto runtimeName = typeid(ComponentTypeT).name(); - auto runtimeNameIt = this->runtimeNamesById.find(typeHash); - if (runtimeNameIt != this->runtimeNamesById.end()) - { - // Warn user if type was previously registered with a different name. - // We're leaving the ID set in case this is a false difference across - // libraries. - if (runtimeNameIt->second != runtimeName) - { - std::cerr - << "Registered components of different types with same name: type [" - << runtimeNameIt->second << "] and type [" << runtimeName - << "] with name [" << _type << "]. Second type will not work." - << std::endl; - } - return; - } - - // This happens at static initialization time, so we can't use common - // console - std::string debugEnv; - ignition::common::env("IGN_DEBUG_COMPONENT_FACTORY", debugEnv); - if (debugEnv == "true") - { - std::cout << "Registering [" << ComponentTypeT::typeName << "]" - << std::endl; - } - - // Keep track of all types - this->compsById[ComponentTypeT::typeId] = _compDesc; - this->storagesById[ComponentTypeT::typeId] = _storageDesc; - namesById[ComponentTypeT::typeId] = ComponentTypeT::typeName; - runtimeNamesById[ComponentTypeT::typeId] = runtimeName; - } - - /// \brief Unregister a component so that the factory can't create instances - /// of the component or its storage anymore. - /// \tparam ComponentTypeT Type of component to unregister. - public: template - void Unregister() - { - this->Unregister(ComponentTypeT::typeId); - - ComponentTypeT::typeId = 0; - } - - /// \brief Unregister a component so that the factory can't create instances - /// of the component or its storage anymore. - /// \details This function will not reset the `typeId` static variable - /// within the component type itself. Prefer using the templated - /// `Unregister` function when possible. - /// \param[in] _typeId Type of component to unregister. - public: void Unregister(ComponentTypeId _typeId) - { - // Not registered - if (_typeId == 0) - { - return; - } - - { - auto it = this->compsById.find(_typeId); - if (it != this->compsById.end()) - { - delete it->second; - this->compsById.erase(it); - } - } - - { - auto it = this->storagesById.find(_typeId); - if (it != this->storagesById.end()) - { - delete it->second; - this->storagesById.erase(it); - } - } - - { - auto it = namesById.find(_typeId); - if (it != namesById.end()) - { - namesById.erase(it); - } - } - - { - auto it = runtimeNamesById.find(_typeId); - if (it != runtimeNamesById.end()) - { - runtimeNamesById.erase(it); - } - } - } - - /// \brief Create a new instance of a component. - /// \return Pointer to a component. Null if the component - /// type could not be handled. - /// \tparam ComponentTypeT component type requested - public: template - std::unique_ptr New() - { - return std::unique_ptr(static_cast( - this->New(ComponentTypeT::typeId).release())); - } - - /// \brief Create a new instance of a component. - /// \param[in] _type Component id to create. - /// \return Pointer to a component. Null if the component - /// type could not be handled. - public: std::unique_ptr New( - const ComponentTypeId &_type) - { - // Create a new component if a FactoryFn has been assigned to this type. - std::unique_ptr comp; - auto it = this->compsById.find(_type); - if (it != this->compsById.end() && nullptr != it->second) - comp = it->second->Create(); - - return comp; - } - - /// \brief Create a new instance of a component storage. - /// \param[in] _typeId Type of component which the storage will hold. - /// \return Pointer to a storage. Null if the component type could not be - /// handled. - public: std::unique_ptr NewStorage( - const ComponentTypeId &_typeId) - { - std::unique_ptr storage; - auto it = this->storagesById.find(_typeId); - if (it != this->storagesById.end() && nullptr != it->second) - storage = it->second->Create(); - - return storage; - } - - /// \brief Get all the registered component types by ID. - /// return Vector of component IDs. - public: std::vector TypeIds() const - { - std::vector types; - - // Return the list of all known component types. - for (const auto &comp : this->compsById) - types.push_back(comp.first); - - return types; - } - - /// \brief Check if a component type has been registered. - /// return True if registered. - public: bool HasType(ComponentTypeId _typeId) - { - return this->compsById.find(_typeId) != this->compsById.end(); - } - - /// \brief Get a component's type name given its type ID. - /// return Unique component name. - public: std::string Name(ComponentTypeId _typeId) const - { - if (this->namesById.find(_typeId) != this->namesById.end()) - return namesById.at(_typeId); - - return ""; - } - - /// \brief A list of registered components where the key is its id. - /// - /// Note about compsByName and compsById. The maps store pointers as the - /// values, but never cleans them up, which may (at first glance) seem like - /// incorrect behavior. This is not a mistake. Since ComponentDescriptors - /// are created at the point in the code where components are defined, this - /// generally ends up in a shared library that will be loaded at runtime. - /// - /// Because this and the plugin loader both use static variables, and the - /// order of static initialization and destruction are not guaranteed, this - /// can lead to a scenario where the shared library is unloaded (with the - /// ComponentDescriptor), but the Factory still exists. For this reason, - /// we just keep a pointer, which will dangle until the program is shutdown. - private: std::map compsById; - - /// \brief A list of registered storages where the key is its component's - /// type id. - private: std::map storagesById; - - /// \brief A list of IDs and their equivalent names. - /// \details Make it non-static on version 2.0. - public: inline static std::map namesById; - - /// \brief Keep track of the runtime names for types and warn the user if - /// they try to register different types with the same typeName. - /// \details Make it non-static on version 2.0. - public: inline static std::map - runtimeNamesById; - }; - - /// \brief Static component registration macro. - /// - /// Use this macro to register components. - /// - /// \details Each time a plugin which uses a component is loaded, it tries to - /// register the component again, so we prevent that. - /// \param[in] _compType Component type name. - /// \param[in] _classname Class name for component. - #define IGN_GAZEBO_REGISTER_COMPONENT(_compType, _classname) \ - class IGNITION_GAZEBO_VISIBLE IgnGazeboComponents##_classname \ - { \ - public: IgnGazeboComponents##_classname() \ - { \ - if (_classname::typeId != 0) \ - return; \ - using namespace ignition;\ - using Desc = gazebo::components::ComponentDescriptor<_classname>; \ - using StorageDesc = gazebo::components::StorageDescriptor<_classname>; \ - gazebo::components::Factory::Instance()->Register<_classname>(\ - _compType, new Desc(), new StorageDesc());\ - } \ - }; \ - static IgnGazeboComponents##_classname\ - IgnitionGazeboComponentsInitializer##_classname; -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Geometry.hh b/include/ignition/gazebo/components/Geometry.hh index 5a8b75835e..4f1422854d 100644 --- a/include/ignition/gazebo/components/Geometry.hh +++ b/include/ignition/gazebo/components/Geometry.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,43 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_GEOMETRY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_GEOMETRY_HH_ + */ -#include - -#include - -#include -#include -#include +#include #include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace serializers -{ - using GeometrySerializer = - serializers::ComponentToMsgSerializer; -} - -namespace components -{ - /// \brief This component holds an entity's geometry. - using Geometry = Component; - - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Geometry", Geometry) - -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/GpuLidar.hh b/include/ignition/gazebo/components/GpuLidar.hh index ba1f50f047..27d948bb8a 100644 --- a/include/ignition/gazebo/components/GpuLidar.hh +++ b/include/ignition/gazebo/components/GpuLidar.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,31 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_GPU_LIDAR_HH_ -#define IGNITION_GAZEBO_COMPONENTS_GPU_LIDAR_HH_ + */ -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains a GPU Lidar sensor, - /// sdf::Lidar, information. - using GpuLidar = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.GpuLidar", GpuLidar) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/Gravity.hh b/include/ignition/gazebo/components/Gravity.hh index bceedf278a..9f3b9b74ec 100644 --- a/include/ignition/gazebo/components/Gravity.hh +++ b/include/ignition/gazebo/components/Gravity.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,31 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_GRAVITY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_GRAVITY_HH_ - -#include + */ +#include #include -#include - -#include -#include "ignition/gazebo/components/Component.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Store the gravity acceleration. - using Gravity = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Gravity", Gravity) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/Imu.hh b/include/ignition/gazebo/components/Imu.hh index fbd023c345..87d126ac37 100644 --- a/include/ignition/gazebo/components/Imu.hh +++ b/include/ignition/gazebo/components/Imu.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,34 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_IMU_HH_ -#define IGNITION_GAZEBO_COMPONENTS_IMU_HH_ - -#include + */ +#include #include -#include - -#include -#include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains an IMU sensor, - /// sdf::IMU, information. - using Imu = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Imu", Imu) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/Inertial.hh b/include/ignition/gazebo/components/Inertial.hh index 5f467f05c1..ea769736b1 100644 --- a/include/ignition/gazebo/components/Inertial.hh +++ b/include/ignition/gazebo/components/Inertial.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,39 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_INERTIAL_HH_ -#define IGNITION_GAZEBO_COMPONENTS_INERTIAL_HH_ + */ -#include -#include -#include -#include -#include +#include #include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace serializers -{ - using InertialSerializer = - serializers::ComponentToMsgSerializer; -} - -namespace components -{ - /// \brief This component holds an entity's inertial. - using Inertial = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Inertial", Inertial) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Joint.hh b/include/ignition/gazebo/components/Joint.hh index effb4520ef..9911dd75d2 100644 --- a/include/ignition/gazebo/components/Joint.hh +++ b/include/ignition/gazebo/components/Joint.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,28 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINT_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINT_HH_ + */ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that identifies an entity as being a joint. - using Joint = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Joint", Joint) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/JointAxis.hh b/include/ignition/gazebo/components/JointAxis.hh index 5bfc5885c7..05fe8bfcff 100644 --- a/include/ignition/gazebo/components/JointAxis.hh +++ b/include/ignition/gazebo/components/JointAxis.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,45 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTAXIS_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTAXIS_HH_ -#include -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace serializers -{ - using JointAxisSerializer = - serializers::ComponentToMsgSerializer; -} -namespace components -{ - /// \brief A component that contains the joint axis . This is a simple wrapper - /// around sdf::JointAxis - using JointAxis = Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_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) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/JointEffortLimitsCmd.hh b/include/ignition/gazebo/components/JointEffortLimitsCmd.hh index b8b9217974..0055a16e7c 100644 --- a/include/ignition/gazebo/components/JointEffortLimitsCmd.hh +++ b/include/ignition/gazebo/components/JointEffortLimitsCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,47 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTEFFORTLIMITSCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTEFFORTLIMITSCMD_HH_ -#include -#include - -#include -#include -#include +#include #include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - -namespace components -{ - -/// \brief Command for setting effort limits of a joint. Data are a vector -/// with a Vector2 for each DOF. The X() component of the Vector2 specifies -/// the minimum effort limit, the Y() component stands for maximum limit. -/// Set to +-infinity to disable the limits. -/// \note It is expected that the physics plugin reads this component and -/// sets the limit to the dynamics engine. After setting it, the data of this -/// component will be cleared (i.e. the vector will have length zero). -using JointEffortLimitsCmd = Component< - std::vector, - class JointEffortLimitsCmdTag, - serializers::VectorSerializer ->; - -IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointEffortLimitsCmd", JointEffortLimitsCmd) -} - -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/JointForce.hh b/include/ignition/gazebo/components/JointForce.hh index 2152d25d98..2478809360 100644 --- a/include/ignition/gazebo/components/JointForce.hh +++ b/include/ignition/gazebo/components/JointForce.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,33 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTFORCE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTFORCE_HH_ -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Force applied to a joint in SI units (Nm for revolute, N for - /// prismatic). - using JointForce = Component, class JointForceTag, - serializers::VectorDoubleSerializer>; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointForce", JointForce) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/JointForceCmd.hh b/include/ignition/gazebo/components/JointForceCmd.hh index ffcee4c4df..eab7568629 100644 --- a/include/ignition/gazebo/components/JointForceCmd.hh +++ b/include/ignition/gazebo/components/JointForceCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,33 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTFORCECMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTFORCECMD_HH_ -#include - -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Commanded joint forces (or torques) to be applied to a joint - /// in SI units (Nm for revolute, N for prismatic). The component wraps a - /// 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", - JointForceCmd) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/JointPosition.hh b/include/ignition/gazebo/components/JointPosition.hh index f215b931e9..6113013778 100644 --- a/include/ignition/gazebo/components/JointPosition.hh +++ b/include/ignition/gazebo/components/JointPosition.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,34 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTPOSITION_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTPOSITION_HH_ -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Joint positions in SI units (rad for revolute, m for prismatic). - /// The component wraps a std::vector of size equal to the degrees of freedom - /// of the joint. - using JointPosition = Component, class JointPositionTag, - serializers::VectorDoubleSerializer>; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointPosition", JointPosition) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/JointPositionLimitsCmd.hh b/include/ignition/gazebo/components/JointPositionLimitsCmd.hh index 775937fbff..d98d7c62f6 100644 --- a/include/ignition/gazebo/components/JointPositionLimitsCmd.hh +++ b/include/ignition/gazebo/components/JointPositionLimitsCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,45 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTPOSITIONLIMITSCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTPOSITIONLIMITSCMD_HH_ -#include -#include - -#include -#include -#include +#include #include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - -namespace components -{ -/// \brief Command for setting position limits of a joint. Data are a vector -/// with a Vector2 for each DOF. The X() component of the Vector2 specifies -/// the minimum positional limit, the Y() component stands for maximum limit. -/// Set to +-infinity to disable the limits. -/// \note It is expected that the physics plugin reads this component and -/// sets the limit to the dynamics engine. After setting it, the data of this -/// component will be cleared (i.e. the vector will have length zero). -using JointPositionLimitsCmd = Component< - std::vector, - class JointPositionLimitsCmdTag, - serializers::VectorSerializer ->; - -IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointPositionLimitsCmd", JointPositionLimitsCmd) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/JointPositionReset.hh b/include/ignition/gazebo/components/JointPositionReset.hh index aee79983b1..dbad467a07 100644 --- a/include/ignition/gazebo/components/JointPositionReset.hh +++ b/include/ignition/gazebo/components/JointPositionReset.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,36 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTPOSITIONRESET_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTPOSITIONRESET_HH_ -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Joint positions in SI units (rad for revolute, m for prismatic). - /// - /// The component wraps a std::vector of size equal to the degrees of freedom - /// of the joint. - using JointPositionReset = Component, - class JointPositionResetTag, - serializers::VectorDoubleSerializer>; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointPositionReset", JointPositionReset) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/JointType.hh b/include/ignition/gazebo/components/JointType.hh index 1d63995ccf..517330c4e2 100644 --- a/include/ignition/gazebo/components/JointType.hh +++ b/include/ignition/gazebo/components/JointType.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,61 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTTYPE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTTYPE_HH_ -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace serializers -{ - class JointTypeSerializer - { - /// \brief Serialization for `sdf::JointType`. - /// \param[in] _out Output stream. - /// \param[in] _type JointType to stream - /// \return The stream. - public: static std::ostream &Serialize(std::ostream &_out, - const sdf::JointType &_type) - { - _out << static_cast(_type); - return _out; - } - - /// \brief Deserialization for `sdf::JointType`. - /// \param[in] _in Input stream. - /// \param[out] _type JointType to populate - /// \return The stream. - public: static std::istream &Deserialize(std::istream &_in, - sdf::JointType &_type) - { - int type; - _in >> type; - _type = sdf::JointType(type); - return _in; - } - }; -} -namespace components -{ - /// \brief A component that contains the joint type. This is a simple wrapper - /// around sdf::JointType - using JointType = Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointType", JointType) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/JointVelocity.hh b/include/ignition/gazebo/components/JointVelocity.hh index 7b0867c383..338bbb4b9f 100644 --- a/include/ignition/gazebo/components/JointVelocity.hh +++ b/include/ignition/gazebo/components/JointVelocity.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,33 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTVELOCITY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTVELOCITY_HH_ -#include - -#include -#include -#include +#include #include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Base class which can be extended to add serialization - using JointVelocity = Component, class JointVelocityTag, - serializers::VectorDoubleSerializer>; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointVelocity", JointVelocity) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/JointVelocityCmd.hh b/include/ignition/gazebo/components/JointVelocityCmd.hh index d37b3b263d..b5ba6d88d8 100644 --- a/include/ignition/gazebo/components/JointVelocityCmd.hh +++ b/include/ignition/gazebo/components/JointVelocityCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,35 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTVELOCITYCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTVELOCITYCMD_HH_ -#include - -#include -#include -#include +#include #include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Base class which can be extended to add serialization - using JointVelocityCmd = - Component, class JointVelocityCmdTag, - serializers::VectorDoubleSerializer>; - - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointVelocityCmd", JointVelocityCmd) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/JointVelocityLimitsCmd.hh b/include/ignition/gazebo/components/JointVelocityLimitsCmd.hh index e85905095f..deb2f0bdee 100644 --- a/include/ignition/gazebo/components/JointVelocityLimitsCmd.hh +++ b/include/ignition/gazebo/components/JointVelocityLimitsCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,45 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTVELOCITYLIMITSCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTVELOCITYLIMITSCMD_HH_ -#include -#include - -#include -#include -#include +#include #include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - -namespace components -{ -/// \brief Command for setting velocity limits of a joint. Data are a vector -/// with a Vector2 for each DOF. The X() component of the Vector2 specifies -/// the minimum velocity limit, the Y() component stands for maximum limit. -/// Set to +-infinity to disable the limits. -/// \note It is expected that the physics plugin reads this component and -/// sets the limit to the dynamics engine. After setting it, the data of this -/// component will be cleared (i.e. the vector will have length zero). -using JointVelocityLimitsCmd = Component< - std::vector, - class JointVelocityLimitsCmdTag, - serializers::VectorSerializer ->; - -IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointVelocityLimitsCmd", JointVelocityLimitsCmd) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/JointVelocityReset.hh b/include/ignition/gazebo/components/JointVelocityReset.hh index f4cb92e015..79abfa801c 100644 --- a/include/ignition/gazebo/components/JointVelocityReset.hh +++ b/include/ignition/gazebo/components/JointVelocityReset.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,37 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTVELOCITYRESET_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTVELOCITYRESET_HH_ -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Joint velocities in SI units - /// (rad/s for revolute, m/s for prismatic). - /// - /// The component wraps a std::vector of size equal to the degrees of freedom - /// of the joint. - using JointVelocityReset = Component, - class JointVelocityResetTag, - serializers::VectorDoubleSerializer>; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.JointVelocityReset", JointVelocityReset) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/LaserRetro.hh b/include/ignition/gazebo/components/LaserRetro.hh index 75d1145e92..256b122f92 100644 --- a/include/ignition/gazebo/components/LaserRetro.hh +++ b/include/ignition/gazebo/components/LaserRetro.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,28 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LASERRETRO_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LASERRETRO_HH_ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component used to indicate an lidar reflective value - using LaserRetro = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LaserRetro", - LaserRetro) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Level.hh b/include/ignition/gazebo/components/Level.hh index e95a6dc30c..2c3812264e 100644 --- a/include/ignition/gazebo/components/Level.hh +++ b/include/ignition/gazebo/components/Level.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,33 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LEVEL_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LEVEL_HH_ +#include #include -#include - -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Component.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief This component identifies an entity as being a level. - using Level = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_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", - DefaultLevel) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/LevelBuffer.hh b/include/ignition/gazebo/components/LevelBuffer.hh index 3cea1172e4..faa59fedf0 100644 --- a/include/ignition/gazebo/components/LevelBuffer.hh +++ b/include/ignition/gazebo/components/LevelBuffer.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,30 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LEVELBUFFER_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LEVELBUFFER_HH_ +#include #include -#include - -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Component.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that holds the buffer setting of a level's geometry - using LevelBuffer = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LevelBuffer", - LevelBuffer) -} -} -} -} -#endif - diff --git a/include/ignition/gazebo/components/LevelEntityNames.hh b/include/ignition/gazebo/components/LevelEntityNames.hh index 9c45bc31a2..5dc8d2ee8f 100644 --- a/include/ignition/gazebo/components/LevelEntityNames.hh +++ b/include/ignition/gazebo/components/LevelEntityNames.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,76 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LEVELENTITYNAMES_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LEVELENTITYNAMES_HH_ -#include -#include -#include +#include #include -#include - -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Component.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace serializers -{ - class LevelEntityNamesSerializer - { - /// \brief Serialization for `std::set`. - /// \param[in] _out Output stream. - /// \param[in] _set Set to stream - /// \return The stream. - public: static std::ostream &Serialize(std::ostream &_out, - const std::set &_set) - { - for (const auto &entity : _set) - { - _out << entity << " "; - } - return _out; - } - - /// \brief Deserialization for `std::set`. - /// \param[in] _in Input stream. - /// \param[out] _set Set to populate - /// \return The stream. - public: static std::istream &Deserialize(std::istream &_in, - std::set &_set) - { - _in.setf(std::ios_base::skipws); - - _set.clear(); - - for (auto it = std::istream_iterator(_in); - it != std::istream_iterator(); ++it) - { - _set.insert(*it); - } - return _in; - } - }; -} - -namespace components -{ - /// \brief A component that holds a list of names of entities to be loaded in - /// a level. - using LevelEntityNames = - Component, class LevelEntityNamesTag, - serializers::LevelEntityNamesSerializer>; - - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LevelEntityNames", - LevelEntityNames) -} -} -} -} -#endif - diff --git a/include/ignition/gazebo/components/Lidar.hh b/include/ignition/gazebo/components/Lidar.hh index 770c4b9664..7f058d4072 100644 --- a/include/ignition/gazebo/components/Lidar.hh +++ b/include/ignition/gazebo/components/Lidar.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,31 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_LIDAR_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LIDAR_HH_ + */ -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains a Lidar sensor, - /// sdf::Lidar, information. - using Lidar = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Lidar", Lidar) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/Light.hh b/include/ignition/gazebo/components/Light.hh index 13964b35ef..d515ccf1bd 100644 --- a/include/ignition/gazebo/components/Light.hh +++ b/include/ignition/gazebo/components/Light.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,43 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_LIGHT_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LIGHT_HH_ + */ -#include - -#include - -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace serializers -{ - using LightSerializer = - serializers::ComponentToMsgSerializer; -} - -namespace components -{ - /// \brief This component contains light source information. For more - /// information on lights, see [SDF's Light - /// element](http://sdformat.org/spec?ver=1.6&elem=light). - using Light = - Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Light", Light) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/LinearAcceleration.hh b/include/ignition/gazebo/components/LinearAcceleration.hh index 23cf1c87fc..c48a5f9e18 100644 --- a/include/ignition/gazebo/components/LinearAcceleration.hh +++ b/include/ignition/gazebo/components/LinearAcceleration.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,40 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LINEARACCELERATION_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LINEARACCELERATION_HH_ - -#include +#include #include -#include - -#include -#include "ignition/gazebo/components/Component.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains linear acceleration of an entity - /// represented by ignition::math::Vector3d. - using LinearAcceleration = - Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_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", - WorldLinearAcceleration) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/LinearVelocity.hh b/include/ignition/gazebo/components/LinearVelocity.hh index 3fc93cf5ec..193a76aa54 100644 --- a/include/ignition/gazebo/components/LinearVelocity.hh +++ b/include/ignition/gazebo/components/LinearVelocity.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,37 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LINEARVELOCITY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LINEARVELOCITY_HH_ -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains linear velocity of an entity - /// represented by ignition::math::Vector3d. - using LinearVelocity = Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_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) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/LinearVelocityCmd.hh b/include/ignition/gazebo/components/LinearVelocityCmd.hh index cf03bea0ce..662cfa3bf6 100644 --- a/include/ignition/gazebo/components/LinearVelocityCmd.hh +++ b/include/ignition/gazebo/components/LinearVelocityCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,42 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LINEARVELOCITYCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LINEARVELOCITYCMD_HH_ - -#include +#include #include - -#include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - // \brief A component type that contains the commanded linear velocity of an - /// entity represented by ignition::math::Vector3d, expressed in the entity's - /// frame. - using LinearVelocityCmd = Component< - math::Vector3d, class LinearVelocityCmdTag>; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_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 - /// frame. - using WorldLinearVelocityCmd = - Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.WorldLinearVelocityCmd", WorldLinearVelocityCmd) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/LinearVelocitySeed.hh b/include/ignition/gazebo/components/LinearVelocitySeed.hh index 1bb69b905a..826b73e6a7 100644 --- a/include/ignition/gazebo/components/LinearVelocitySeed.hh +++ b/include/ignition/gazebo/components/LinearVelocitySeed.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,42 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LINEARVELOCITYSEED_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LINEARVELOCITYSEED_HH_ -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains linear velocity seed of an entity - /// expressed in the local frame of the entity and represented by - /// ignition::math::Vector3d. This seed can used to generate linear velocities - /// by applying transformations and adding noise. - using LinearVelocitySeed = - Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LinearVelocitySeed", - LinearVelocitySeed) - - /// \brief A component type that contains linear velocity seed of an entity in - /// the world frame represented by ignition::math::Vector3d. This seed can - /// used to generate linear velocities by applying transformations and adding - /// noise. - using WorldLinearVelocitySeed = - Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WorldLinearVelocitySeed", - WorldLinearVelocitySeed) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Link.hh b/include/ignition/gazebo/components/Link.hh index 433dac2ef5..ff2518e68f 100644 --- a/include/ignition/gazebo/components/Link.hh +++ b/include/ignition/gazebo/components/Link.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,28 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_LINK_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LINK_HH_ + */ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that identifies an entity as being a link. - using Link = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Link", Link) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/LogPlaybackStatistics.hh b/include/ignition/gazebo/components/LogPlaybackStatistics.hh index 973eec3857..5d6718aa98 100644 --- a/include/ignition/gazebo/components/LogPlaybackStatistics.hh +++ b/include/ignition/gazebo/components/LogPlaybackStatistics.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,36 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_LogPlaybackStatistics_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LogPlaybackStatistics_HH_ + */ -#include -#include -#include -#include +#include #include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains log playback, - /// systems::LogPlayback, information. - /// The log playback is created from world entity upon the playback plugin - /// being loaded - using LogPlaybackStatistics = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LogPlaybackStatistics", - LogPlaybackStatistics) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/LogicalAudio.hh b/include/ignition/gazebo/components/LogicalAudio.hh index 7b465e6178..579effe05c 100644 --- a/include/ignition/gazebo/components/LogicalAudio.hh +++ b/include/ignition/gazebo/components/LogicalAudio.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,313 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_LOGICALAUDIO_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LOGICALAUDIO_HH_ + */ -#include -#include -#include -#include -#include - -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace logical_audio -{ - /// \brief Audio source attenuation functions. - /// AttenuationFunction::Undefined is used to indicate that an - /// attenuation function has not been defined yet. - enum class AttenuationFunction { LINEAR, UNDEFINED }; - - /// \brief Audio source attenuation shapes. - /// AttenuationShape::Undefined is used to indicate that an - /// attenuation shape has not been defined yet. - enum class AttenuationShape { SPHERE, UNDEFINED }; - - /// \brief Properties of a logical audio source. - /// A source also has a pose, which can be stored as a component of a - /// source entity via ignition::gazebo::components::Pose - struct Source - { - /// \brief The source's id - unsigned int id; - - /// \brief The source's attenuation function - logical_audio::AttenuationFunction attFunc; - - /// \brief The source's attenuation shape - logical_audio::AttenuationShape attShape; - - /// \brief The source's inner radius, which should be >= 0 - double innerRadius; - - /// \brief The source's falloff distance, which should be - /// greater than Source::innerRadius - double falloffDistance; - - /// \brief The source's emission volume, which should be - /// between 0.0 (0% volume) and 1.0 (100% volume) - double emissionVolume; - - public: bool operator==(const Source &_source) const - { - return this->id == _source.id; - } - - public: bool operator!=(const Source &_source) const - { - return !(*this == _source); - } - }; - - /// \brief A source's playing information. - /// Useful for keeping track of when to start/stop playing a source. - struct SourcePlayInfo - { - /// \brief Constructor - SourcePlayInfo() : startTime() - { - } - - /// \brief Whether the source is currently playing or not - bool playing{false}; - - /// \brief How long the source should play for, in seconds. - /// Setting this to 0 means the source has a play duration of infinity - std::chrono::seconds playDuration; - - /// \brief The time at which the source most recently started playing - std::chrono::steady_clock::duration startTime; - - public: bool operator==(const SourcePlayInfo &_sourcePlayInfo) const - { - return (this->playing == _sourcePlayInfo.playing) && - (this->playDuration == _sourcePlayInfo.playDuration) && - (this->startTime == _sourcePlayInfo.startTime); - } - - public: bool operator!=(const SourcePlayInfo &_sourcePlayInfo) const - { - return !(*this == _sourcePlayInfo); - } - }; - - /// \brief Properties of a logical audio microphone. - /// A microphone also has a pose, which can be stored as a component of a - /// microphone entity via ignition::gazebo::components::Pose - struct Microphone - { - /// \brief The microphone's id - unsigned int id; - - /// \brief The minimum volume this microphone can detect. - /// This should be a value between 0.0 (0% volume) and 1.0 (100% volume) - double volumeDetectionThreshold; - - public: bool operator==(const Microphone &_microphone) const - { - return this->id == _microphone.id; - } - - public: bool operator!=(const Microphone &_microphone) const - { - return !(*this == _microphone); - } - }; -} - -namespace serializers -{ - /// \brief Output stream overload for logical_audio::AttenuationFunction - inline std::ostream &operator<<(std::ostream &_out, - const logical_audio::AttenuationFunction &_func) - { - auto temp = static_cast(_func); - _out << temp; - return _out; - } - - /// \brief Input stream overload for logical_audio::AttenuationFunction - inline std::istream &operator>>(std::istream &_in, - logical_audio::AttenuationFunction &_func) - { - unsigned int temp = 0u; - if (_in >> temp) - _func = static_cast(temp); - return _in; - } - - /// \brief Output stream overload for logical_audio::AttenuationShape - inline std::ostream &operator<<(std::ostream &_out, - const logical_audio::AttenuationShape &_shape) - { - auto temp = static_cast(_shape); - _out << temp; - return _out; - } - - /// \brief Input stream overload for logical_audio::AttenuationShape - inline std::istream &operator>>(std::istream &_in, - logical_audio::AttenuationShape &_shape) - { - unsigned int temp = 0u; - if (_in >> temp) - _shape = static_cast(temp); - return _in; - } - - /// \brief Output stream overload for std::chrono::steady_clock::duration - inline std::ostream &operator<<(std::ostream &_out, - const std::chrono::steady_clock::duration &_dur) - { - _out << std::chrono::duration_cast( - _dur).count(); - return _out; - } - - /// \brief Input stream overload for std::chrono::steady_clock::duration - inline std::istream &operator>>(std::istream &_in, - std::chrono::steady_clock::duration &_dur) - { - int64_t time; - _in >> time; - _dur = std::chrono::duration(time); - return _in; - } - - /// \brief Serializer for components::LogicalAudioSource object - class LogicalAudioSourceSerializer - { - /// \brief Serialization for logical_audio::Source - /// \param[out] _out Output stream - /// \param[in] _source Object for the stream - /// \return The stream - public: static std::ostream &Serialize(std::ostream &_out, - const logical_audio::Source &_source) - { - _out << _source.id << " " << _source.attFunc << " " << _source.attShape - << " " << _source.innerRadius << " " << _source.falloffDistance - << " " << _source.emissionVolume; - return _out; - } - - /// \brief Deserialization for logical_audio::Source - /// \param[in] _in Input stream - /// \param[out] _source The object to populate - /// \return The stream - public: static std::istream &Deserialize(std::istream &_in, - logical_audio::Source &_source) - { - _in >> _source.id >> _source.attFunc >> _source.attShape - >> _source.innerRadius >> _source.falloffDistance - >> _source.emissionVolume; - return _in; - } - }; - - /// \brief Serializer for components::LogicalAudioSourcePlayInfo object - class LogicalAudioSourcePlayInfoSerializer - { - /// \brief Serialization for logical_audio::SourcePlayInfo - /// \param[out] _out Output stream - /// \param[in] _playInfo Object for the stream - /// \return The stream - public: static std::ostream &Serialize(std::ostream &_out, - const logical_audio::SourcePlayInfo &_playInfo) - { - _out << _playInfo.playing << " " << _playInfo.playDuration.count() << " " - << _playInfo.startTime; - return _out; - } - - /// \brief Deserialization for logical_audio::SourcePlayInfo - /// \param[in] _in Input stream - /// \param[out] _playInfo The object to populate - /// \return The stream - public: static std::istream &Deserialize(std::istream &_in, - logical_audio::SourcePlayInfo &_playInfo) - { - uint64_t count; - _in >> _playInfo.playing >> count >> _playInfo.startTime; - _playInfo.playDuration = std::chrono::seconds(count); - return _in; - } - }; - - /// \brief Serializer for components::LogicalMicrophone object - class LogicalMicrophoneSerializer - { - /// \brief Serialization for logical_audio::Microphone - /// \param[out] _out Output stream - /// \param[in] _mic Object for the stream - /// \return The stream - public: static std::ostream &Serialize(std::ostream &_out, - const logical_audio::Microphone &_mic) - { - _out << _mic.id << " " << _mic.volumeDetectionThreshold; - return _out; - } - - /// \brief Deserialization for logical_audio::Microphone - /// \param[in] _in Inout stream - /// \param[out] _mic The object to populate - public: static std::istream &Deserialize(std::istream &_in, - logical_audio::Microphone &_mic) - { - _in >> _mic.id >> _mic.volumeDetectionThreshold; - return _in; - } - }; -} - -// using separate namespace blocks so all components appear in Doxygen -// (appears as if Doxygen can't parse multiple components in a single -// namespace block since IGN_GAZEBO_REGISTER_COMPONENT doesn't have a -// trailing semicolon) -namespace components -{ - /// \brief A component that contains a logical audio source, which is - /// represented by logical_audio::Source - using LogicalAudioSource = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LogicalAudioSource", - LogicalAudioSource) -} - -namespace components -{ - /// \brief A component that contains a logical audio source's playing - /// information, which is represented by logical_audio::SourcePlayInfo - using LogicalAudioSourcePlayInfo = Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.LogicalAudioSourcePlayInfo", - LogicalAudioSourcePlayInfo) -} - -namespace components -{ - /// \brief A component that contains a logical microphone, which is - /// represented by logical_audio::Microphone - using LogicalMicrophone = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LogicalMicrophone", - LogicalMicrophone) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/LogicalCamera.hh b/include/ignition/gazebo/components/LogicalCamera.hh index 7ed6463163..4086290573 100644 --- a/include/ignition/gazebo/components/LogicalCamera.hh +++ b/include/ignition/gazebo/components/LogicalCamera.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,31 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_LOGICALCAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LOGICALCAMERA_HH_ + */ -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief 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", - LogicalCamera) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/MagneticField.hh b/include/ignition/gazebo/components/MagneticField.hh index 8986f47813..f17a736c00 100644 --- a/include/ignition/gazebo/components/MagneticField.hh +++ b/include/ignition/gazebo/components/MagneticField.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,32 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_MAGNETICFIELD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_MAGNETICFIELD_HH_ - -#include + */ +#include #include -#include - -#include -#include "ignition/gazebo/components/Component.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Stores the 3D magnetic field in teslas. - using MagneticField = Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.MagneticField", MagneticField) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/Magnetometer.hh b/include/ignition/gazebo/components/Magnetometer.hh index daa7c5a860..619b1931e6 100644 --- a/include/ignition/gazebo/components/Magnetometer.hh +++ b/include/ignition/gazebo/components/Magnetometer.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,36 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_MAGNETOMETER_HH_ -#define IGNITION_GAZEBO_COMPONENTS_MAGNETOMETER_HH_ - -#include + */ +#include #include -#include - -#include -#include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains a magnetometer sensor, - /// sdf::Magnetometer, information. - using Magnetometer = Component; - - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.Magnetometer", Magnetometer) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/Material.hh b/include/ignition/gazebo/components/Material.hh index 2acf7a839a..4d786db826 100644 --- a/include/ignition/gazebo/components/Material.hh +++ b/include/ignition/gazebo/components/Material.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,39 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_MATERIAL_HH_ -#define IGNITION_GAZEBO_COMPONENTS_MATERIAL_HH_ + */ -#include - -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace serializers -{ - using MaterialSerializer = - serializers::ComponentToMsgSerializer; -} -namespace components -{ - /// \brief This component holds an entity's material. - using Material = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Material", Material) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Model.hh b/include/ignition/gazebo/components/Model.hh index 7fdc7014ce..8fe0cef5e4 100644 --- a/include/ignition/gazebo/components/Model.hh +++ b/include/ignition/gazebo/components/Model.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,34 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_MODEL_HH_ -#define IGNITION_GAZEBO_COMPONENTS_MODEL_HH_ + */ -#include - -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that identifies an entity as being a model. - using Model = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_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) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Name.hh b/include/ignition/gazebo/components/Name.hh index 553be0b555..aa367b9294 100644 --- a/include/ignition/gazebo/components/Name.hh +++ b/include/ignition/gazebo/components/Name.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,30 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_NAME_HH_ -#define IGNITION_GAZEBO_COMPONENTS_NAME_HH_ + */ -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief This component holds an entity's name. The component has no concept - /// of scoped names nor does it care about uniqueness. - using Name = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Name", Name) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/ParentEntity.hh b/include/ignition/gazebo/components/ParentEntity.hh index 5871d5a3d5..c34f961106 100644 --- a/include/ignition/gazebo/components/ParentEntity.hh +++ b/include/ignition/gazebo/components/ParentEntity.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,37 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_PARENTENTITY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PARENTENTITY_HH_ + */ -#include -#include +#include #include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief This component holds an entity's parent entity. - /// - /// Note that the EntityComponentManager also keeps the parent-child - /// relationship stored in a graph, and that information should be - /// kept in sync with the parent entity components. Therefore, - /// it is recommended that the `ParentEntity` component is never - /// edited by hand, and instead, entities should be created using - /// the `gazebo::SdfEntityCreator` class. - using ParentEntity = Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.ParentEntity", ParentEntity) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/ParentLinkName.hh b/include/ignition/gazebo/components/ParentLinkName.hh index 6071431977..0a2e942b26 100644 --- a/include/ignition/gazebo/components/ParentLinkName.hh +++ b/include/ignition/gazebo/components/ParentLinkName.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,29 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_PARENTLINKNAME_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PARENTLINKNAME_HH_ -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Holds the name of the entity's parent link. - using ParentLinkName = Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.ParentLinkName", ParentLinkName) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Performer.hh b/include/ignition/gazebo/components/Performer.hh index e458058609..f386b656fb 100644 --- a/include/ignition/gazebo/components/Performer.hh +++ b/include/ignition/gazebo/components/Performer.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,28 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_PERFORMER_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PERFORMER_HH_ +#include #include -#include - -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Component.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief This component identifies an entity as being a performer. - using Performer = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Performer", Performer) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/PerformerAffinity.hh b/include/ignition/gazebo/components/PerformerAffinity.hh index acb439ef25..e8dac3722e 100644 --- a/include/ignition/gazebo/components/PerformerAffinity.hh +++ b/include/ignition/gazebo/components/PerformerAffinity.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,35 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_PERFORMERAFFINITY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PERFORMERAFFINITY_HH_ - -#include + */ +#include #include -#include - -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Component.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief This component holds the address of the distributed secondary that - /// this performer is associated with. - using PerformerAffinity = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.PerformerAffinity", - PerformerAffinity) -} -} -} -} - -#endif - diff --git a/include/ignition/gazebo/components/PerformerLevels.hh b/include/ignition/gazebo/components/PerformerLevels.hh index a9f84faa94..0bfc4229ff 100644 --- a/include/ignition/gazebo/components/PerformerLevels.hh +++ b/include/ignition/gazebo/components/PerformerLevels.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,72 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_PERFORMERLEVELS_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PERFORMERLEVELS_HH_ -#include +#include #include -#include - -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Component.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace serializers -{ - class PerformerLevelsSerializer - { - /// \brief Serialization for `std::set`. - /// \param[in] _out Output stream. - /// \param[in] _set Set to stream - /// \return The stream. - public: static std::ostream &Serialize(std::ostream &_out, - const std::set &_set) - { - for (const auto &level : _set) - { - _out << level << " "; - } - return _out; - } - - /// \brief Deserialization for `std::set`. - /// \param[in] _in Input stream. - /// \param[out] _set Set to populate - /// \return The stream. - public: static std::istream &Deserialize(std::istream &_in, - std::set &_set) - { - _in.setf(std::ios_base::skipws); - - _set.clear(); - - for (auto it = std::istream_iterator(_in); - it != std::istream_iterator(); ++it) - { - _set.insert(*it); - } - return _in; - } - }; -} - -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", - PerformerLevels) -} -} -} -} -#endif - diff --git a/include/ignition/gazebo/components/Physics.hh b/include/ignition/gazebo/components/Physics.hh index 804059dedc..ce8d2769db 100644 --- a/include/ignition/gazebo/components/Physics.hh +++ b/include/ignition/gazebo/components/Physics.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,44 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_PHYSICS_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PHYSICS_HH_ - -#include - -#include + */ +#include #include -#include - -#include -#include "ignition/gazebo/components/Component.hh" -#include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace serializers -{ - using PhysicsSerializer = - serializers::ComponentToMsgSerializer; -} -namespace components -{ - /// \brief A component type that contains the physics properties of - /// the World entity. - using Physics = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Physics", - Physics) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/PhysicsCmd.hh b/include/ignition/gazebo/components/PhysicsCmd.hh index f72dc328b0..f2abcac2b9 100644 --- a/include/ignition/gazebo/components/PhysicsCmd.hh +++ b/include/ignition/gazebo/components/PhysicsCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,34 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_PHYSICSCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PHYSICSCMD_HH_ - -#include + */ +#include #include -#include - -#include -#include "ignition/gazebo/components/Component.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -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", - PhysicsCmd) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/PhysicsEnginePlugin.hh b/include/ignition/gazebo/components/PhysicsEnginePlugin.hh index 2e5d5cbf73..7d22f178cc 100644 --- a/include/ignition/gazebo/components/PhysicsEnginePlugin.hh +++ b/include/ignition/gazebo/components/PhysicsEnginePlugin.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,31 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_PHYSICSENGINEPLUGIN_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PHYSICSENGINEPLUGIN_HH_ + */ -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Holds the physics engine shared library. - using PhysicsEnginePlugin = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.PhysicsEnginePlugin", - PhysicsEnginePlugin) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Pose.hh b/include/ignition/gazebo/components/Pose.hh index 96b8626442..90aaf89598 100644 --- a/include/ignition/gazebo/components/Pose.hh +++ b/include/ignition/gazebo/components/Pose.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,36 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_POSE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_POSE_HH_ + */ -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains pose, ignition::math::Pose3d, - /// information. - using Pose = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_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) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/PoseCmd.hh b/include/ignition/gazebo/components/PoseCmd.hh index 8f63faefee..afea27506c 100644 --- a/include/ignition/gazebo/components/PoseCmd.hh +++ b/include/ignition/gazebo/components/PoseCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,32 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_POSECMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_POSECMD_HH_ - -#include +#include #include -#include - -#include -#include "ignition/gazebo/components/Component.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains commanded pose of an - /// entity in the world frame represented by ignition::math::Pose3d. - using WorldPoseCmd = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WorldPoseCmd", - WorldPoseCmd) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/RenderEngineGuiPlugin.hh b/include/ignition/gazebo/components/RenderEngineGuiPlugin.hh index e2539e1331..8d13081803 100644 --- a/include/ignition/gazebo/components/RenderEngineGuiPlugin.hh +++ b/include/ignition/gazebo/components/RenderEngineGuiPlugin.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,32 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_RENDERENGINEGUIPLUGIN_HH_ -#define IGNITION_GAZEBO_COMPONENTS_RENDERENGINEGUIPLUGIN_HH_ + */ -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Holds the render engine gui shared library. - using RenderEngineGuiPlugin = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.RenderEngineGuiPlugin", - RenderEngineGuiPlugin) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/RenderEngineServerPlugin.hh b/include/ignition/gazebo/components/RenderEngineServerPlugin.hh index 6d32db368e..3cb2025d50 100644 --- a/include/ignition/gazebo/components/RenderEngineServerPlugin.hh +++ b/include/ignition/gazebo/components/RenderEngineServerPlugin.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,33 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_RENDERENGINESERVERPLUGIN_HH_ -#define IGNITION_GAZEBO_COMPONENTS_RENDERENGINESERVERPLUGIN_HH_ + */ -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Holds the render engine server shared library. - using RenderEngineServerPlugin = Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.RenderEngineServerPlugin", - RenderEngineServerPlugin) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/RgbdCamera.hh b/include/ignition/gazebo/components/RgbdCamera.hh index 54347b7bdd..dec1b18058 100644 --- a/include/ignition/gazebo/components/RgbdCamera.hh +++ b/include/ignition/gazebo/components/RgbdCamera.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,32 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_RGBDCAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_RGBDCAMERA_HH_ + */ -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains a RGBD camera sensor, - /// sdf::Camera, information. - using RgbdCamera = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.RgbdCamera", RgbdCamera) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/Scene.hh b/include/ignition/gazebo/components/Scene.hh index 20ea32123c..4dbd5c91c4 100644 --- a/include/ignition/gazebo/components/Scene.hh +++ b/include/ignition/gazebo/components/Scene.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,41 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_SCENE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SCENE_HH_ + */ -#include - -#include -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace serializers -{ - using SceneSerializer = - serializers::ComponentToMsgSerializer; -} - -namespace components -{ - /// \brief This component holds scene properties of the world. - using Scene = - Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.Scene", Scene) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/SelfCollide.hh b/include/ignition/gazebo/components/SelfCollide.hh index ae0ddc6be3..eb984145dd 100644 --- a/include/ignition/gazebo/components/SelfCollide.hh +++ b/include/ignition/gazebo/components/SelfCollide.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,29 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_SELFCOLLIDE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SELFCOLLIDE_HH_ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component used to hold a model's self collide property. - using SelfCollide = Component; - - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SelfCollide", - SelfCollide) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Sensor.hh b/include/ignition/gazebo/components/Sensor.hh index 2d7ddb39a3..61ef5e5469 100644 --- a/include/ignition/gazebo/components/Sensor.hh +++ b/include/ignition/gazebo/components/Sensor.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,39 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_SENSOR_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SENSOR_HH_ + */ -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that identifies an entity as being a sensor. - using Sensor = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Sensor", Sensor) - - /// \brief Name of the transport topic where a sensor is publishing its - /// data. - /// For sensors that publish on more than one topic, this will usually be the - /// prefix common to all topics of that sensor. - using SensorTopic = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SensorTopic", - SensorTopic) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Serialization.hh b/include/ignition/gazebo/components/Serialization.hh index 151af91adc..25f99c7a26 100644 --- a/include/ignition/gazebo/components/Serialization.hh +++ b/include/ignition/gazebo/components/Serialization.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,213 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_SERIALIZATION_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SERIALIZATION_HH_ + */ -#include -#include - -#include -#include -#include - -#include - -// This header holds serialization operators which are shared among several -// components - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -/// \brief A Serializer class is used to serialize and deserialize a component. -/// It is passed in as the third template parameter to components::Component. -/// Eg. -/// \code -/// using Geometry = components::Component -/// \endcode -/// A serializer class implements two static functions: `Serialize` and -/// `Deserialize` with the following signatures -/// \code -/// class ExampleSerializer -/// { -/// public: static std::ostream &Serialize(std::ostream &_out, -/// const DataType &_data); -/// public: static std::istream &Deserialize(std::istream &_in, -/// DataType &_data) -/// }; -/// \endcode - -namespace serializers -{ - /// \brief Serialization for that converts components data types to - /// ignition::msgs. This assumes that ignition::gazebo::convert is - /// defined - /// \tparam DataType Underlying data type of the component - /// - /// This can be used for components that can be converted to ignition::msg - /// types via ignition::gazebo::convert. For example sdf::Geometry can be - /// converted to msgs::Geometry so the component can be defined as - /// \code - /// using Geometry = Component> - /// \endcode - template - class ComponentToMsgSerializer - { - /// \brief Serialization - /// \param[in] _out Output stream. - /// \param[in] _data data to stream - /// \return The stream. - public: static std::ostream &Serialize(std::ostream &_out, - const DataType &_data) - { - auto msg = ignition::gazebo::convert(_data); - msg.SerializeToOstream(&_out); - return _out; - } - - /// \brief Deserialization - /// \param[in] _in Input stream. - /// \param[out] _data data to populate - /// \return The stream. - public: static std::istream &Deserialize(std::istream &_in, - DataType &_data) - { - MsgType msg; - msg.ParseFromIstream(&_in); - - _data = ignition::gazebo::convert(msg); - return _in; - } - }; - - /// \brief Common serializer for sensors - using SensorSerializer = ComponentToMsgSerializer; - - /// \brief Serializer for components that hold `std::vector`. - class VectorDoubleSerializer - { - /// \brief Serialization - /// \param[in] _out Output stream. - /// \param[in] _vec Vector to stream - /// \return The stream. - public: static std::ostream &Serialize(std::ostream &_out, - const std::vector &_vec) - { - ignition::msgs::Double_V msg; - *msg.mutable_data() = {_vec.begin(), _vec.end()}; - msg.SerializeToOstream(&_out); - return _out; - } - - /// \brief Deserialization - /// \param[in] _in Input stream. - /// \param[in] _vec Vector to populate - /// \return The stream. - public: static std::istream &Deserialize(std::istream &_in, - std::vector &_vec) - { - ignition::msgs::Double_V msg; - msg.ParseFromIstream(&_in); - - _vec = {msg.data().begin(), msg.data().end()}; - return _in; - } - }; - - /// \brief Serializer for components that hold protobuf messages. - class MsgSerializer - { - /// \brief Serialization - /// \param[in] _out Output stream. - /// \param[in] _msg Message to stream - /// \return The stream. - public: static std::ostream &Serialize(std::ostream &_out, - const google::protobuf::Message &_msg) - { - _msg.SerializeToOstream(&_out); - return _out; - } - - /// \brief Deserialization - /// \param[in] _in Input stream. - /// \param[in] _msg Message to populate - /// \return The stream. - public: static std::istream &Deserialize(std::istream &_in, - google::protobuf::Message &_msg) - { - _msg.ParseFromIstream(&_in); - return _in; - } - }; - - /// \brief Serializer for components that hold std::string. - class StringSerializer - { - /// \brief Serialization - /// \param[in] _out Output stream. - /// \param[in] _data Data to serialize. - /// \return The stream. - public: static std::ostream &Serialize(std::ostream &_out, - const std::string &_data) - { - _out << _data; - return _out; - } - - /// \brief Deserialization - /// \param[in] _in Input stream. - /// \param[in] _data Data to populate. - /// \return The stream. - public: static std::istream &Deserialize(std::istream &_in, - std::string &_data) - { - _data = std::string(std::istreambuf_iterator(_in), {}); - return _in; - } - }; - - template - class VectorSerializer - { - /// \brief Serialization for `std::vector` with serializable T. - /// \param[in] _out Output stream. - /// \param[in] _data The data to stream. - /// \return The stream. - public: static std::ostream &Serialize(std::ostream &_out, - const std::vector &_data) - { - _out << _data.size(); - for (const auto& datum : _data) - _out << " " << datum; - return _out; - } - - /// \brief Deserialization for `std::vector` with serializable T. - /// \param[in] _in Input stream. - /// \param[out] _data The data to populate. - /// \return The stream. - public: static std::istream &Deserialize(std::istream &_in, - std::vector &_data) - { - size_t size; - _in >> size; - _data.resize(size); - for (size_t i = 0; i < size; ++i) - { - _in >> _data[i]; - } - return _in; - } - }; -} -} -} -} - -#endif +#include +#include diff --git a/include/ignition/gazebo/components/SlipComplianceCmd.hh b/include/ignition/gazebo/components/SlipComplianceCmd.hh index f8122b7c41..38227cc013 100644 --- a/include/ignition/gazebo/components/SlipComplianceCmd.hh +++ b/include/ignition/gazebo/components/SlipComplianceCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -15,35 +15,5 @@ * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_SLIPCOMPLIANCECMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SLIPCOMPLIANCECMD_HH_ - -#include - +#include #include -#include - -#include -#include "ignition/gazebo/components/Component.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains the slip compliance parameters to be - /// set on a collision. The 0 and 1 index values correspond to the slip - /// compliance parameters in friction direction 1 (fdir1) and friction - /// direction 2 (fdir2) respectively. - using SlipComplianceCmd = - Component, class SlipComplianceCmdTag>; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SlipComplianceCmd ", - SlipComplianceCmd) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/SourceFilePath.hh b/include/ignition/gazebo/components/SourceFilePath.hh index 96cd30ebbb..c830539003 100644 --- a/include/ignition/gazebo/components/SourceFilePath.hh +++ b/include/ignition/gazebo/components/SourceFilePath.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,32 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_SOURCEFILEPATH_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SOURCEFILEPATH_HH_ -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief This component holds the filepath to the source from which an - /// entity is created. For example, it can be used to store the file path of a - /// model's SDFormat file. - using SourceFilePath = Component; - - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SourceFilePath", - SourceFilePath) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Static.hh b/include/ignition/gazebo/components/Static.hh index d9b876a584..f2279d7040 100644 --- a/include/ignition/gazebo/components/Static.hh +++ b/include/ignition/gazebo/components/Static.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,28 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_STATIC_HH_ -#define IGNITION_GAZEBO_COMPONENTS_STATIC_HH_ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component used to indicate that a model is static (i.e. not - /// moveable). - using Static = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Static", Static) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Temperature.hh b/include/ignition/gazebo/components/Temperature.hh index 228e208518..56545ab92d 100644 --- a/include/ignition/gazebo/components/Temperature.hh +++ b/include/ignition/gazebo/components/Temperature.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,31 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_TEMPERATURE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_TEMPERATURE_HH_ + */ -#include - -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that stores temperature data in Kelvin - using Temperature = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Temperature", - Temperature) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/ThermalCamera.hh b/include/ignition/gazebo/components/ThermalCamera.hh index 5061070f84..e94bebfa4e 100644 --- a/include/ignition/gazebo/components/ThermalCamera.hh +++ b/include/ignition/gazebo/components/ThermalCamera.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,33 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_THERMALCAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_THERMALCAMERA_HH_ + */ -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains a Thermal camera sensor, - /// sdf::Sensor, information. - using ThermalCamera = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ThermalCamera", - ThermalCamera) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/ThreadPitch.hh b/include/ignition/gazebo/components/ThreadPitch.hh index 0a9f2c0551..301d0bf1b9 100644 --- a/include/ignition/gazebo/components/ThreadPitch.hh +++ b/include/ignition/gazebo/components/ThreadPitch.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,28 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_THREADPITCH_HH_ -#define IGNITION_GAZEBO_COMPONENTS_THREADPITCH_HH_ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component used to store the thread pitch of a screw joint - using ThreadPitch = Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.ThreadPitch", ThreadPitch) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Transparency.hh b/include/ignition/gazebo/components/Transparency.hh index 1c2a9f3c3d..c3efbc805c 100644 --- a/include/ignition/gazebo/components/Transparency.hh +++ b/include/ignition/gazebo/components/Transparency.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,30 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_TRANSPARENCY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_TRANSPARENCY_HH_ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component used to indicate an entity's transparency value - /// 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", - Transparency) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Visual.hh b/include/ignition/gazebo/components/Visual.hh index 9d90871a7b..89b5e0e03a 100644 --- a/include/ignition/gazebo/components/Visual.hh +++ b/include/ignition/gazebo/components/Visual.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,28 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_VISUAL_HH_ -#define IGNITION_GAZEBO_COMPONENTS_VISUAL_HH_ + */ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that identifies an entity as being a visual. - using Visual = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Visual", Visual) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Volume.hh b/include/ignition/gazebo/components/Volume.hh index 75a0ee8135..707b59d122 100644 --- a/include/ignition/gazebo/components/Volume.hh +++ b/include/ignition/gazebo/components/Volume.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,29 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_VOLUME_HH_ -#define IGNITION_GAZEBO_COMPONENTS_VOLUME_HH_ + */ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A 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) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Wind.hh b/include/ignition/gazebo/components/Wind.hh index 1fc9349493..b8b15af42d 100644 --- a/include/ignition/gazebo/components/Wind.hh +++ b/include/ignition/gazebo/components/Wind.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,27 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_WIND_HH_ -#define IGNITION_GAZEBO_COMPONENTS_WIND_HH_ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that identifies an entity as being a wind. - using Wind = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Wind", Wind) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/WindMode.hh b/include/ignition/gazebo/components/WindMode.hh index 04cac9ce3d..16dc8fc04e 100644 --- a/include/ignition/gazebo/components/WindMode.hh +++ b/include/ignition/gazebo/components/WindMode.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,27 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_WINDMODE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_WINDMODE_HH_ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component used to indicate whether an entity is affected by wind. - using WindMode = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WindMode", WindMode) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/World.hh b/include/ignition/gazebo/components/World.hh index bb37c0e8d5..348e058f58 100644 --- a/include/ignition/gazebo/components/World.hh +++ b/include/ignition/gazebo/components/World.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,34 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_WORLD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_WORLD_HH_ + */ -#include - -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that identifies an entity as being a world. - using World = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_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) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/config.hh b/include/ignition/gazebo/config.hh new file mode 100644 index 0000000000..1981f733e9 --- /dev/null +++ b/include/ignition/gazebo/config.hh @@ -0,0 +1,65 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#ifndef IGNITION_GAZEBO__CONFIG_HH_ +#define IGNITION_GAZEBO__CONFIG_HH_ + +#include + +/* Version number */ +// #define IGNITION_GAZEBO_MAJOR_VERSION GZ_SIM_MAJOR_VERSION +// #define IGNITION_GAZEBO_MINOR_VERSION GZ_SIM_MINOR_VERSION +// #define IGNITION_GAZEBO_PATCH_VERSION GZ_SIM_PATCH_VERSION + +// #define IGNITION_GAZEBO_VERSION GZ_SIM_VERSION +// #define IGNITION_GAZEBO_VERSION_FULL GZ_SIM_VERSION_FULL +// #define IGNITION_GAZEBO_MAJOR_VERSION_STR GZ_SIM_MAJOR_VERSION_STR + +// #define IGNITION_GAZEBO_VERSION_NAMESPACE GZ_SIM_VERSION_NAMESPACE + +// #define IGNITION_GAZEBO_VERSION_HEADER GZ_SIM_VERSION_HEADER + +// #define IGNITION_GAZEBO_GUI_CONFIG_PATH GZ_SIM_GUI_CONFIG_PATH +// #define IGNITION_GAZEBO_SYSTEM_CONFIG_PATH GZ_SIM_SYSTEM_CONFIG_PATH +// #define IGNITION_GAZEBO_SERVER_CONFIG_PATH GZ_SIM_SERVER_CONFIG_PATH +// #define IGN_GAZEBO_PLUGIN_INSTALL_DIR GZ_SIM_PLUGIN_INSTALL_DIR +// #define IGN_GAZEBO_GUI_PLUGIN_INSTALL_DIR GZ_SIM_GUI_PLUGIN_INSTALL_DIR +// #define IGN_GAZEBO_WORLD_INSTALL_DIR GZ_SIM_WORLD_INSTALL_DIR +// #define IGN_DISTRIBUTION GZ_DISTRIBUTION + +/* #undef IGNITION_GAZEBO_BUILD_TYPE_PROFILE */ +/* #undef IGNITION_GAZEBO_BUILD_TYPE_DEBUG */ +/* #undef IGNITION_GAZEBO_BUILD_TYPE_RELEASE */ + +namespace ignition +{ + namespace gazebo + { + } +} + +namespace gz +{ + using namespace ignition; + + namespace sim + { + using namespace gazebo; + } +} + +#endif diff --git a/include/ignition/gazebo/contact-system/Export.hh b/include/ignition/gazebo/contact-system/Export.hh new file mode 100644 index 0000000000..4bc5c4ba8e --- /dev/null +++ b/include/ignition/gazebo/contact-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/detachable-joint-system/Export.hh b/include/ignition/gazebo/detachable-joint-system/Export.hh new file mode 100644 index 0000000000..009e5e9485 --- /dev/null +++ b/include/ignition/gazebo/detachable-joint-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/diff-drive-system/Export.hh b/include/ignition/gazebo/diff-drive-system/Export.hh new file mode 100644 index 0000000000..c0c2c2f523 --- /dev/null +++ b/include/ignition/gazebo/diff-drive-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/elevator-system/Export.hh b/include/ignition/gazebo/elevator-system/Export.hh new file mode 100644 index 0000000000..4f3a767fc1 --- /dev/null +++ b/include/ignition/gazebo/elevator-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/gui/Export.hh b/include/ignition/gazebo/gui/Export.hh new file mode 100644 index 0000000000..00d93deca9 --- /dev/null +++ b/include/ignition/gazebo/gui/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/gui/Gui.hh b/include/ignition/gazebo/gui/Gui.hh index 6c9fb219e9..51807c3c72 100644 --- a/include/ignition/gazebo/gui/Gui.hh +++ b/include/ignition/gazebo/gui/Gui.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -15,100 +15,5 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_GUI_HH_ -#define IGNITION_GAZEBO_GUI_GUI_HH_ - -#include -#include -#include - -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/gui/Export.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace gui -{ - /// \brief Run GUI application - /// \param[in] _argc Number of command line arguments (Used when running - /// without ign-tools. Set to 1 if using ign-tools). Note: The object - /// referenced by this variable must continue to exist for the lifetime of the - /// application. - /// \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. - IGNITION_GAZEBO_GUI_VISIBLE int runGui(int &_argc, char **_argv, - const char *_guiConfig); - - /// \brief Run GUI application - /// \param[in] _argc Number of command line arguments (Used when running - /// without ign-tools. Set to 1 if using ign-tools). Note: The object - /// referenced by this variable must continue to exist for the lifetime of the - /// application. - /// \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. - /// \param[in] _sdfFile The world file path passed as a command line argument. - /// If set, QuickStart Dialog will not be shown. - /// \param[in] _waitGui Flag indicating whether the server waits until - /// it receives a world path from GUI. - IGNITION_GAZEBO_GUI_VISIBLE int runGui(int &_argc, char **_argv, - const char *_guiConfig, const char *_sdfFile, int _waitGui); - - /// \brief Create a Gazebo GUI application - /// \param[in] _argc Number of command line arguments (Used when running - /// without ign-tools. Set to 1 if using ign-tools). Note: The object - /// referenced by this variable must continue to exist for the lifetime of the - /// application. - /// \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. - /// \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. - /// \param[in] _loadPluginsFromSdf If true, plugins specified in the world - /// SDFormat file will get loaded. - IGNITION_GAZEBO_GUI_VISIBLE - std::unique_ptr createGui( - int &_argc, char **_argv, const char *_guiConfig, - const char *_defaultGuiConfig = nullptr, bool _loadPluginsFromSdf = true); - - /// \brief Create a Gazebo GUI application - /// \param[in] _argc Number of command line arguments (Used when running - /// without ign-tools. Set to 1 if using ign-tools). Note: The object - /// referenced by this variable must continue to exist for the lifetime of the - /// application. - /// \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. - /// \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. - /// \param[in] _loadPluginsFromSdf If true, plugins specified in the world - /// SDFormat file will get loaded. - /// \param[in] _sdfFile SDF world file, or nullptr if not set. - /// \param[in] _waitGui True if the server is waiting for the GUI to decide on - /// a starting world. - IGNITION_GAZEBO_GUI_VISIBLE - std::unique_ptr createGui( - int &_argc, char **_argv, const char *_guiConfig, - const char *_defaultGuiConfig, bool _loadPluginsFromSdf, - const char *_sdfFile, int _waitGui); -} // namespace gui -} // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition - -#endif +#include +#include diff --git a/include/ignition/gazebo/gui/GuiEvents.hh b/include/ignition/gazebo/gui/GuiEvents.hh index 6af9c5a69c..41cfcc0e35 100644 --- a/include/ignition/gazebo/gui/GuiEvents.hh +++ b/include/ignition/gazebo/gui/GuiEvents.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,207 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_GUI_GUIEVENTS_HH_ -#define IGNITION_GAZEBO_GUI_GUIEVENTS_HH_ + */ -#include -#include -#include -#include -#include -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/config.hh" - -namespace ignition -{ -namespace gazebo -{ -namespace gui { -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -/// \brief Namespace for all events. Refer to the EventManager class for -/// more information about events. -namespace events -{ - /// \brief The class for sending and receiving custom snap value events. - class SnapIntervals : public QEvent - { - /// \brief Constructor - /// \param[in] _xyz XYZ snapping values. - /// \param[in] _rpy RPY snapping values. - /// \param[in] _scale Scale snapping values. - public: SnapIntervals( - const math::Vector3d &_xyz, - const math::Vector3d &_rpy, - const math::Vector3d &_scale) - : QEvent(kType), xyz(_xyz), rpy(_rpy), scale(_scale) - { - } - - /// \brief Get the XYZ snapping values. - /// \return The XYZ snapping values. - public: math::Vector3d XYZ() const - { - return this->xyz; - } - - /// \brief Get the RPY snapping values. - /// \return The RPY snapping values. - public: math::Vector3d RPY() const - { - return this->rpy; - } - - /// \brief Get the scale snapping values. - /// \return The scale snapping values. - public: math::Vector3d Scale() const - { - return this->scale; - } - - /// \brief The QEvent representing a snap event occurrence. - static const QEvent::Type kType = QEvent::Type(QEvent::User); - - /// \brief XYZ snapping values in meters, these values must be positive. - private: math::Vector3d xyz; - - /// \brief RPY snapping values in degrees, these values must be positive. - private: math::Vector3d rpy; - - /// \brief Scale snapping values - a multiplier of the current size, - /// these values must be positive. - private: math::Vector3d scale; - }; - - /// \brief Event that notifies when new entities have been selected. - class EntitiesSelected : public QEvent - { - /// \brief Constructor - /// \param[in] _entities All the selected entities - /// \param[in] _fromUser True if the event was directly generated by the - /// user, false in case it's been propagated through a different mechanism. - public: explicit EntitiesSelected( - const std::vector &_entities, // NOLINT - bool _fromUser = false) - : QEvent(kType), entities(_entities), fromUser(_fromUser) - { - } - - /// \brief Get the data sent with the event. - /// \return The entities being selected. - public: std::vector Data() const - { - return this->entities; - } - - /// \brief Get whether the event was generated by the user. - /// \return True for the user. - public: bool FromUser() const - { - return this->fromUser; - } - - /// \brief Unique type for this event. - static const QEvent::Type kType = QEvent::Type(QEvent::User + 1); - - /// \brief The selected entities. - private: std::vector entities; - - /// \brief Whether the event was generated by the user, - private: bool fromUser{false}; - }; - - /// \brief Event that notifies when all entities have been deselected. - class DeselectAllEntities : public QEvent - { - /// \brief Constructor - /// \param[in] _fromUser True if the event was directly generated by the - /// user, false in case it's been propagated through a different mechanism. - public: explicit DeselectAllEntities(bool _fromUser = false) - : QEvent(kType), fromUser(_fromUser) - { - } - - /// \brief Get whether the event was generated by the user. - /// \return True for the user. - public: bool FromUser() const - { - return this->fromUser; - } - - /// \brief Unique type for this event. - static const QEvent::Type kType = QEvent::Type(QEvent::User + 2); - - /// \brief Whether the event was generated by the user, - private: bool fromUser{false}; - }; - - /// \brief Event called in the render thread of a 3D scene. - /// It's safe to make rendering calls in this event's callback. - class Render : public QEvent - { - public: Render() - : QEvent(kType) - { - } - /// \brief Unique type for this event. - static const QEvent::Type kType = QEvent::Type(QEvent::User + 3); - }; - - /// \brief Event called to spawn a preview model. - /// Used by plugins that spawn models. - class SpawnPreviewModel : public QEvent - { - /// \brief Constructor - /// \param[in] _modelSdfString The model's SDF file as a string. - public: explicit SpawnPreviewModel(std::string &_modelSdfString) - : QEvent(kType), modelSdfString(_modelSdfString) - { - } - - /// \brief Unique type for this event. - static const QEvent::Type kType = QEvent::Type(QEvent::User + 4); - - /// \brief Get the sdf string of the model. - /// \return The model sdf string - public: std::string ModelSdfString() const - { - return this->modelSdfString; - } - - /// \brief The sdf string of the model to be previewed. - std::string modelSdfString; - }; - - /// \brief Event called to spawn a preview resource, which takes the path - /// to the SDF file. Used by plugins that spawn resources. - class SpawnPreviewPath : public QEvent - { - /// \brief Constructor - /// \param[in] _filePath The path to an SDF file. - public: explicit SpawnPreviewPath(const std::string &_filePath) - : QEvent(kType), filePath(_filePath) - { - } - - /// \brief Unique type for this event. - static const QEvent::Type kType = QEvent::Type(QEvent::User + 5); - - /// \brief Get the path of the SDF file. - /// \return The file path. - public: std::string FilePath() const - { - return this->filePath; - } - - /// \brief The path of SDF file to be previewed. - std::string filePath; - }; -} // namespace events -} -} // namespace gui -} // namespace gazebo -} // namespace ignition - -#endif // IGNITION_GAZEBO_GUI_GUIEVENTS_HH_ +#include +#include diff --git a/include/ignition/gazebo/gui/GuiRunner.hh b/include/ignition/gazebo/gui/GuiRunner.hh index cc8386945a..78b61c2781 100644 --- a/include/ignition/gazebo/gui/GuiRunner.hh +++ b/include/ignition/gazebo/gui/GuiRunner.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,79 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_GUI_GUIRUNNER_HH_ -#define IGNITION_GAZEBO_GUI_GUIRUNNER_HH_ + */ -#include - -#include -#include -#include -#include - -#include - -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/gui/Export.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -/// \brief Responsible for running GUI systems as new states are received from -/// the backend. -class IGNITION_GAZEBO_GUI_VISIBLE GuiRunner : public QObject -{ - Q_OBJECT - - /// \brief Constructor - /// \param[in] _worldName World name. - public: explicit GuiRunner(const std::string &_worldName); - - /// \brief Destructor - public: ~GuiRunner() override; - - /// \brief Callback when a plugin has been added. - /// This function has no effect and is left here for ABI compatibility. - /// \param[in] _objectName Plugin's object name. - public slots: void OnPluginAdded(const QString &_objectName); - - /// \brief Make a new state request to the server. - public slots: void RequestState(); - - /// \brief Callback for the async state service. - /// \param[in] _res Response containing new state. - private: void OnStateAsyncService(const msgs::SerializedStepMap &_res); - - /// \brief Callback when a new state is received from the server. Actual - /// updating of the ECM is delegated to OnStateQt - /// \param[in] _msg New state message. - private: void OnState(const msgs::SerializedStepMap &_msg); - - /// \brief Called by the Qt thread to update the ECM with new state - /// \param[in] _msg New state message. - private: Q_INVOKABLE void OnStateQt(const msgs::SerializedStepMap &_msg); - - /// \brief Update the plugins. - /// \todo(anyone) Move to GuiRunner::Implementation when porting to v5 - private: Q_INVOKABLE void UpdatePlugins(); - - /// \brief Entity-component manager. - private: gazebo::EntityComponentManager ecm; - - /// \brief Transport node. - private: transport::Node node; - - /// \brief Topic to request state - private: std::string stateTopic; - - /// \brief Latest update info - private: UpdateInfo updateInfo; -}; -} -} -} -#endif +#include +#include diff --git a/include/ignition/gazebo/gui/GuiSystem.hh b/include/ignition/gazebo/gui/GuiSystem.hh index 1de32584eb..0c16df3966 100644 --- a/include/ignition/gazebo/gui/GuiSystem.hh +++ b/include/ignition/gazebo/gui/GuiSystem.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,53 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_GUI_GUISYSTEM_HH_ -#define IGNITION_GAZEBO_GUI_GUISYSTEM_HH_ - -#include + */ +#include #include -#include -#include -#include - -#include - -namespace ignition -{ -namespace gazebo -{ - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - /// \brief Base class for a GUI System. - /// - /// A System operates on Entities that have certain Components. A System - /// will only operate on an Entity if it has all of the required - /// Components. - /// - /// GUI systems are different from `ignition::gazebo::System`s because they - /// don't run in the same process as the physics. Instead, they run in a - /// separate process that is stepped by updates coming through the network - class IGNITION_GAZEBO_VISIBLE GuiSystem : public ignition::gui::Plugin - { - Q_OBJECT - - /// \brief Update callback called every time the system is stepped. - /// This is called at an Ignition transport thread, so any interaction - /// with Qt should be done through signals and slots. - /// \param[in] _info Current simulation information, such as time. - /// \param[in] _ecm Mutable reference to the ECM, so the system can read - /// and write entities and their components. - public: virtual void Update(const UpdateInfo &_info, - EntityComponentManager &_ecm) - { - // This will avoid many doxygen warnings - (void)_info; - (void)_ecm; - } - }; -} -} -} -#endif diff --git a/include/ignition/gazebo/gui/TmpIface.hh b/include/ignition/gazebo/gui/TmpIface.hh index 0cc91c1073..ac1d8ebcde 100644 --- a/include/ignition/gazebo/gui/TmpIface.hh +++ b/include/ignition/gazebo/gui/TmpIface.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2018 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,71 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_GUI_TMPIFACE_HH_ -#define IGNITION_GAZEBO_GUI_TMPIFACE_HH_ + */ -#ifndef Q_MOC_RUN - #include -#endif - -#include -#include - -#include "ignition/gazebo/Export.hh" - -namespace ignition -{ - namespace gazebo - { - /// \brief Temporary place to prototype transport interfaces while it's not - /// clear where they will live. - /// - /// Move API from here to their appropriate locations once that's known. - /// - /// This class should be removed before releasing! - class IGNITION_GAZEBO_VISIBLE TmpIface : public QObject - { - Q_OBJECT - - /// \brief Constructor: advertize services and topics - public: TmpIface(); - - /// \brief Destructor - public: ~TmpIface() override = default; - - /// \brief Callback when user asks to start a new world. - /// This is the client-side logic which requests the server_control - /// service. - public slots: void OnNewWorld(); - - /// \brief Callback when user asks to load a world file. - /// This is the client-side logic which requests the server_control - /// service. - /// \param[in] _path Path to world file. - public slots: void OnLoadWorld(const QString &_path); - - /// \brief Callback when user asks to save a world file providing a path. - /// This is the client-side logic which requests the server_control - /// service. - /// \param[in] _path Path to world file. - public slots: void OnSaveWorldAs(const QString &_path); - - /// \brief This function does nothing and is kept only for retaining ABI - /// compatibility. /server_control service handling was moved to - /// ServerPrivate. - /// \param[in] _req Request - /// \param[out] _res Response - /// \return False. - private: bool IGN_DEPRECATED(3) OnServerControl( - const msgs::ServerControl &_req, msgs::Boolean &_res); - - /// \brief Communication node - private: transport::Node node; - - /// \brief Publisher - private: transport::Node::Publisher worldStatsPub; - }; - } -} -#endif +#include +#include diff --git a/include/ignition/gazebo/ign/gazebo/Export.hh b/include/ignition/gazebo/ign/gazebo/Export.hh new file mode 100644 index 0000000000..a851891bca --- /dev/null +++ b/include/ignition/gazebo/ign/gazebo/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/ignition/gazebo/Export.hh b/include/ignition/gazebo/ignition/gazebo/Export.hh new file mode 100644 index 0000000000..a851891bca --- /dev/null +++ b/include/ignition/gazebo/ignition/gazebo/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/imu-system/Export.hh b/include/ignition/gazebo/imu-system/Export.hh new file mode 100644 index 0000000000..3297991023 --- /dev/null +++ b/include/ignition/gazebo/imu-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/joint-controller-system/Export.hh b/include/ignition/gazebo/joint-controller-system/Export.hh new file mode 100644 index 0000000000..60bde96540 --- /dev/null +++ b/include/ignition/gazebo/joint-controller-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/joint-position-controller-system/Export.hh b/include/ignition/gazebo/joint-position-controller-system/Export.hh new file mode 100644 index 0000000000..83b02db5b9 --- /dev/null +++ b/include/ignition/gazebo/joint-position-controller-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/joint-state-publisher-system/Export.hh b/include/ignition/gazebo/joint-state-publisher-system/Export.hh new file mode 100644 index 0000000000..0a97d304b4 --- /dev/null +++ b/include/ignition/gazebo/joint-state-publisher-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/kinetic-energy-monitor-system/Export.hh b/include/ignition/gazebo/kinetic-energy-monitor-system/Export.hh new file mode 100644 index 0000000000..785d8a30d6 --- /dev/null +++ b/include/ignition/gazebo/kinetic-energy-monitor-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/lift-drag-system/Export.hh b/include/ignition/gazebo/lift-drag-system/Export.hh new file mode 100644 index 0000000000..3ec1e55260 --- /dev/null +++ b/include/ignition/gazebo/lift-drag-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/linearbatteryplugin-system/Export.hh b/include/ignition/gazebo/linearbatteryplugin-system/Export.hh new file mode 100644 index 0000000000..3c57ecdd44 --- /dev/null +++ b/include/ignition/gazebo/linearbatteryplugin-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/log-system/Export.hh b/include/ignition/gazebo/log-system/Export.hh new file mode 100644 index 0000000000..3d16d058f6 --- /dev/null +++ b/include/ignition/gazebo/log-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/log-video-recorder-system/Export.hh b/include/ignition/gazebo/log-video-recorder-system/Export.hh new file mode 100644 index 0000000000..f9dca5ae69 --- /dev/null +++ b/include/ignition/gazebo/log-video-recorder-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/logical-camera-system/Export.hh b/include/ignition/gazebo/logical-camera-system/Export.hh new file mode 100644 index 0000000000..5eafafc63a --- /dev/null +++ b/include/ignition/gazebo/logical-camera-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/logicalaudiosensorplugin-system/Export.hh b/include/ignition/gazebo/logicalaudiosensorplugin-system/Export.hh new file mode 100644 index 0000000000..43290664f1 --- /dev/null +++ b/include/ignition/gazebo/logicalaudiosensorplugin-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/magnetometer-system/Export.hh b/include/ignition/gazebo/magnetometer-system/Export.hh new file mode 100644 index 0000000000..83bed9d98c --- /dev/null +++ b/include/ignition/gazebo/magnetometer-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/multicopter-control-system/Export.hh b/include/ignition/gazebo/multicopter-control-system/Export.hh new file mode 100644 index 0000000000..5d36126af1 --- /dev/null +++ b/include/ignition/gazebo/multicopter-control-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/multicopter-motor-model-system/Export.hh b/include/ignition/gazebo/multicopter-motor-model-system/Export.hh new file mode 100644 index 0000000000..247da7a23b --- /dev/null +++ b/include/ignition/gazebo/multicopter-motor-model-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/performer-detector-system/Export.hh b/include/ignition/gazebo/performer-detector-system/Export.hh new file mode 100644 index 0000000000..baeea5cacc --- /dev/null +++ b/include/ignition/gazebo/performer-detector-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/physics-system/Export.hh b/include/ignition/gazebo/physics-system/Export.hh new file mode 100644 index 0000000000..89de9ac8a1 --- /dev/null +++ b/include/ignition/gazebo/physics-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/physics/Events.hh b/include/ignition/gazebo/physics/Events.hh index 668e19a2ad..7c980873e7 100644 --- a/include/ignition/gazebo/physics/Events.hh +++ b/include/ignition/gazebo/physics/Events.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,53 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_PHYSICS_EVENTS_HH_ -#define IGNITION_GAZEBO_PHYSICS_EVENTS_HH_ + */ -#include - -#include - -#include - -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Entity.hh" - -#include - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - - namespace events - { - using Policy = physics::FeaturePolicy3d; - - /// \brief This event is called when the physics engine needs to collect - /// what customizations it should do to the surface of a contact point. It - /// is called during the Update phase after collision checking has been - /// finished and before the physics update has happened. The event - /// subscribers are expected to change the `params` argument. - using CollectContactSurfaceProperties = ignition::common::EventT< - void( - const Entity& /* collision1 */, - const Entity& /* collision2 */, - const math::Vector3d & /* point */, - const std::optional /* force */, - const std::optional /* normal */, - const std::optional /* depth */, - const size_t /* numContactsOnCollision */, - physics::SetContactPropertiesCallbackFeature:: - ContactSurfaceParams& /* params */ - ), - struct CollectContactSurfacePropertiesTag>; - } - } // namespace events - } // namespace gazebo -} // namespace ignition - -#endif // IGNITION_GAZEBO_PHYSICS_EVENTS_HH_ +#include +#include diff --git a/include/ignition/gazebo/pose-publisher-system/Export.hh b/include/ignition/gazebo/pose-publisher-system/Export.hh new file mode 100644 index 0000000000..9c39026656 --- /dev/null +++ b/include/ignition/gazebo/pose-publisher-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/rendering/Events.hh b/include/ignition/gazebo/rendering/Events.hh index d17b3922c5..2acd63172f 100644 --- a/include/ignition/gazebo/rendering/Events.hh +++ b/include/ignition/gazebo/rendering/Events.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,49 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_RENDERING_EVENTS_HH_ -#define IGNITION_GAZEBO_RENDERING_EVENTS_HH_ + */ - -#include - -#include "ignition/gazebo/config.hh" - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - /// \brief Namespace for all events. Refer to the EventManager class for - /// more information about events. - namespace events - { - /// \brief The render event is emitted before rendering updates. - /// The event is emitted in the rendering thread so rendering - /// calls can ben make in this event callback - /// - /// For example: - /// \code - /// eventManager.Emit(); - /// \endcode - using PreRender = ignition::common::EventT; - - /// \brief The render event is emitted after rendering updates. - /// The event is emitted in the rendering thread so rendering - /// calls can ben make in this event callback - /// - /// For example: - /// \code - /// eventManager.Emit(); - /// \endcode - using PostRender = ignition::common::EventT; - } - } // namespace events - } // namespace gazebo -} // namespace ignition - -#endif // IGNITION_GAZEBO_RENDEREVENTS_HH_ +#include +#include diff --git a/include/ignition/gazebo/rendering/Export.hh b/include/ignition/gazebo/rendering/Export.hh new file mode 100644 index 0000000000..f36ae6b28c --- /dev/null +++ b/include/ignition/gazebo/rendering/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/rendering/MarkerManager.hh b/include/ignition/gazebo/rendering/MarkerManager.hh index 691d08fdbc..989367fb63 100644 --- a/include/ignition/gazebo/rendering/MarkerManager.hh +++ b/include/ignition/gazebo/rendering/MarkerManager.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,65 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_MARKERMANAGER_HH_ -#define IGNITION_GAZEBO_MARKERMANAGER_HH_ + */ -#include -#include - -#include - -#include "ignition/rendering/RenderTypes.hh" - -namespace ignition -{ -namespace gazebo -{ -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -// Forward declare private data class. -class MarkerManagerPrivate; - -/// \brief Creates, deletes, and maintains marker visuals. Only the -/// Scene class should instantiate and use this class. -class IGNITION_GAZEBO_RENDERING_VISIBLE MarkerManager -{ - /// \brief Constructor - public: MarkerManager(); - - /// \brief Destructor - public: virtual ~MarkerManager(); - - /// \brief Set the simulation time. - /// \param[in] _time The provided time. - public: void SetSimTime(const std::chrono::steady_clock::duration &_time); - - /// \brief Set the scene to manage - /// \param[in] _scene Scene pointer. - public: void SetScene(rendering::ScenePtr _scene); - - /// \brief Get the scene - /// \return Pointer to scene - public: rendering::ScenePtr Scene() const; - - /// \brief Update MarkerManager - public: void Update(); - - /// \brief Initialize the marker manager. - /// \param[in] _scene Reference to the scene. - /// \return True on success - public: bool Init(const ignition::rendering::ScenePtr &_scene); - - /// \brief Set the marker service topic name. - /// \param[in] _name Name of service - public: void SetTopic(const std::string &_name); - - /// \internal - /// \brief Private data pointer - private: std::unique_ptr dataPtr; -}; -} - -} -} -#endif +#include +#include diff --git a/include/ignition/gazebo/rendering/RenderUtil.hh b/include/ignition/gazebo/rendering/RenderUtil.hh index 7cc824a632..ea17e4da91 100644 --- a/include/ignition/gazebo/rendering/RenderUtil.hh +++ b/include/ignition/gazebo/rendering/RenderUtil.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,155 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_RENDERUTIL_HH_ -#define IGNITION_GAZEBO_RENDERUTIL_HH_ - -#include -#include -#include - -#include + */ +#include #include -#include -#include - -#include "ignition/gazebo/rendering/SceneManager.hh" -#include "ignition/gazebo/rendering/MarkerManager.hh" - - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // forward declaration - class RenderUtilPrivate; - - /// \class RenderUtil RenderUtil.hh ignition/gazebo/gui/plugins/RenderUtil.hh - class IGNITION_GAZEBO_RENDERING_VISIBLE RenderUtil - { - /// \brief Constructor - public: explicit RenderUtil(); - - /// \brief Destructor - public: ~RenderUtil(); - - /// \brief Initialize the renderer. Must be called in the rendering thread. - public: void Init(); - - /// \brief Count of pending sensors. Must be called in the rendering thread. - /// \return Number of sensors to be added on the next `Update` call - /// - /// In the case that RenderUtil has not been initialized, this method - /// will return -1. - public: int PendingSensors() const; - - /// \brief Main update function. Must be called in the rendering thread. - public: void Update(); - - /// \brief Get a pointer to the scene - /// \return Pointer to the scene - public: rendering::ScenePtr Scene() const; - - /// \brief Helper PostUpdate function for updating the scene - public: void UpdateFromECM(const UpdateInfo &_info, - const EntityComponentManager &_ecm); - - /// \brief Set the rendering engine to use - /// \param[in] _engineName Name of the rendering engine. - public: void SetEngineName(const std::string &_engineName); - - /// \brief Get the name of the rendering engine used - /// \return Name of the rendering engine - public: std::string EngineName() const; - - /// \brief Set the scene to use - /// \param[in] _sceneName Name of the engine. - public: void SetSceneName(const std::string &_sceneName); - - /// \brief Get the name of the rendering scene used - /// \return Name of the rendering scene. - public: std::string SceneName() const; - - /// \brief Set background color of render window. This will override - /// other sources, such as from SDF. - /// \param[in] _color Color of render window background - public: void SetBackgroundColor(const math::Color &_color); - - /// \brief Set ambient light of render window. This will override - /// other sources, such as from SDF. - /// \param[in] _ambient Color of ambient light - public: void SetAmbientLight(const math::Color &_ambient); - - /// \brief Show grid view in the scene - public: void ShowGrid(); - - /// \brief Set whether to use the current GL context - /// \param[in] _enable True to use the current GL context - public: void SetUseCurrentGLContext(bool _enable); - - /// \brief Set whether to create rendering sensors - /// \param[in] _enable True to create rendering sensors - /// \param[in] _createSensorCb Callback function for creating the sensors - /// The callback function args are: sensor sdf, and parent name, and - /// returns the name of the rendering sensor created. - public: void SetEnableSensors(bool _enable, std::function< - std::string(const sdf::Sensor &, const std::string &)> - _createSensorCb = {}); - - /// \brief View collisions of specified entity which are shown in orange - /// \param[in] _entity Entity to view collisions - public: void ViewCollisions(const Entity &_entity); - - /// \brief Get the scene manager - /// Returns reference to the scene manager. - public: class SceneManager &SceneManager(); - - /// \brief Get the marker manager - /// Returns reference to the marker manager. - public: class MarkerManager &MarkerManager(); - - /// \brief Get simulation time that the current rendering state corresponds - /// to - /// \returns Simulation time. - public: std::chrono::steady_clock::duration SimTime() const; - - /// \brief Set the entity being selected - /// \param[in] _node Node representing the selected entity - /// TODO(anyone) Make const ref when merging forward - // NOLINTNEXTLINE - public: void SetSelectedEntity(rendering::NodePtr _node); - - /// \brief Get the entity for a given node. - /// \param[in] _node Node to get the entity for. - /// \return The entity for that node, or `kNullEntity` for no entity. - /// \deprecated Use `ignition::rendering::Visual::UserData` instead. - public: Entity IGN_DEPRECATED(3) - EntityFromNode(const rendering::NodePtr &_node); - - /// \brief Get the entity being selected. This will only return the - /// last entity selected. - /// TODO(anyone) Deprecate in favour of SelectedEntities - public: rendering::NodePtr SelectedEntity() const; - - /// \brief Get the entities currently selected, in order of selection. - /// \return Vector of currently selected entities - public: std::vector SelectedEntities() const; - - /// \brief Clears the set of selected entities and lowlights all of them. - public: void DeselectAllEntities(); - - /// \brief Set whether the transform controls are currently being dragged. - /// \param[in] _active True if active. - public: void SetTransformActive(bool _active); - - /// \brief Private data pointer. - private: std::unique_ptr dataPtr; - }; -} -} -} -#endif diff --git a/include/ignition/gazebo/rendering/SceneManager.hh b/include/ignition/gazebo/rendering/SceneManager.hh index ca2261a481..d70a9cb94a 100644 --- a/include/ignition/gazebo/rendering/SceneManager.hh +++ b/include/ignition/gazebo/rendering/SceneManager.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -15,198 +15,5 @@ * */ -#ifndef IGNITION_GAZEBO_SCENEMANAGER_HH_ -#define IGNITION_GAZEBO_SCENEMANAGER_HH_ - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include - -#include - -#include - +#include #include -#include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // Forward declaration - class SceneManagerPrivate; - - /// \brief Scene manager class for loading and managing objects in the scene - class IGNITION_GAZEBO_RENDERING_VISIBLE SceneManager - { - /// \brief Constructor - public: SceneManager(); - - /// \brief Destructor - public: ~SceneManager(); - - /// \brief Set the scene to manage - /// \param[in] _scene Scene pointer. - public: void SetScene(rendering::ScenePtr _scene); - - /// \brief Get the scene - /// \return Pointer to scene - public: rendering::ScenePtr Scene() const; - - /// \brief Set the world's ID. - /// \param[in] _id World ID. - public: void SetWorldId(Entity _id); - - /// \brief Get the world's ID. - /// \return World ID - public: Entity WorldId() const; - - /// \brief Create a model - /// \param[in] _id Unique model id - /// \param[in] _model Model sdf dom - /// \param[in] _parentId Parent id - /// \return Model visual created from the sdf dom - public: rendering::VisualPtr CreateModel(Entity _id, - const sdf::Model &_model, Entity _parentId = 0); - - /// \brief Create a link - /// \param[in] _id Unique link id - /// \param[in] _link Link sdf dom - /// \param[in] _parentId Parent id - /// \return Link visual created from the sdf dom - public: rendering::VisualPtr CreateLink(Entity _id, - const sdf::Link &_link, Entity _parentId = 0); - - /// \brief Create a visual - /// \param[in] _id Unique visual id - /// \param[in] _visual Visual sdf dom - /// \param[in] _parentId Parent id - /// \return Visual object created from the sdf dom - public: rendering::VisualPtr CreateVisual(Entity _id, - const sdf::Visual &_visual, Entity _parentId = 0); - - /// \brief Create a collision visual - /// \param[in] _id Unique visual id - /// \param[in] _collision Collision sdf dom - /// \param[in] _parentId Parent id - /// \return Visual (collision) object created from the sdf dom - public: rendering::VisualPtr CreateCollision(Entity _id, - const sdf::Collision &_collision, Entity _parentId = 0); - - /// \brief Retrieve visual - /// \param[in] _id Unique visual (entity) id - /// \return Pointer to requested visual - public: rendering::VisualPtr VisualById(Entity _id); - - /// \brief Create an actor - /// \param[in] _id Unique actor id - /// \param[in] _actor Actor sdf dom - /// \param[in] _parentId Parent id - /// \return Actor object created from the sdf dom - public: rendering::VisualPtr CreateActor(Entity _id, - const sdf::Actor &_actor, Entity _parentId = 0); - - /// \brief Create a light - /// \param[in] _id Unique light id - /// \param[in] _light Light sdf dom - /// \param[in] _parentId Parent id - /// \return Light object created from the sdf dom - public: rendering::LightPtr CreateLight(Entity _id, - const sdf::Light &_light, Entity _parentId); - - /// \brief Ignition sensors is the one responsible for adding sensors - /// to the scene. Here we just keep track of it and make sure it has - /// the correct parent. - /// \param[in] _gazeboId Entity in Gazebo - /// \param[in] _sensorName Name of sensor node in Ignition Rendering. - /// \param[in] _parentGazeboId Parent Id on Gazebo. - /// \return True if sensor is successfully handled - public: bool AddSensor(Entity _gazeboId, const std::string &_sensorName, - Entity _parentGazeboId = 0); - - /// \brief Check if entity exists - /// \param[in] _id Unique entity id - /// \return true if exists, false otherwise - public: bool HasEntity(Entity _id) const; - - /// \brief Get a rendering node given an entity id - /// \param[in] _id Entity's unique id - /// \return Pointer to requested entity's node - public: rendering::NodePtr NodeById(Entity _id) const; - - /// \brief Get a rendering mesh given an id - /// \param[in] _id Actor entity's unique id - /// \return Pointer to requested entity's mesh - public: rendering::MeshPtr ActorMeshById(Entity _id) const; - - /// \brief Get the animation of actor mesh given an id - /// \param[in] _id Entity's unique id - /// \param[in] _time Timepoint for the animation - /// \return Map from the skeleton node name to transforms - public: std::map ActorMeshAnimationAt( - Entity _id, std::chrono::steady_clock::duration _time) const; - - /// \brief Remove an entity by id - /// \param[in] _id Entity's unique id - public: void RemoveEntity(Entity _id); - - /// \brief Get the entity for a given node. - /// \param[in] _node Node to get the entity for. - /// \return The entity for that node, or `kNullEntity` for no entity. - /// \todo(anyone) Deprecate in favour of - /// `ignition::rendering::Node::UserData` once that's available. - public: Entity EntityFromNode(const rendering::NodePtr &_node) const; - - /// \brief Load a geometry - /// \param[in] _geom Geometry sdf dom - /// \param[out] _scale Geometry scale that will be set based on sdf - /// \param[out] _localPose Additional local pose to be applied after the - /// visual's pose - /// \return Geometry object loaded from the sdf dom - private: rendering::GeometryPtr LoadGeometry(const sdf::Geometry &_geom, - math::Vector3d &_scale, math::Pose3d &_localPose); - - /// \brief Load a material - /// \param[in] _material Material sdf dom - /// \return Material object loaded from the sdf dom - private: rendering::MaterialPtr LoadMaterial( - const sdf::Material &_material); - - /// \brief Get the top level visual for the given visual, which - /// is the ancestor which is a direct child to the root visual. - /// Usually, this will be a model or a light. - /// \param[in] _visual Child visual - /// \return Top level visual containining this visual - /// TODO(anyone) Make it const ref when merging forward - public: rendering::VisualPtr TopLevelVisual( - // NOLINTNEXTLINE - rendering::VisualPtr _visual) const; - - /// \brief Get the top level node for the given node, which - /// is the ancestor which is a direct child to the root visual. - /// Usually, this will be a model or a light. - /// \param[in] _node Child node - /// \return Top level node containining this node - public: rendering::NodePtr TopLevelNode( - const rendering::NodePtr &_node) const; - - /// \internal - /// \brief Pointer to private data class - private: std::unique_ptr dataPtr; - }; -} -} -} - -#endif diff --git a/include/ignition/gazebo/scene-broadcaster-system/Export.hh b/include/ignition/gazebo/scene-broadcaster-system/Export.hh new file mode 100644 index 0000000000..292963308c --- /dev/null +++ b/include/ignition/gazebo/scene-broadcaster-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/sensors-system/Export.hh b/include/ignition/gazebo/sensors-system/Export.hh new file mode 100644 index 0000000000..eab1c2b6ea --- /dev/null +++ b/include/ignition/gazebo/sensors-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/thermal-system/Export.hh b/include/ignition/gazebo/thermal-system/Export.hh new file mode 100644 index 0000000000..cfaf2c966c --- /dev/null +++ b/include/ignition/gazebo/thermal-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/touchplugin-system/Export.hh b/include/ignition/gazebo/touchplugin-system/Export.hh new file mode 100644 index 0000000000..dc607b58e5 --- /dev/null +++ b/include/ignition/gazebo/touchplugin-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/track-controller-system/Export.hh b/include/ignition/gazebo/track-controller-system/Export.hh new file mode 100644 index 0000000000..8d889cede5 --- /dev/null +++ b/include/ignition/gazebo/track-controller-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/tracked-vehicle-system/Export.hh b/include/ignition/gazebo/tracked-vehicle-system/Export.hh new file mode 100644 index 0000000000..23e09e029c --- /dev/null +++ b/include/ignition/gazebo/tracked-vehicle-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/triggered-publisher-system/Export.hh b/include/ignition/gazebo/triggered-publisher-system/Export.hh new file mode 100644 index 0000000000..81b88be375 --- /dev/null +++ b/include/ignition/gazebo/triggered-publisher-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/user-commands-system/Export.hh b/include/ignition/gazebo/user-commands-system/Export.hh new file mode 100644 index 0000000000..607ca54f5a --- /dev/null +++ b/include/ignition/gazebo/user-commands-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/velocity-control-system/Export.hh b/include/ignition/gazebo/velocity-control-system/Export.hh new file mode 100644 index 0000000000..cf1402da98 --- /dev/null +++ b/include/ignition/gazebo/velocity-control-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/wheel-slip-system/Export.hh b/include/ignition/gazebo/wheel-slip-system/Export.hh new file mode 100644 index 0000000000..49a3579b0e --- /dev/null +++ b/include/ignition/gazebo/wheel-slip-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/include/ignition/gazebo/wind-effects-system/Export.hh b/include/ignition/gazebo/wind-effects-system/Export.hh new file mode 100644 index 0000000000..310dd4e596 --- /dev/null +++ b/include/ignition/gazebo/wind-effects-system/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include diff --git a/src/Barrier.cc b/src/Barrier.cc index 97dc9f7b36..3bafb2af04 100644 --- a/src/Barrier.cc +++ b/src/Barrier.cc @@ -17,6 +17,7 @@ #include "Barrier.hh" + class ignition::gazebo::BarrierPrivate { /// \brief Mutex for syncronization @@ -97,4 +98,3 @@ void Barrier::Cancel() this->dataPtr->cancelled = true; this->dataPtr->cv.notify_all(); } - diff --git a/src/Barrier.hh b/src/Barrier.hh index e0f6dcf10d..743e5c1282 100644 --- a/src/Barrier.hh +++ b/src/Barrier.hh @@ -15,16 +15,16 @@ * */ -#ifndef IGNITION_GAZEBO_BARRIER_HH_ -#define IGNITION_GAZEBO_BARRIER_HH_ +#ifndef GZ_GAZEBO_BARRIER_HH_ +#define GZ_GAZEBO_BARRIER_HH_ #include #include #include #include -#include -#include +#include +#include namespace ignition { @@ -92,4 +92,4 @@ namespace ignition } // namespace gazebo } // namespace ignition -#endif // IGNITION_GAZEBO_BARRIER_HH_ +#endif // GZ_GAZEBO_BARRIER_HH_ diff --git a/src/Barrier_TEST.cc b/src/Barrier_TEST.cc index 8f57127851..411a68e8ca 100644 --- a/src/Barrier_TEST.cc +++ b/src/Barrier_TEST.cc @@ -21,18 +21,18 @@ #include "Barrier.hh" -using namespace ignition; +using namespace gz; ////////////////////////////////////////////////// -inline bool wasCancelled(const gazebo::Barrier::ExitStatus &_ret) +inline bool wasCancelled(const gz::sim::Barrier::ExitStatus &_ret) { - return _ret == gazebo::Barrier::ExitStatus::CANCELLED; + return _ret == gz::sim::Barrier::ExitStatus::CANCELLED; } ////////////////////////////////////////////////// void syncThreadsTest(unsigned int _threadCount) { - auto barrier = std::make_unique(_threadCount + 1); + auto barrier = std::make_unique(_threadCount + 1); unsigned int preBarrier { 0 }; unsigned int postBarrier { 0 }; @@ -51,7 +51,7 @@ void syncThreadsTest(unsigned int _threadCount) } EXPECT_EQ(barrier->Wait(), - gazebo::Barrier::ExitStatus::DONE); + gz::sim::Barrier::ExitStatus::DONE); { std::lock_guard lock(mutex); @@ -74,7 +74,7 @@ void syncThreadsTest(unsigned int _threadCount) // Give time for the last thread to call Wait std::this_thread::sleep_for(std::chrono::milliseconds(100)); - EXPECT_EQ(barrier->Wait(), gazebo::Barrier::ExitStatus::DONE_LAST); + EXPECT_EQ(barrier->Wait(), gz::sim::Barrier::ExitStatus::DONE_LAST); { std::unique_lock lock(mutex); @@ -125,7 +125,7 @@ TEST(Barrier, Cancel) { // Use 3 as number of threads, but only create one, which // guarantees it won't make it past `wait` - auto barrier = std::make_unique(3); + auto barrier = std::make_unique(3); unsigned int preBarrier { 0 }; unsigned int postBarrier { 0 }; diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index e20b7b2c5b..59a1e99180 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -33,7 +33,7 @@ set(gui_sources ign_add_component(ign SOURCES - ign.cc + gz.cc cmd/ModelCommandAPI.cc GET_TARGET_NAME ign_lib_target) target_link_libraries(${ign_lib_target} @@ -77,7 +77,7 @@ set (gtest_sources Conversions_TEST.cc EntityComponentManager_TEST.cc EventManager_TEST.cc - ign_TEST.cc + gz_TEST.cc Link_TEST.cc Model_TEST.cc ModelCommandAPI_TEST.cc @@ -144,7 +144,7 @@ ign_build_tests(TYPE UNIT # Command line tests need extra settings foreach(CMD_TEST - UNIT_ign_TEST + UNIT_gz_TEST UNIT_ModelCommandAPI_TEST) if(NOT TARGET ${CMD_TEST}) @@ -183,4 +183,3 @@ endforeach() if(NOT WIN32) add_subdirectory(cmd) endif() - diff --git a/src/ComponentFactory_TEST.cc b/src/ComponentFactory_TEST.cc index 68957a503f..beb130e3ce 100644 --- a/src/ComponentFactory_TEST.cc +++ b/src/ComponentFactory_TEST.cc @@ -16,15 +16,15 @@ */ #include -#include "ignition/gazebo/test_config.hh" -#include "ignition/gazebo/components/Component.hh" -#include "ignition/gazebo/components/Factory.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/Pose.hh" #include "../test/helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ///////////////////////////////////////////////// class ComponentFactoryTest : public InternalFixture<::testing::Test> diff --git a/src/Component_TEST.cc b/src/Component_TEST.cc index 1b03f4e547..61bc1710d6 100644 --- a/src/Component_TEST.cc +++ b/src/Component_TEST.cc @@ -16,23 +16,23 @@ */ #include -#include +#include #include #include -#include -#include +#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" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ////////////////////////////////////////////////// class ComponentTest : public InternalFixture<::testing::Test> diff --git a/src/Conversions.cc b/src/Conversions.cc index 7e874dce05..72a7ea6f06 100644 --- a/src/Conversions.cc +++ b/src/Conversions.cc @@ -15,29 +15,29 @@ * */ -#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 @@ -61,11 +61,11 @@ #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; +using namespace gz; ////////////////////////////////////////////////// template<> diff --git a/src/Conversions_TEST.cc b/src/Conversions_TEST.cc index a9c2cc038e..428fac0dee 100644 --- a/src/Conversions_TEST.cc +++ b/src/Conversions_TEST.cc @@ -36,12 +36,12 @@ #include #include -#include +#include -#include "ignition/gazebo/Conversions.hh" +#include "gz/sim/Conversions.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; ///////////////////////////////////////////////// diff --git a/src/EntityComponentManager.cc b/src/EntityComponentManager.cc index 0203a435e0..67c76857ec 100644 --- a/src/EntityComponentManager.cc +++ b/src/EntityComponentManager.cc @@ -23,16 +23,16 @@ #include #include -#include -#include -#include "ignition/gazebo/components/Component.hh" -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/EntityComponentManager.hh" +#include +#include +#include "gz/sim/components/Component.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/EntityComponentManager.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; -class ignition::gazebo::EntityComponentManagerPrivate +class gz::sim::EntityComponentManagerPrivate { /// \brief Implementation of the CreateEntity function, which takes a specific /// entity as input. @@ -1303,7 +1303,7 @@ void EntityComponentManager::SetAllComponentsUnchanged() ///////////////////////////////////////////////// void EntityComponentManager::SetChanged( const Entity _entity, const ComponentTypeId _type, - gazebo::ComponentState _c) + gz::sim::ComponentState _c) { auto ecIter = this->dataPtr->entityComponents.find(_entity); diff --git a/src/EntityComponentManager_TEST.cc b/src/EntityComponentManager_TEST.cc index 3a56e0526a..28853f95d6 100644 --- a/src/EntityComponentManager_TEST.cc +++ b/src/EntityComponentManager_TEST.cc @@ -17,18 +17,18 @@ #include -#include -#include -#include - -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/config.hh" +#include +#include +#include + +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/config.hh" #include "../test/helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace components; namespace ignition diff --git a/src/EventManager.cc b/src/EventManager.cc index 656c816607..8977e89715 100644 --- a/src/EventManager.cc +++ b/src/EventManager.cc @@ -14,10 +14,10 @@ * limitations under the License. * */ -#include "ignition/gazebo/EventManager.hh" +#include "gz/sim/EventManager.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ////////////////////////////////////////////////// EventManager::EventManager() = default; diff --git a/src/EventManager_TEST.cc b/src/EventManager_TEST.cc index c68335e723..78ef5cda90 100644 --- a/src/EventManager_TEST.cc +++ b/src/EventManager_TEST.cc @@ -19,10 +19,10 @@ #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; +using namespace gz::sim; ///////////////////////////////////////////////// TEST(EventManager, EmitConnectTest) @@ -68,7 +68,7 @@ TEST(EventManager, NewEvent) { EventManager eventManager; - using TestEvent = ignition::common::EventT; + using TestEvent = gz::common::EventT; std::string val1, val2; auto connection = eventManager.Connect( @@ -91,8 +91,8 @@ TEST(EventManager, NewEvent) TEST(EventManager, Ambiguous) { EventManager eventManager; - using TestEvent1 = ignition::common::EventT; - using TestEvent2 = ignition::common::EventT; + using TestEvent1 = gz::common::EventT; + using TestEvent2 = gz::common::EventT; std::atomic calls = 0; auto connection = eventManager.Connect([&](){ calls++;}); @@ -107,8 +107,8 @@ TEST(EventManager, Ambiguous) TEST(EventManager, Disambiguate) { EventManager eventManager; - using TestEvent1 = ignition::common::EventT; - using TestEvent2 = ignition::common::EventT; + using TestEvent1 = gz::common::EventT; + using TestEvent2 = gz::common::EventT; std::atomic calls = 0; auto connection1 = eventManager.Connect([&](){ calls++;}); diff --git a/src/LevelManager.cc b/src/LevelManager.cc index ed585c70cf..b08cf26d0b 100644 --- a/src/LevelManager.cc +++ b/src/LevelManager.cc @@ -25,40 +25,40 @@ #include #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/RenderEngineServerPlugin.hh" -#include "ignition/gazebo/components/Scene.hh" -#include "ignition/gazebo/components/Wind.hh" -#include "ignition/gazebo/components/World.hh" +#include + +#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/RenderEngineServerPlugin.hh" +#include "gz/sim/components/Scene.hh" +#include "gz/sim/components/Wind.hh" +#include "gz/sim/components/World.hh" #include "SimulationRunner.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ///////////////////////////////////////////////// LevelManager::LevelManager(SimulationRunner *_runner, const bool _useLevels) @@ -151,10 +151,10 @@ void LevelManager::ReadLevelPerformerInfo() // TODO(anyone) This should probably go somewhere else as it is a global // constant. - const std::string kPluginName{"ignition::gazebo"}; + const std::string kPluginName{"gz::sim"}; sdf::ElementPtr pluginElem; - // Get the ignition::gazebo plugin element + // Get the gz::sim plugin element for (auto plugin = worldElem->FindElement("plugin"); plugin; plugin = plugin->GetNextElement("plugin")) { diff --git a/src/LevelManager.hh b/src/LevelManager.hh index 556ad87d29..d872962afb 100644 --- a/src/LevelManager.hh +++ b/src/LevelManager.hh @@ -18,8 +18,8 @@ #ifndef IGNITION_GAZEBO_LEVELMANAGER_HH #define IGNITION_GAZEBO_LEVELMANAGER_HH -#include -#include +#include +#include #include #include @@ -31,12 +31,12 @@ #include #include -#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 { @@ -108,12 +108,12 @@ namespace ignition /// \brief Read information about performers from the sdf Element and /// create performer entities - /// \param[in] _sdf sdf::ElementPtr of the ignition::gazebo plugin tag + /// \param[in] _sdf sdf::ElementPtr of the gz::sim plugin tag private: void ReadPerformers(const sdf::ElementPtr &_sdf); /// \brief Read information about levels from the sdf Element and /// create level entities - /// \param[in] _sdf sdf::ElementPtr of the ignition::gazebo plugin tag + /// \param[in] _sdf sdf::ElementPtr of the gz::sim plugin tag private: void ReadLevels(const sdf::ElementPtr &_sdf); /// \brief Determine which entities belong to the default level and @@ -171,7 +171,7 @@ namespace ignition private: std::unique_ptr entityCreator{nullptr}; /// \brief Transport node. - private: ignition::transport::Node node; + private: gz::transport::Node node; /// \brief The list of performers to add. private: std::list> performersToAdd; diff --git a/src/Link.cc b/src/Link.cc index 41f814cd88..904d769d98 100644 --- a/src/Link.cc +++ b/src/Link.cc @@ -15,38 +15,38 @@ * */ -#include - -#include "ignition/gazebo/components/AngularVelocity.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/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" - -class ignition::gazebo::LinkPrivate +#include + +#include "gz/sim/components/AngularVelocity.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/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 gz::sim::LinkPrivate { /// \brief Id of link entity. public: Entity id{kNullEntity}; }; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ////////////////////////////////////////////////// -Link::Link(gazebo::Entity _entity) +Link::Link(gz::sim::Entity _entity) : dataPtr(std::make_unique()) { this->dataPtr->id = _entity; @@ -81,7 +81,7 @@ Entity Link::Entity() const } ////////////////////////////////////////////////// -void Link::ResetEntity(gazebo::Entity _newEntity) +void Link::ResetEntity(gz::sim::Entity _newEntity) { this->dataPtr->id = _newEntity; } diff --git a/src/Link_TEST.cc b/src/Link_TEST.cc index 5193c1f425..f5da1459f0 100644 --- a/src/Link_TEST.cc +++ b/src/Link_TEST.cc @@ -17,16 +17,16 @@ #include -#include "ignition/gazebo/Link.hh" +#include "gz/sim/Link.hh" ///////////////////////////////////////////////// TEST(LinkTest, Constructor) { - ignition::gazebo::Link linkNull; - EXPECT_EQ(ignition::gazebo::kNullEntity, linkNull.Entity()); + gz::sim::Link linkNull; + EXPECT_EQ(gz::sim::kNullEntity, linkNull.Entity()); - ignition::gazebo::Entity id(3); - ignition::gazebo::Link link(id); + gz::sim::Entity id(3); + gz::sim::Link link(id); EXPECT_EQ(id, link.Entity()); } @@ -34,22 +34,22 @@ TEST(LinkTest, Constructor) ///////////////////////////////////////////////// TEST(LinkTest, CopyConstructor) { - ignition::gazebo::Entity id(3); - ignition::gazebo::Link link(id); + gz::sim::Entity id(3); + gz::sim::Link link(id); // Marked nolint because we are specifically testing copy // constructor here (clang wants unnecessary copies removed) - ignition::gazebo::Link linkCopy(link); // NOLINT + gz::sim::Link linkCopy(link); // NOLINT EXPECT_EQ(link.Entity(), linkCopy.Entity()); } ///////////////////////////////////////////////// TEST(LinkTest, CopyAssignmentOperator) { - ignition::gazebo::Entity id(3); - ignition::gazebo::Link link(id); + gz::sim::Entity id(3); + gz::sim::Link link(id); - ignition::gazebo::Link linkCopy; + gz::sim::Link linkCopy; linkCopy = link; EXPECT_EQ(link.Entity(), linkCopy.Entity()); } @@ -57,20 +57,20 @@ TEST(LinkTest, CopyAssignmentOperator) ///////////////////////////////////////////////// TEST(LinkTest, MoveConstructor) { - ignition::gazebo::Entity id(3); - ignition::gazebo::Link link(id); + gz::sim::Entity id(3); + gz::sim::Link link(id); - ignition::gazebo::Link linkMoved(std::move(link)); + gz::sim::Link linkMoved(std::move(link)); EXPECT_EQ(id, linkMoved.Entity()); } ///////////////////////////////////////////////// TEST(LinkTest, MoveAssignmentOperator) { - ignition::gazebo::Entity id(3); - ignition::gazebo::Link link(id); + gz::sim::Entity id(3); + gz::sim::Link link(id); - ignition::gazebo::Link linkMoved; + gz::sim::Link linkMoved; linkMoved = std::move(link); EXPECT_EQ(id, linkMoved.Entity()); } diff --git a/src/Model.cc b/src/Model.cc index 0b59c1132b..5f63074151 100644 --- a/src/Model.cc +++ b/src/Model.cc @@ -15,29 +15,29 @@ * */ -#include "ignition/gazebo/components/CanonicalLink.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/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" - -class ignition::gazebo::ModelPrivate +#include "gz/sim/components/CanonicalLink.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 gz::sim::ModelPrivate { /// \brief Id of model entity. public: Entity id{kNullEntity}; }; -using namespace ignition::gazebo; +using namespace gz::sim; ////////////////////////////////////////////////// -Model::Model(gazebo::Entity _entity) +Model::Model(gz::sim::Entity _entity) : dataPtr(std::make_unique()) { this->dataPtr->id = _entity; diff --git a/src/ModelCommandAPI_TEST.cc b/src/ModelCommandAPI_TEST.cc index efb6225411..46b1f63760 100644 --- a/src/ModelCommandAPI_TEST.cc +++ b/src/ModelCommandAPI_TEST.cc @@ -21,8 +21,8 @@ #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 "); @@ -87,12 +87,12 @@ TEST(ModelCommandAPI, NoServerRunning) // Tests `ign model` command. TEST(ModelCommandAPI, Commands) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; // Using an static model to avoid any movements in the simulation. serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/static_diff_drive_vehicle.sdf"); - ignition::gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); // Run at least one iteration before continuing to guarantee correctly set up. ASSERT_TRUE(server.Run(true, 5, false)); // Run without blocking. diff --git a/src/Model_TEST.cc b/src/Model_TEST.cc index e6134f6860..7ad95464b0 100644 --- a/src/Model_TEST.cc +++ b/src/Model_TEST.cc @@ -17,16 +17,16 @@ #include -#include "ignition/gazebo/Model.hh" +#include "gz/sim/Model.hh" ///////////////////////////////////////////////// TEST(ModelTest, Constructor) { - ignition::gazebo::Model modelNull; - EXPECT_EQ(ignition::gazebo::kNullEntity, modelNull.Entity()); + gz::sim::Model modelNull; + EXPECT_EQ(gz::sim::kNullEntity, modelNull.Entity()); - ignition::gazebo::Entity id(3); - ignition::gazebo::Model model(id); + gz::sim::Entity id(3); + gz::sim::Model model(id); EXPECT_EQ(id, model.Entity()); } @@ -34,22 +34,22 @@ TEST(ModelTest, Constructor) ///////////////////////////////////////////////// TEST(ModelTest, CopyConstructor) { - ignition::gazebo::Entity id(3); - ignition::gazebo::Model model(id); + gz::sim::Entity id(3); + gz::sim::Model model(id); // Marked nolint because we are specifically testing copy // constructor here (clang wants unnecessary copies removed) - ignition::gazebo::Model modelCopy(model); // NOLINT + gz::sim::Model modelCopy(model); // NOLINT EXPECT_EQ(model.Entity(), modelCopy.Entity()); } ///////////////////////////////////////////////// TEST(ModelTest, CopyAssignmentOperator) { - ignition::gazebo::Entity id(3); - ignition::gazebo::Model model(id); + gz::sim::Entity id(3); + gz::sim::Model model(id); - ignition::gazebo::Model modelCopy; + gz::sim::Model modelCopy; modelCopy = model; EXPECT_EQ(model.Entity(), modelCopy.Entity()); } @@ -57,20 +57,20 @@ TEST(ModelTest, CopyAssignmentOperator) ///////////////////////////////////////////////// TEST(ModelTest, MoveConstructor) { - ignition::gazebo::Entity id(3); - ignition::gazebo::Model model(id); + gz::sim::Entity id(3); + gz::sim::Model model(id); - ignition::gazebo::Model modelMoved(std::move(model)); + gz::sim::Model modelMoved(std::move(model)); EXPECT_EQ(id, modelMoved.Entity()); } ///////////////////////////////////////////////// TEST(ModelTest, MoveAssignmentOperator) { - ignition::gazebo::Entity id(3); - ignition::gazebo::Model model(id); + gz::sim::Entity id(3); + gz::sim::Model model(id); - ignition::gazebo::Model modelMoved; + gz::sim::Model modelMoved; modelMoved = std::move(model); EXPECT_EQ(id, modelMoved.Entity()); } diff --git a/src/SdfEntityCreator.cc b/src/SdfEntityCreator.cc index ae0232872c..e40978a5b5 100644 --- a/src/SdfEntityCreator.cc +++ b/src/SdfEntityCreator.cc @@ -15,62 +15,62 @@ * */ -#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/DepthCamera.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/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/ParentLinkName.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#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/SelfCollide.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/SourceFilePath.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/Visual.hh" -#include "ignition/gazebo/components/WindMode.hh" -#include "ignition/gazebo/components/World.hh" - -class ignition::gazebo::SdfEntityCreatorPrivate +#include +#include + +#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/DepthCamera.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/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/ParentLinkName.hh" +#include "gz/sim/components/ParentEntity.hh" +#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/SelfCollide.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/SourceFilePath.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/Visual.hh" +#include "gz/sim/components/WindMode.hh" +#include "gz/sim/components/World.hh" + +class gz::sim::SdfEntityCreatorPrivate { /// \brief Pointer to entity component manager. We don't assume ownership. public: EntityComponentManager *ecm{nullptr}; @@ -91,8 +91,8 @@ class ignition::gazebo::SdfEntityCreatorPrivate public: std::map newVisuals; }; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ///////////////////////////////////////////////// /// \brief Resolve the pose of an SDF DOM object with respect to its relative_to diff --git a/src/SdfEntityCreator_TEST.cc b/src/SdfEntityCreator_TEST.cc index 605c04286d..7cafa6f133 100644 --- a/src/SdfEntityCreator_TEST.cc +++ b/src/SdfEntityCreator_TEST.cc @@ -16,7 +16,7 @@ */ #include -#include +#include #include #include #include @@ -25,35 +25,35 @@ #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/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/Visual.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/SdfEntityCreator.hh" #include "../test/helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ///////////////////////////////////////////////// class EntityCompMgrTest : public EntityComponentManager diff --git a/src/SdfGenerator.cc b/src/SdfGenerator.cc index 08b281b0a4..f7722f4f4c 100644 --- a/src/SdfGenerator.cc +++ b/src/SdfGenerator.cc @@ -22,16 +22,16 @@ #include -#include - -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/components/Light.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/SourceFilePath.hh" -#include "ignition/gazebo/components/World.hh" +#include + +#include "gz/sim/Util.hh" +#include "gz/sim/components/Light.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/SourceFilePath.hh" +#include "gz/sim/components/World.hh" namespace ignition diff --git a/src/SdfGenerator.hh b/src/SdfGenerator.hh index 5e267e9d9b..b88020c4ca 100644 --- a/src/SdfGenerator.hh +++ b/src/SdfGenerator.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SDFGENERATOR_HH_ -#define IGNITION_GAZEBO_SDFGENERATOR_HH_ +#ifndef GZ_GAZEBO_SDFGENERATOR_HH_ +#define GZ_GAZEBO_SDFGENERATOR_HH_ -#include +#include #include #include #include -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/EntityComponentManager.hh" namespace ignition { @@ -92,4 +92,4 @@ namespace sdf_generator } // namespace gazebo } // namespace ignition -#endif /* end of include guard: IGNITION_GAZEBO_SDFGENERATOR_HH_ */ +#endif /* end of include guard: GZ_GAZEBO_SDFGENERATOR_HH_ */ diff --git a/src/SdfGenerator_TEST.cc b/src/SdfGenerator_TEST.cc index 995ae9f54c..0d8b67e7bc 100644 --- a/src/SdfGenerator_TEST.cc +++ b/src/SdfGenerator_TEST.cc @@ -18,34 +18,34 @@ #include #include -#include -#include -#include +#include +#include +#include #include #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" #include "SdfGenerator.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ///////////////////////////////////////////////// /// \breif Checks if elemA is a subset of elemB diff --git a/src/Server.cc b/src/Server.cc index 7e7de3b975..deb622cf5d 100644 --- a/src/Server.cc +++ b/src/Server.cc @@ -15,21 +15,21 @@ * */ -#include -#include -#include +#include +#include +#include #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" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ////////////////////////////////////////////////// // Getting the first .sdf file in the path diff --git a/src/ServerConfig.cc b/src/ServerConfig.cc index a8ea6c6731..f61447e839 100644 --- a/src/ServerConfig.cc +++ b/src/ServerConfig.cc @@ -14,24 +14,24 @@ * limitations under the License. * */ -#include "ignition/gazebo/ServerConfig.hh" +#include "gz/sim/ServerConfig.hh" #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Private data for PluginInfoConfig. -class ignition::gazebo::ServerConfig::PluginInfoPrivate +class gz::sim::ServerConfig::PluginInfoPrivate { /// \brief Default constructor. public: PluginInfoPrivate() = default; @@ -192,7 +192,7 @@ void ServerConfig::PluginInfo::SetSdf(const sdf::ElementPtr &_sdf) } /// \brief Private data for ServerConfig. -class ignition::gazebo::ServerConfigPrivate +class gz::sim::ServerConfigPrivate { /// \brief Default constructor. public: ServerConfigPrivate() @@ -562,7 +562,7 @@ ServerConfig::LogPlaybackPlugin() const { auto entityName = "*"; auto entityType = "world"; - auto pluginName = "ignition::gazebo::systems::LogPlayback"; + auto pluginName = "gz::sim::systems::LogPlayback"; auto pluginFilename = "ignition-gazebo-log-system"; sdf::ElementPtr playbackElem; @@ -592,7 +592,7 @@ ServerConfig::LogRecordPlugin() const { auto entityName = "*"; auto entityType = "world"; - auto pluginName = "ignition::gazebo::systems::LogRecord"; + auto pluginName = "gz::sim::systems::LogRecord"; auto pluginFilename = std::string("ignition-gazebo") + IGNITION_GAZEBO_MAJOR_VERSION_STR + "-log-system"; @@ -800,7 +800,7 @@ parsePluginsFromDoc(const tinyxml2::XMLDocument &_doc) ///////////////////////////////////////////////// std::list -gazebo::parsePluginsFromFile(const std::string &_fname) +ignition::gazebo::parsePluginsFromFile(const std::string &_fname) { tinyxml2::XMLDocument doc; doc.LoadFile(_fname.c_str()); @@ -809,7 +809,7 @@ gazebo::parsePluginsFromFile(const std::string &_fname) ///////////////////////////////////////////////// std::list -gazebo::parsePluginsFromString(const std::string &_str) +ignition::gazebo::parsePluginsFromString(const std::string &_str) { tinyxml2::XMLDocument doc; doc.Parse(_str.c_str()); @@ -819,7 +819,7 @@ gazebo::parsePluginsFromString(const std::string &_str) ///////////////////////////////////////////////// std::list -gazebo::loadPluginInfo(bool _isPlayback) +ignition::gazebo::loadPluginInfo(bool _isPlayback) { std::list ret; @@ -834,7 +834,7 @@ gazebo::loadPluginInfo(bool _isPlayback) if (common::exists(envConfig)) { // Parse configuration stored in environment variable - ret = gazebo::parsePluginsFromFile(envConfig); + ret = gz::sim::parsePluginsFromFile(envConfig); if (ret.empty()) { // This may be desired behavior, but warn just in case. @@ -914,7 +914,7 @@ gazebo::loadPluginInfo(bool _isPlayback) } } - ret = gazebo::parsePluginsFromFile(defaultConfig); + ret = gz::sim::parsePluginsFromFile(defaultConfig); if (ret.empty()) { @@ -928,4 +928,3 @@ gazebo::loadPluginInfo(bool _isPlayback) return ret; } - diff --git a/src/ServerConfig_TEST.cc b/src/ServerConfig_TEST.cc index c97c0922cd..6b6e84adcd 100644 --- a/src/ServerConfig_TEST.cc +++ b/src/ServerConfig_TEST.cc @@ -17,13 +17,13 @@ #include -#include -#include -#include -#include +#include +#include +#include +#include -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ////////////////////////////////////////////////// TEST(ParsePluginsFromString, Valid) @@ -35,21 +35,21 @@ TEST(ParsePluginsFromString, Valid) entity_name="default" entity_type="world" filename="TestWorldSystem" - name="ignition::gazebo::TestWorldSystem"> + name="gz::sim::TestWorldSystem"> 0.123 + name="gz::sim::TestModelSystem"> 987 + name="gz::sim::TestSensorSystem"> 456 @@ -63,21 +63,21 @@ TEST(ParsePluginsFromString, Valid) EXPECT_EQ("default", plugin->EntityName()); EXPECT_EQ("world", plugin->EntityType()); EXPECT_EQ("TestWorldSystem", plugin->Filename()); - EXPECT_EQ("ignition::gazebo::TestWorldSystem", plugin->Name()); + EXPECT_EQ("gz::sim::TestWorldSystem", plugin->Name()); plugin = std::next(plugin, 1); EXPECT_EQ("box", plugin->EntityName()); EXPECT_EQ("model", plugin->EntityType()); EXPECT_EQ("TestModelSystem", plugin->Filename()); - EXPECT_EQ("ignition::gazebo::TestModelSystem", plugin->Name()); + EXPECT_EQ("gz::sim::TestModelSystem", plugin->Name()); plugin = std::next(plugin, 1); EXPECT_EQ("default::box::link_1::camera", plugin->EntityName()); EXPECT_EQ("sensor", plugin->EntityType()); EXPECT_EQ("TestSensorSystem", plugin->Filename()); - EXPECT_EQ("ignition::gazebo::TestSensorSystem", plugin->Name()); + EXPECT_EQ("gz::sim::TestSensorSystem", plugin->Name()); } ////////////////////////////////////////////////// @@ -89,7 +89,7 @@ TEST(ParsePluginsFromString, Invalid) entity_name="default" entity_type="world" filename="TestWorldSystem" - name="ignition::gazebo::TestWorldSystem"> + name="gz::sim::TestWorldSystem"> 0.123 )"; @@ -115,21 +115,21 @@ TEST(ParsePluginsFromFile, Valid) EXPECT_EQ("default", plugin->EntityName()); EXPECT_EQ("world", plugin->EntityType()); EXPECT_EQ("TestWorldSystem", plugin->Filename()); - EXPECT_EQ("ignition::gazebo::TestWorldSystem", plugin->Name()); + EXPECT_EQ("gz::sim::TestWorldSystem", plugin->Name()); plugin = std::next(plugin, 1); EXPECT_EQ("box", plugin->EntityName()); EXPECT_EQ("model", plugin->EntityType()); EXPECT_EQ("TestModelSystem", plugin->Filename()); - EXPECT_EQ("ignition::gazebo::TestModelSystem", plugin->Name()); + EXPECT_EQ("gz::sim::TestModelSystem", plugin->Name()); plugin = std::next(plugin, 1); EXPECT_EQ("default::box::link_1::camera", plugin->EntityName()); EXPECT_EQ("sensor", plugin->EntityType()); EXPECT_EQ("TestSensorSystem", plugin->Filename()); - EXPECT_EQ("ignition::gazebo::TestSensorSystem", plugin->Name()); + EXPECT_EQ("gz::sim::TestSensorSystem", plugin->Name()); } ////////////////////////////////////////////////// @@ -155,7 +155,7 @@ TEST(ParsePluginsFromFile, DefaultConfig) // If more systems are added, then the number needs // to be adjusted below. auto config = common::joinPaths(PROJECT_SOURCE_PATH, - "include", "ignition", "gazebo", "server.config"); + "include", "gz", "sim", "server.config"); auto plugins = parsePluginsFromFile(config); ASSERT_EQ(3u, plugins.size()); @@ -169,7 +169,7 @@ TEST(ParsePluginsFromFile, PlaybackConfig) // If more systems are added, then the number needs // to be adjusted below. auto config = common::joinPaths(PROJECT_SOURCE_PATH, - "include", "ignition", "gazebo", "playback_server.config"); + "include", "gz", "sim", "playback_server.config"); auto plugins = parsePluginsFromFile(config); ASSERT_EQ(2u, plugins.size()); @@ -202,14 +202,14 @@ TEST(LoadPluginInfo, FromValidEnv) EXPECT_EQ("*", plugin->EntityName()); EXPECT_EQ("world", plugin->EntityType()); EXPECT_EQ("TestWorldSystem", plugin->Filename()); - EXPECT_EQ("ignition::gazebo::TestWorldSystem", plugin->Name()); + EXPECT_EQ("gz::sim::TestWorldSystem", plugin->Name()); plugin = std::next(plugin, 1); EXPECT_EQ("box", plugin->EntityName()); EXPECT_EQ("model", plugin->EntityType()); EXPECT_EQ("TestModelSystem", plugin->Filename()); - EXPECT_EQ("ignition::gazebo::TestModelSystem", plugin->Name()); + EXPECT_EQ("gz::sim::TestModelSystem", plugin->Name()); EXPECT_TRUE(common::unsetenv(kServerConfigPathEnv)); } @@ -225,6 +225,6 @@ TEST(ServerConfig, GenerateRecordPlugin) auto plugin = config.LogRecordPlugin(); EXPECT_EQ(plugin.EntityName(), "*"); EXPECT_EQ(plugin.EntityType(), "world"); - EXPECT_EQ(plugin.Name(), "ignition::gazebo::systems::LogRecord"); + EXPECT_EQ(plugin.Name(), "gz::sim::systems::LogRecord"); } diff --git a/src/ServerPrivate.cc b/src/ServerPrivate.cc index d80d8443bb..49884d1a54 100644 --- a/src/ServerPrivate.cc +++ b/src/ServerPrivate.cc @@ -21,18 +21,18 @@ #include #include -#include -#include +#include +#include -#include +#include -#include +#include -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Util.hh" #include "SimulationRunner.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief This struct provides access to the record plugin SDF string struct LoggingPlugin @@ -61,7 +61,7 @@ struct LoggingPlugin public: static std::string &RecordPluginName() { static std::string recordPluginName = - "ignition::gazebo::systems::LogRecord"; + "gz::sim::systems::LogRecord"; return recordPluginName; } @@ -78,7 +78,7 @@ struct LoggingPlugin public: static std::string &PlaybackPluginName() { static std::string playbackPluginName = - "ignition::gazebo::systems::LogPlayback"; + "gz::sim::systems::LogPlayback"; return playbackPluginName; } }; diff --git a/src/ServerPrivate.hh b/src/ServerPrivate.hh index 1542b802be..88dee3fbb4 100644 --- a/src/ServerPrivate.hh +++ b/src/ServerPrivate.hh @@ -14,10 +14,10 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SERVERPRIVATE_HH_ -#define IGNITION_GAZEBO_SERVERPRIVATE_HH_ +#ifndef GZ_GAZEBO_SERVERPRIVATE_HH_ +#define GZ_GAZEBO_SERVERPRIVATE_HH_ -#include +#include #include #include @@ -31,20 +31,20 @@ #include -#include -#include -#include +#include +#include +#include -#include +#include -#include +#include -#include +#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; @@ -104,24 +104,24 @@ namespace ignition /// \brief Callback for worlds service. /// \param[out] _res Response containing the names of all the worlds. /// \return True if successful. - private: bool WorldsService(ignition::msgs::StringMsg_V &_res); + private: bool WorldsService(gz::msgs::StringMsg_V &_res); /// \brief Callback for add resource paths service. /// \param[out] _req Request containing the paths to be added. private: void AddResourcePathsService( - const ignition::msgs::StringMsg_V &_req); + const gz::msgs::StringMsg_V &_req); /// \brief Callback for get resource paths service. /// \param[out] _res Response filled with all current paths. /// \return True if successful. - private: bool ResourcePathsService(ignition::msgs::StringMsg_V &_res); + private: bool ResourcePathsService(gz::msgs::StringMsg_V &_res); /// \brief Callback for server control service. /// \param[out] _req The control request. /// \param[out] _res Whether the request was successfully fullfilled. /// \return True if successful. private: bool ServerControlService( - const ignition::msgs::ServerControl &_req, msgs::Boolean &_res); + const gz::msgs::ServerControl &_req, msgs::Boolean &_res); /// \brief A pool of worker threads. public: common::WorkerPool workerPool{2}; @@ -143,7 +143,7 @@ namespace ignition public: std::shared_ptr stopThread; /// \brief Our signal handler. - public: ignition::common::SignalHandler sigHandler; + public: gz::common::SignalHandler sigHandler; /// \brief Our system loader. public: SystemLoaderPtr systemLoader; diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc index 60f429123a..a2ff63ae55 100644 --- a/src/Server_TEST.cc +++ b/src/Server_TEST.cc @@ -18,32 +18,32 @@ #include #include #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#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" #include "../test/helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace ignition::gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; ///////////////////////////////////////////////// @@ -75,7 +75,7 @@ TEST_P(ServerFixture, DefaultServerConfig) EXPECT_TRUE(serverConfig.Plugins().empty()); EXPECT_TRUE(serverConfig.LogRecordTopics().empty()); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_EQ(std::nullopt, server.Running(1)); @@ -91,7 +91,7 @@ TEST_P(ServerFixture, DefaultServerConfig) ///////////////////////////////////////////////// TEST_P(ServerFixture, UpdateRate) { - gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetUpdateRate(1000.0); EXPECT_DOUBLE_EQ(1000.0, *serverConfig.UpdateRate()); serverConfig.SetUpdateRate(-1000.0); @@ -172,7 +172,7 @@ TEST_P(ServerFixture, ServerConfigRealPlugin) sdf::ElementPtr sdf(new sdf::Element); sdf->SetName("plugin"); sdf->AddAttribute("name", "string", - "ignition::gazebo::TestModelSystem", true); + "gz::sim::TestModelSystem", true); sdf->AddAttribute("filename", "string", "libTestModelSystem.so", true); sdf::ElementPtr child(new sdf::Element); @@ -181,9 +181,9 @@ TEST_P(ServerFixture, ServerConfigRealPlugin) child->AddValue("string", "987", "1"); serverConfig.AddPlugin({"box", "model", - "libTestModelSystem.so", "ignition::gazebo::TestModelSystem", sdf}); + "libTestModelSystem.so", "gz::sim::TestModelSystem", sdf}); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); // The simulation runner should not be running. EXPECT_FALSE(*server.Running(0)); @@ -222,16 +222,16 @@ TEST_P(ServerFixture, ServerConfigSensorPlugin) sdf::ElementPtr sdf(new sdf::Element); sdf->SetName("plugin"); sdf->AddAttribute("name", "string", - "ignition::gazebo::TestSensorSystem", true); + "gz::sim::TestSensorSystem", true); sdf->AddAttribute("filename", "string", "libTestSensorSystem.so", true); serverConfig.AddPlugin({ "air_pressure_sensor::air_pressure_model::link::air_pressure_sensor", - "sensor", "libTestSensorSystem.so", "ignition::gazebo::TestSensorSystem", + "sensor", "libTestSensorSystem.so", "gz::sim::TestSensorSystem", sdf}); igndbg << "Create server" << std::endl; - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); // The simulation runner should not be running. EXPECT_FALSE(*server.Running(0)); @@ -277,7 +277,7 @@ TEST_P(ServerFixture, SdfServerConfig) EXPECT_FALSE(serverConfig.SdfFile().empty()); EXPECT_TRUE(serverConfig.SdfString().empty()); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_TRUE(*server.Paused()); @@ -309,11 +309,11 @@ TEST_P(ServerFixture, ServerConfigLogRecord) EXPECT_FALSE(common::exists(compressedFile)); { - gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetUseLogRecord(true); serverConfig.SetLogRecordPath(logPath); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_EQ(0u, *server.IterationCount()); EXPECT_EQ(3u, *server.EntityCount()); @@ -348,12 +348,12 @@ TEST_P(ServerFixture, ServerConfigLogRecordCompress) EXPECT_FALSE(common::exists(compressedFile)); { - gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetUseLogRecord(true); serverConfig.SetLogRecordPath(logPath); serverConfig.SetLogRecordCompressPath(compressedFile); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_EQ(0u, *server.IterationCount()); EXPECT_EQ(3u, *server.EntityCount()); EXPECT_EQ(4u, *server.SystemCount()); @@ -378,7 +378,7 @@ TEST_P(ServerFixture, SdfStringServerConfig) EXPECT_TRUE(serverConfig.SdfFile().empty()); EXPECT_FALSE(serverConfig.SdfString().empty()); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_TRUE(*server.Paused()); @@ -390,7 +390,7 @@ TEST_P(ServerFixture, SdfStringServerConfig) ///////////////////////////////////////////////// TEST_P(ServerFixture, RunBlocking) { - gazebo::Server server; + gz::sim::Server server; EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_TRUE(*server.Paused()); @@ -416,7 +416,7 @@ TEST_P(ServerFixture, RunBlocking) ///////////////////////////////////////////////// TEST_P(ServerFixture, RunNonBlockingPaused) { - gazebo::Server server; + gz::sim::Server server; // The server should not be running. EXPECT_FALSE(server.Running()); @@ -466,7 +466,7 @@ TEST_P(ServerFixture, RunNonBlockingPaused) ///////////////////////////////////////////////// TEST_P(ServerFixture, RunNonBlocking) { - gazebo::Server server; + gz::sim::Server server; EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_EQ(0u, *server.IterationCount()); @@ -486,15 +486,15 @@ TEST_P(ServerFixture, RunNonBlocking) ///////////////////////////////////////////////// TEST_P(ServerFixture, RunOnceUnpaused) { - gazebo::Server server; + gz::sim::Server server; EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_EQ(0u, *server.IterationCount()); // Load a system - gazebo::SystemLoader systemLoader; + gz::sim::SystemLoader systemLoader; auto mockSystemPlugin = systemLoader.LoadPlugin( - "libMockSystem.so", "ignition::gazebo::MockSystem", nullptr); + "libMockSystem.so", "gz::sim::MockSystem", nullptr); ASSERT_TRUE(mockSystemPlugin.has_value()); // Check that it was loaded @@ -503,9 +503,9 @@ TEST_P(ServerFixture, RunOnceUnpaused) EXPECT_EQ(systemCount + 1, *server.SystemCount()); // Query the interface from the plugin - auto system = mockSystemPlugin.value()->QueryInterface(); + auto system = mockSystemPlugin.value()->QueryInterface(); EXPECT_NE(system, nullptr); - auto mockSystem = dynamic_cast(system); + auto mockSystem = dynamic_cast(system); EXPECT_NE(mockSystem, nullptr); // No steps should have been executed @@ -533,15 +533,15 @@ TEST_P(ServerFixture, RunOnceUnpaused) ///////////////////////////////////////////////// TEST_P(ServerFixture, RunOncePaused) { - gazebo::Server server; + gz::sim::Server server; EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_EQ(0u, *server.IterationCount()); // Load a system - gazebo::SystemLoader systemLoader; + gz::sim::SystemLoader systemLoader; auto mockSystemPlugin = systemLoader.LoadPlugin( - "libMockSystem.so", "ignition::gazebo::MockSystem", nullptr); + "libMockSystem.so", "gz::sim::MockSystem", nullptr); ASSERT_TRUE(mockSystemPlugin.has_value()); // Check that it was loaded @@ -550,9 +550,9 @@ TEST_P(ServerFixture, RunOncePaused) EXPECT_EQ(systemCount + 1, *server.SystemCount()); // Query the interface from the plugin - auto system = mockSystemPlugin.value()->QueryInterface(); + auto system = mockSystemPlugin.value()->QueryInterface(); EXPECT_NE(system, nullptr); - auto mockSystem = dynamic_cast(system); + auto mockSystem = dynamic_cast(system); EXPECT_NE(mockSystem, nullptr); // No steps should have been executed @@ -582,7 +582,7 @@ TEST_P(ServerFixture, RunNonBlockingMultiple) { ServerConfig serverConfig; serverConfig.SetSdfString(TestWorldSansPhysics::World()); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); @@ -602,7 +602,7 @@ TEST_P(ServerFixture, RunNonBlockingMultiple) ///////////////////////////////////////////////// TEST_P(ServerFixture, SigInt) { - gazebo::Server server; + gz::sim::Server server; EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); @@ -626,7 +626,7 @@ TEST_P(ServerFixture, ServerControlStop) // Test that the server correctly reacts to requests on /server_control // service with `stop` set to either false or true. - gazebo::Server server; + gz::sim::Server server; EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); @@ -685,8 +685,8 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_MAC(TwoServersNonBlocking)) ServerConfig serverConfig; serverConfig.SetSdfString(TestWorldSansPhysics::World()); - gazebo::Server server1(serverConfig); - gazebo::Server server2(serverConfig); + gz::sim::Server server1(serverConfig); + gz::sim::Server server2(serverConfig); EXPECT_FALSE(server1.Running()); EXPECT_FALSE(*server1.Running(0)); EXPECT_FALSE(server2.Running()); @@ -726,8 +726,8 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_MAC(TwoServersMixedBlocking)) ServerConfig serverConfig; serverConfig.SetSdfString(TestWorldSansPhysics::World()); - gazebo::Server server1(serverConfig); - gazebo::Server server2(serverConfig); + gz::sim::Server server1(serverConfig); + gz::sim::Server server2(serverConfig); EXPECT_FALSE(server1.Running()); EXPECT_FALSE(*server1.Running(0)); EXPECT_FALSE(server2.Running()); @@ -761,7 +761,7 @@ TEST_P(ServerFixture, AddSystemWhileRunning) serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); server.SetUpdatePeriod(1us); @@ -777,9 +777,9 @@ TEST_P(ServerFixture, AddSystemWhileRunning) EXPECT_EQ(3u, *server.SystemCount()); // Add system from plugin - gazebo::SystemLoader systemLoader; + gz::sim::SystemLoader systemLoader; auto mockSystemPlugin = systemLoader.LoadPlugin("libMockSystem.so", - "ignition::gazebo::MockSystem", nullptr); + "gz::sim::MockSystem", nullptr); ASSERT_TRUE(mockSystemPlugin.has_value()); auto result = server.AddSystem(mockSystemPlugin.value()); @@ -809,19 +809,19 @@ TEST_P(ServerFixture, AddSystemAfterLoad) serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); // Add system from plugin - gazebo::SystemLoader systemLoader; + gz::sim::SystemLoader systemLoader; auto mockSystemPlugin = systemLoader.LoadPlugin("libMockSystem.so", - "ignition::gazebo::MockSystem", nullptr); + "gz::sim::MockSystem", nullptr); ASSERT_TRUE(mockSystemPlugin.has_value()); - auto system = mockSystemPlugin.value()->QueryInterface(); + auto system = mockSystemPlugin.value()->QueryInterface(); EXPECT_NE(system, nullptr); - auto mockSystem = dynamic_cast(system); + auto mockSystem = dynamic_cast(system); ASSERT_NE(mockSystem, nullptr); EXPECT_EQ(3u, *server.SystemCount()); @@ -884,13 +884,13 @@ TEST_P(ServerFixture, ResourcePath) ServerConfig serverConfig; serverConfig.SetSdfFile("resource_paths.sdf"); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); test::Relay testSystem; unsigned int preUpdates{0}; testSystem.OnPreUpdate( - [&preUpdates](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + [&preUpdates](const gz::sim::UpdateInfo &, + gz::sim::EntityComponentManager &_ecm) { // Create AABB so it is populated unsigned int eachCount{0}; @@ -908,8 +908,8 @@ TEST_P(ServerFixture, ResourcePath) }); unsigned int postUpdates{0}; - testSystem.OnPostUpdate([&postUpdates](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&postUpdates](const gz::sim::UpdateInfo &, + const gz::sim::EntityComponentManager &_ecm) { // Check geometry components unsigned int eachCount{0}; @@ -970,7 +970,7 @@ TEST_P(ServerFixture, GetResourcePaths) "/tmp/some/path:/home/user/another_path"); ServerConfig serverConfig; - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(*server.Running(0)); @@ -1028,7 +1028,7 @@ TEST_P(ServerFixture, AddResourcePaths) common::setenv("IGN_FILE_PATH", ""); ServerConfig serverConfig; - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(*server.Running(0)); diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc index ebd33f7c51..9136b0122b 100644 --- a/src/SimulationRunner.cc +++ b/src/SimulationRunner.cc @@ -21,23 +21,23 @@ #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/Physics.hh" -#include "ignition/gazebo/components/PhysicsCmd.hh" -#include "ignition/gazebo/Events.hh" -#include "ignition/gazebo/SdfEntityCreator.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/common/Profiler.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/Physics.hh" +#include "gz/sim/components/PhysicsCmd.hh" +#include "gz/sim/Events.hh" +#include "gz/sim/SdfEntityCreator.hh" +#include "gz/sim/Util.hh" #include "network/NetworkManagerPrimary.hh" #include "SdfGenerator.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using StringSet = std::unordered_set; @@ -175,7 +175,7 @@ SimulationRunner::SimulationRunner(const sdf::World *_world, { ignmsg << "No systems loaded from SDF, loading defaults" << std::endl; bool isPlayback = !this->serverConfig.LogPlaybackPath().empty(); - auto plugins = gazebo::loadPluginInfo(isPlayback); + auto plugins = gz::sim::loadPluginInfo(isPlayback); this->LoadServerPlugins(plugins); } diff --git a/src/SimulationRunner.hh b/src/SimulationRunner.hh index 4362044566..46c06d3ea2 100644 --- a/src/SimulationRunner.hh +++ b/src/SimulationRunner.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SIMULATIONRUNNER_HH_ -#define IGNITION_GAZEBO_SIMULATIONRUNNER_HH_ +#ifndef GZ_GAZEBO_SIMULATIONRUNNER_HH_ +#define GZ_GAZEBO_SIMULATIONRUNNER_HH_ -#include -#include -#include +#include +#include +#include #include #include @@ -35,21 +35,21 @@ #include -#include -#include -#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/System.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/SystemPluginPtr.hh" -#include "ignition/gazebo/Types.hh" +#include +#include +#include +#include + +#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/System.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/SystemPluginPtr.hh" +#include "gz/sim/Types.hh" #include "network/NetworkManager.hh" #include "LevelManager.hh" @@ -343,11 +343,11 @@ namespace ignition /// \brief Get the step size; /// \return Step size. - public: const ignition::math::clock::duration &StepSize() const; + public: const gz::math::clock::duration &StepSize() const; /// \brief Set the step size; /// \param[in] _step Step size. - public: void SetStepSize(const ignition::math::clock::duration &_step); + public: void SetStepSize(const gz::math::clock::duration &_step); /// \brief World control service callback. This function stores the /// the request which will then be processed by the ProcessMessages @@ -372,7 +372,7 @@ namespace ignition /// \brief Callback for GUI info service. /// \param[out] _res Response containing the latest GUI message. /// \return True if successful. - private: bool GuiInfoService(ignition::msgs::GUI &_res); + private: bool GuiInfoService(gz::msgs::GUI &_res); /// \brief Calculate real time factor and populate currentInfo. private: void UpdateCurrentInfo(); @@ -503,34 +503,34 @@ namespace ignition private: std::unique_ptr node{nullptr}; /// \brief World statistics publisher. - private: ignition::transport::Node::Publisher statsPub; + private: gz::transport::Node::Publisher statsPub; /// \brief Clock publisher for the root `/stats` topic. - private: ignition::transport::Node::Publisher rootStatsPub; + private: gz::transport::Node::Publisher rootStatsPub; /// \brief Clock publisher. - private: ignition::transport::Node::Publisher clockPub; + private: gz::transport::Node::Publisher clockPub; /// \brief Clock publisher for the root `/clock` topic. - private: ignition::transport::Node::Publisher rootClockPub; + private: gz::transport::Node::Publisher rootClockPub; /// \brief Name of world being simulated. private: std::string worldName; /// \brief Stopwatch to keep track of wall time. - private: ignition::math::Stopwatch realTimeWatch; + private: gz::math::Stopwatch realTimeWatch; /// \brief Step size - private: ignition::math::clock::duration stepSize{10ms}; + private: gz::math::clock::duration stepSize{10ms}; /// \brief Desired real time factor private: double desiredRtf{1.0}; /// \brief Connection to the pause event. - private: ignition::common::ConnectionPtr pauseConn; + private: gz::common::ConnectionPtr pauseConn; /// \brief Connection to the stop event. - private: ignition::common::ConnectionPtr stopConn; + private: gz::common::ConnectionPtr stopConn; /// \brief Connection to the load plugins event. private: common::ConnectionPtr loadPluginsConn; diff --git a/src/SimulationRunner_TEST.cc b/src/SimulationRunner_TEST.cc index 49e3cbeb27..5d5d078692 100644 --- a/src/SimulationRunner_TEST.cc +++ b/src/SimulationRunner_TEST.cc @@ -18,9 +18,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include #include #include @@ -30,35 +30,35 @@ #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" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace components; namespace ignition @@ -1272,7 +1272,7 @@ TEST_P(SimulationRunnerTest, LoadPluginsDefault) // Load the default config, but not through the default code path. // The user may have modified their local config. auto config = common::joinPaths(PROJECT_SOURCE_PATH, - "include", "ignition", "gazebo", "server.config"); + "include", "gz", "sim", "server.config"); ASSERT_TRUE(common::setenv(kServerConfigPathEnv, config)); // Create simulation runner diff --git a/src/System.cc b/src/System.cc index 318e3d431d..b80237ee76 100644 --- a/src/System.cc +++ b/src/System.cc @@ -14,9 +14,9 @@ * limitations under the License. * */ -#include "ignition/gazebo/System.hh" +#include "gz/sim/System.hh" -using namespace ignition::gazebo; +using namespace gz::sim; ////////////////////////////////////////////////// System::System() = default; diff --git a/src/SystemLoader.cc b/src/SystemLoader.cc index 3a78dda509..72d8ac701b 100644 --- a/src/SystemLoader.cc +++ b/src/SystemLoader.cc @@ -19,23 +19,23 @@ #include #include -#include +#include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include +#include -#include +#include -using namespace ignition::gazebo; +using namespace gz::sim; -class ignition::gazebo::SystemLoaderPrivate +class gz::sim::SystemLoaderPrivate { ////////////////////////////////////////////////// public: explicit SystemLoaderPrivate() = default; @@ -44,24 +44,24 @@ class ignition::gazebo::SystemLoaderPrivate public: bool InstantiateSystemPlugin(const std::string &_filename, const std::string &_name, const sdf::ElementPtr &/*_sdf*/, - ignition::plugin::PluginPtr &_plugin) + gz::plugin::PluginPtr &_plugin) { - ignition::common::SystemPaths systemPaths; + gz::common::SystemPaths systemPaths; systemPaths.SetPluginPathEnv(pluginPathEnv); for (const auto &path : this->systemPluginPaths) systemPaths.AddPluginPaths(path); std::string homePath; - ignition::common::env(IGN_HOMEDIR, homePath); + gz::common::env(IGN_HOMEDIR, homePath); systemPaths.AddPluginPaths(homePath + "/.ignition/gazebo/plugins"); systemPaths.AddPluginPaths(IGN_GAZEBO_PLUGIN_INSTALL_DIR); auto pathToLib = systemPaths.FindSharedLibrary(_filename); if (pathToLib.empty()) { - // We assume ignition::gazebo corresponds to the levels feature - if (_name != "ignition::gazebo") + // We assume gz::sim corresponds to the levels feature + if (_name != "gz::sim") { ignerr << "Failed to load system plugin [" << _filename << "] : couldn't find shared library." << std::endl; @@ -113,7 +113,7 @@ class ignition::gazebo::SystemLoaderPrivate public: std::string pluginPathEnv{"IGN_GAZEBO_SYSTEM_PLUGIN_PATH"}; /// \brief Plugin loader instace - public: ignition::plugin::Loader loader; + public: gz::plugin::Loader loader; /// \brief Paths to search for system plugins. public: std::unordered_set systemPluginPaths; @@ -143,7 +143,7 @@ std::optional SystemLoader::LoadPlugin( const std::string &_name, const sdf::ElementPtr &_sdf) { - ignition::plugin::PluginPtr plugin; + gz::plugin::PluginPtr plugin; if (_filename == "" || _name == "") { @@ -182,4 +182,3 @@ std::string SystemLoader::PrettyStr() const { return this->dataPtr->loader.PrettyStr(); } - diff --git a/src/SystemLoader_TEST.cc b/src/SystemLoader_TEST.cc index ce4c7845b7..e85afb9240 100644 --- a/src/SystemLoader_TEST.cc +++ b/src/SystemLoader_TEST.cc @@ -20,18 +20,18 @@ #include #include -#include -#include "ignition/gazebo/System.hh" -#include "ignition/gazebo/SystemLoader.hh" +#include +#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; +using namespace gz; ///////////////////////////////////////////////// TEST(SystemLoader, Constructor) { - gazebo::SystemLoader sm; + gz::sim::SystemLoader sm; // Add test plugin to path (referenced in config) auto testBuildPath = common::joinPaths( @@ -43,7 +43,7 @@ TEST(SystemLoader, Constructor) "" "" + "name='gz::sim::systems::Physics'>" ""); auto worldElem = root.WorldByIndex(0)->Element(); @@ -60,7 +60,7 @@ TEST(SystemLoader, Constructor) TEST(SystemLoader, EmptyNames) { - gazebo::SystemLoader sm; + gz::sim::SystemLoader sm; sdf::ElementPtr element; auto system = sm.LoadPlugin("", "", element); ASSERT_FALSE(system.has_value()); diff --git a/src/System_TEST.cc b/src/System_TEST.cc index 0334400932..e238456085 100644 --- a/src/System_TEST.cc +++ b/src/System_TEST.cc @@ -17,9 +17,9 @@ #include -#include "ignition/gazebo/System.hh" +#include "gz/sim/System.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(System, Constructor) diff --git a/src/TestFixture.cc b/src/TestFixture.cc index e3a9479749..dafd7b94d2 100644 --- a/src/TestFixture.cc +++ b/src/TestFixture.cc @@ -15,13 +15,13 @@ * */ -#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; +using namespace gz; +using namespace gz::sim; /// \brief System that is inserted into the simulation loop to observe the ECM. class HelperSystem : @@ -106,7 +106,7 @@ void HelperSystem::PostUpdate(const UpdateInfo &_info, } ////////////////////////////////////////////////// -class ignition::gazebo::TestFixturePrivate +class gz::sim::TestFixturePrivate { /// \brief Initialize fixture /// \param[in] _config Server config diff --git a/src/TestFixture_TEST.cc b/src/TestFixture_TEST.cc index 4c6d244f87..2e96131759 100644 --- a/src/TestFixture_TEST.cc +++ b/src/TestFixture_TEST.cc @@ -17,17 +17,17 @@ #include -#include -#include +#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; +using namespace gz; +using namespace gz::sim; ///////////////////////////////////////////////// class TestFixtureTest : public InternalFixture<::testing::Test> diff --git a/src/Util.cc b/src/Util.cc index 31aba56865..92a79cae1b 100644 --- a/src/Util.cc +++ b/src/Util.cc @@ -30,25 +30,25 @@ #endif #endif -#include -#include -#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/Pose.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/World.hh" - -#include "ignition/gazebo/Util.hh" +#include +#include +#include +#include + +#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/Pose.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.hh" + +#include "gz/sim/Util.hh" namespace ignition { @@ -483,7 +483,7 @@ void addResourcePaths(const std::vector &_paths) } ////////////////////////////////////////////////// -gazebo::Entity topLevelModel(const Entity &_entity, +gz::sim::Entity topLevelModel(const Entity &_entity, const EntityComponentManager &_ecm) { auto entity = _entity; @@ -610,4 +610,3 @@ Entity entityFromMsg(const EntityComponentManager &_ecm, } } } - diff --git a/src/Util_TEST.cc b/src/Util_TEST.cc index 2385caf31a..7134de8de9 100644 --- a/src/Util_TEST.cc +++ b/src/Util_TEST.cc @@ -16,28 +16,28 @@ */ #include -#include +#include #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/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/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" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Tests for Util.hh class UtilTest : public InternalFixture<::testing::Test> @@ -66,8 +66,8 @@ TEST_F(UtilTest, ScopedName) // World auto worldEntity = ecm.CreateEntity(); - EXPECT_EQ(kNullEntity, gazebo::worldEntity(ecm)); - EXPECT_EQ(kNullEntity, gazebo::worldEntity(worldEntity, ecm)); + EXPECT_EQ(kNullEntity, gz::sim::worldEntity(ecm)); + EXPECT_EQ(kNullEntity, gz::sim::worldEntity(worldEntity, ecm)); ecm.CreateComponent(worldEntity, components::World()); ecm.CreateComponent(worldEntity, components::Name("world_name")); @@ -210,22 +210,22 @@ TEST_F(UtilTest, ScopedName) "world_name::actorD_name"); // World entity - EXPECT_EQ(worldEntity, gazebo::worldEntity(ecm)); - EXPECT_EQ(worldEntity, gazebo::worldEntity(worldEntity, ecm)); - EXPECT_EQ(worldEntity, gazebo::worldEntity(lightAEntity, ecm)); - EXPECT_EQ(worldEntity, gazebo::worldEntity(modelBEntity, ecm)); - EXPECT_EQ(worldEntity, gazebo::worldEntity(linkBEntity, ecm)); - EXPECT_EQ(worldEntity, gazebo::worldEntity(lightBEntity, ecm)); - EXPECT_EQ(worldEntity, gazebo::worldEntity(sensorBEntity, ecm)); - EXPECT_EQ(worldEntity, gazebo::worldEntity(modelCEntity, ecm)); - EXPECT_EQ(worldEntity, gazebo::worldEntity(linkCEntity, ecm)); - EXPECT_EQ(worldEntity, gazebo::worldEntity(collisionCEntity, ecm)); - EXPECT_EQ(worldEntity, gazebo::worldEntity(visualCEntity, ecm)); - EXPECT_EQ(worldEntity, gazebo::worldEntity(jointCEntity, ecm)); - EXPECT_EQ(worldEntity, gazebo::worldEntity(modelCCEntity, ecm)); - EXPECT_EQ(worldEntity, gazebo::worldEntity(linkCCEntity, ecm)); - EXPECT_EQ(worldEntity, gazebo::worldEntity(actorDEntity, ecm)); - EXPECT_EQ(kNullEntity, gazebo::worldEntity(kNullEntity, ecm)); + EXPECT_EQ(worldEntity, gz::sim::worldEntity(ecm)); + EXPECT_EQ(worldEntity, gz::sim::worldEntity(worldEntity, ecm)); + EXPECT_EQ(worldEntity, gz::sim::worldEntity(lightAEntity, ecm)); + EXPECT_EQ(worldEntity, gz::sim::worldEntity(modelBEntity, ecm)); + EXPECT_EQ(worldEntity, gz::sim::worldEntity(linkBEntity, ecm)); + EXPECT_EQ(worldEntity, gz::sim::worldEntity(lightBEntity, ecm)); + EXPECT_EQ(worldEntity, gz::sim::worldEntity(sensorBEntity, ecm)); + EXPECT_EQ(worldEntity, gz::sim::worldEntity(modelCEntity, ecm)); + EXPECT_EQ(worldEntity, gz::sim::worldEntity(linkCEntity, ecm)); + EXPECT_EQ(worldEntity, gz::sim::worldEntity(collisionCEntity, ecm)); + EXPECT_EQ(worldEntity, gz::sim::worldEntity(visualCEntity, ecm)); + EXPECT_EQ(worldEntity, gz::sim::worldEntity(jointCEntity, ecm)); + EXPECT_EQ(worldEntity, gz::sim::worldEntity(modelCCEntity, ecm)); + EXPECT_EQ(worldEntity, gz::sim::worldEntity(linkCCEntity, ecm)); + EXPECT_EQ(worldEntity, gz::sim::worldEntity(actorDEntity, ecm)); + EXPECT_EQ(kNullEntity, gz::sim::worldEntity(kNullEntity, ecm)); } ///////////////////////////////////////////////// @@ -638,8 +638,8 @@ TEST_F(UtilTest, EntityFromMsg) // World auto worldEntity = ecm.CreateEntity(); - EXPECT_EQ(kNullEntity, gazebo::worldEntity(ecm)); - EXPECT_EQ(kNullEntity, gazebo::worldEntity(worldEntity, ecm)); + EXPECT_EQ(kNullEntity, gz::sim::worldEntity(ecm)); + EXPECT_EQ(kNullEntity, gz::sim::worldEntity(worldEntity, ecm)); ecm.CreateComponent(worldEntity, components::World()); ecm.CreateComponent(worldEntity, components::Name("world")); diff --git a/src/View.cc b/src/View.cc index 09ac442984..8acd7e8d0f 100644 --- a/src/View.cc +++ b/src/View.cc @@ -14,11 +14,11 @@ * limitations under the License. * */ -#include "ignition/gazebo/detail/View.hh" -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/detail/View.hh" +#include "gz/sim/EntityComponentManager.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace detail; ////////////////////////////////////////////////// diff --git a/src/World.cc b/src/World.cc index 13a135500c..5f776f0551 100644 --- a/src/World.cc +++ b/src/World.cc @@ -15,30 +15,30 @@ * */ -#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/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/World.hh" +#include "gz/sim/World.hh" -class ignition::gazebo::WorldPrivate +class gz::sim::WorldPrivate { /// \brief Id of world entity. public: Entity id{kNullEntity}; }; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ////////////////////////////////////////////////// -World::World(gazebo::Entity _entity) +World::World(gz::sim::Entity _entity) : dataPtr(std::make_unique()) { this->dataPtr->id = _entity; @@ -159,7 +159,7 @@ std::vector World::Lights(const EntityComponentManager &_ecm) const auto entities = _ecm.EntitiesByComponents( components::ParentEntity(this->dataPtr->id)); - std::vector result; + std::vector result; for (const auto &entity : entities) { if (_ecm.Component(entity)) @@ -176,7 +176,7 @@ std::vector World::Actors(const EntityComponentManager &_ecm) const auto entities = _ecm.EntitiesByComponents( components::ParentEntity(this->dataPtr->id)); - std::vector result; + std::vector result; for (const auto &entity : entities) { if (_ecm.Component(entity)) @@ -210,4 +210,3 @@ uint64_t World::ModelCount(const EntityComponentManager &_ecm) const { return this->Models(_ecm).size(); } - diff --git a/src/World_TEST.cc b/src/World_TEST.cc index 7c3a03d532..824af1f761 100644 --- a/src/World_TEST.cc +++ b/src/World_TEST.cc @@ -17,16 +17,16 @@ #include -#include "ignition/gazebo/World.hh" +#include "gz/sim/World.hh" ///////////////////////////////////////////////// TEST(WorldTest, Constructor) { - ignition::gazebo::World worldNull; - EXPECT_EQ(ignition::gazebo::kNullEntity, worldNull.Entity()); + gz::sim::World worldNull; + EXPECT_EQ(gz::sim::kNullEntity, worldNull.Entity()); - ignition::gazebo::Entity id(3); - ignition::gazebo::World world(id); + gz::sim::Entity id(3); + gz::sim::World world(id); EXPECT_EQ(id, world.Entity()); } @@ -34,22 +34,22 @@ TEST(WorldTest, Constructor) ///////////////////////////////////////////////// TEST(WorldTest, CopyConstructor) { - ignition::gazebo::Entity id(3); - ignition::gazebo::World world(id); + gz::sim::Entity id(3); + gz::sim::World world(id); // Marked nolint because we are specifically testing copy // constructor here (clang wants unnecessary copies removed) - ignition::gazebo::World worldCopy(world); // NOLINT + gz::sim::World worldCopy(world); // NOLINT EXPECT_EQ(world.Entity(), worldCopy.Entity()); } ///////////////////////////////////////////////// TEST(WorldTest, CopyAssignmentOperator) { - ignition::gazebo::Entity id(3); - ignition::gazebo::World world(id); + gz::sim::Entity id(3); + gz::sim::World world(id); - ignition::gazebo::World worldCopy; + gz::sim::World worldCopy; worldCopy = world; EXPECT_EQ(world.Entity(), worldCopy.Entity()); } @@ -57,20 +57,20 @@ TEST(WorldTest, CopyAssignmentOperator) ///////////////////////////////////////////////// TEST(WorldTest, MoveConstructor) { - ignition::gazebo::Entity id(3); - ignition::gazebo::World world(id); + gz::sim::Entity id(3); + gz::sim::World world(id); - ignition::gazebo::World worldMoved(std::move(world)); + gz::sim::World worldMoved(std::move(world)); EXPECT_EQ(id, worldMoved.Entity()); } ///////////////////////////////////////////////// TEST(WorldTest, MoveAssignmentOperator) { - ignition::gazebo::Entity id(3); - ignition::gazebo::World world(id); + gz::sim::Entity id(3); + gz::sim::World world(id); - ignition::gazebo::World worldMoved; + gz::sim::World worldMoved; worldMoved = std::move(world); EXPECT_EQ(id, worldMoved.Entity()); } diff --git a/src/cmd/ModelCommandAPI.cc b/src/cmd/ModelCommandAPI.cc index 7cebd40593..663267403f 100644 --- a/src/cmd/ModelCommandAPI.cc +++ b/src/cmd/ModelCommandAPI.cc @@ -21,28 +21,28 @@ #include #include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -using namespace ignition; -using namespace gazebo; +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace gz; +using namespace gz::sim; ////////////////////////////////////////////////// /// \brief Get the name of the world being used by calling diff --git a/src/cmd/ModelCommandAPI.hh b/src/cmd/ModelCommandAPI.hh index fc776b1c18..99ff547adb 100644 --- a/src/cmd/ModelCommandAPI.hh +++ b/src/cmd/ModelCommandAPI.hh @@ -15,7 +15,7 @@ * */ -#include "ignition/gazebo/Export.hh" +#include "gz/sim/Export.hh" /// \brief External hook to get a list of available models. extern "C" IGNITION_GAZEBO_VISIBLE void cmdModelList(); diff --git a/src/cmd/gazebo.bash_completion.sh b/src/cmd/gazebo.bash_completion.sh index 7d6f6d3042..13b92fae77 100644 --- a/src/cmd/gazebo.bash_completion.sh +++ b/src/cmd/gazebo.bash_completion.sh @@ -55,7 +55,7 @@ function _gz_gazebo if [[ ${COMP_WORDS[COMP_CWORD]} == -* ]]; then # Specify options (-*) word list for this subcommand # TODO(anyone): In Fortress+, add --headless-rendering. - # Update ../ign_TEST.cc accordingly. + # Update ../gz_TEST.cc accordingly. COMPREPLY=($(compgen -W "$GZ_SIM_COMPLETION_LIST" \ -- "${COMP_WORDS[COMP_CWORD]}" )) return diff --git a/src/gui/AboutDialogHandler.cc b/src/gui/AboutDialogHandler.cc index 8e94a48e15..d393f11dd0 100644 --- a/src/gui/AboutDialogHandler.cc +++ b/src/gui/AboutDialogHandler.cc @@ -17,13 +17,13 @@ #include "AboutDialogHandler.hh" -#include -#include -#include +#include +#include +#include -using namespace ignition; -using namespace gazebo; -using namespace gazebo::gui; +using namespace gz; +using namespace gz::sim; +using namespace ignition::gazebo::gui; ///////////////////////////////////////////////// AboutDialogHandler::AboutDialogHandler() diff --git a/src/gui/AboutDialogHandler.hh b/src/gui/AboutDialogHandler.hh index 14f1bbd20c..ca2091d418 100644 --- a/src/gui/AboutDialogHandler.hh +++ b/src/gui/AboutDialogHandler.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_ABOUTDIALOGHANDLER_HH_ -#define IGNITION_GAZEBO_GUI_ABOUTDIALOGHANDLER_HH_ +#ifndef GZ_GAZEBO_GUI_ABOUTDIALOGHANDLER_HH_ +#define GZ_GAZEBO_GUI_ABOUTDIALOGHANDLER_HH_ #include #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/CMakeLists.txt b/src/gui/CMakeLists.txt index 2b37efb6bb..a5bad24abc 100644 --- a/src/gui/CMakeLists.txt +++ b/src/gui/CMakeLists.txt @@ -18,14 +18,14 @@ set(CMAKE_AUTORCC ON) # CMake AUTOMOC does not generate moc_*.cpp files automatically for headers # located in different directories than the containing .cc file. For Qt header -# files in `include/ignition/gazebo/gui`, we use qt5_wrap_cpp instead. There is +# files in `include/gz/sim/gui`, we use qt5_wrap_cpp instead. There is # no need to add entries for Qt header files in `src/gui/`. qt5_wrap_cpp(gui_sources - ${PROJECT_SOURCE_DIR}/include/ignition/gazebo/gui/GuiSystem.hh + ${PROJECT_SOURCE_DIR}/include/gz/sim/gui/GuiSystem.hh # TODO (anyone) Remove when GuiRunner.hh is moved to `src` - ${PROJECT_SOURCE_DIR}/include/ignition/gazebo/gui/GuiRunner.hh + ${PROJECT_SOURCE_DIR}/include/gz/sim/gui/GuiRunner.hh # TODO (anyone) Remove when TmpIface.hh is moved to `src` - ${PROJECT_SOURCE_DIR}/include/ignition/gazebo/gui/TmpIface.hh + ${PROJECT_SOURCE_DIR}/include/gz/sim/gui/TmpIface.hh ) ign_add_component(gui diff --git a/src/gui/Gui.cc b/src/gui/Gui.cc index 342d158e70..f358c91a51 100644 --- a/src/gui/Gui.cc +++ b/src/gui/Gui.cc @@ -16,21 +16,21 @@ */ #include -#include -#include -#include +#include +#include +#include -#include -#include -#include -#include +#include +#include +#include +#include -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/gui/GuiRunner.hh" -#include "ignition/gazebo/gui/TmpIface.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/config.hh" +#include "gz/sim/gui/GuiRunner.hh" +#include "gz/sim/gui/TmpIface.hh" -#include "ignition/gazebo/gui/Gui.hh" +#include "gz/sim/gui/Gui.hh" #include "AboutDialogHandler.hh" #include "QuickStartHandler.hh" #include "GuiFileHandler.hh" @@ -118,14 +118,14 @@ std::string launchQuickStart(int &_argc, char **_argv, ignmsg << "Gazebo Sim Quick start dialog" << std::endl; // Gui application in dialog mode - auto app = std::make_unique( - _argc, _argv, ignition::gui::WindowType::kDialog); + auto app = std::make_unique( + _argc, _argv, gz::gui::WindowType::kDialog); app->SetDefaultConfigPath(_defaultConfig); auto quickStartHandler = new gui::QuickStartHandler(); quickStartHandler->setParent(app->Engine()); - auto dialog = new ignition::gui::Dialog(); + auto dialog = new gz::gui::Dialog(); dialog->setObjectName("quick_start"); igndbg << "Reading Quick start menu config." << std::endl; @@ -153,7 +153,7 @@ std::string launchQuickStart(int &_argc, char **_argv, std::string qmlFile("qrc:/Gazebo/QuickStart.qml"); - QQmlComponent dialogComponent(ignition::gui::App()->Engine(), + QQmlComponent dialogComponent(gz::gui::App()->Engine(), QString(QString::fromStdString(qmlFile))); auto dialogItem = qobject_cast(dialogComponent.create(context)); @@ -173,7 +173,7 @@ std::string launchQuickStart(int &_argc, char **_argv, } ////////////////////////////////////////////////// -std::unique_ptr createGui( +std::unique_ptr createGui( int &_argc, char **_argv, const char *_guiConfig, const char *_defaultGuiConfig, bool _loadPluginsFromSdf) { @@ -182,12 +182,12 @@ std::unique_ptr createGui( } ////////////////////////////////////////////////// -std::unique_ptr createGui( +std::unique_ptr createGui( int &_argc, char **_argv, const char *_guiConfig, const char *_defaultGuiConfig, bool _loadPluginsFromSdf, const char *_sdfFile, int _waitGui) { - ignition::common::SignalHandler sigHandler; + gz::common::SignalHandler sigHandler; bool sigKilled = false; sigHandler.AddCallback([&](const int /*_sig*/) { @@ -257,22 +257,22 @@ std::unique_ptr createGui( } // Launch main window - auto app = std::make_unique( - _argc, _argv, ignition::gui::WindowType::kMainWindow); + auto app = std::make_unique( + _argc, _argv, gz::gui::WindowType::kMainWindow); app->AddPluginPath(IGN_GAZEBO_GUI_PLUGIN_INSTALL_DIR); // Temporary transport interface - auto tmp = new ignition::gazebo::TmpIface(); + auto tmp = new gz::sim::TmpIface(); tmp->setParent(app->Engine()); - auto aboutDialogHandler = new ignition::gazebo::gui::AboutDialogHandler(); + auto aboutDialogHandler = new gz::sim::gui::AboutDialogHandler(); aboutDialogHandler->setParent(app->Engine()); - auto guiFileHandler = new ignition::gazebo::gui::GuiFileHandler(); + auto guiFileHandler = new gz::sim::gui::GuiFileHandler(); guiFileHandler->setParent(app->Engine()); - auto pathManager = new ignition::gazebo::gui::PathManager(); + auto pathManager = new gz::sim::gui::PathManager(); pathManager->setParent(app->Engine()); // add import path so we can load custom modules @@ -281,7 +281,7 @@ std::unique_ptr createGui( app->SetDefaultConfigPath(defaultConfig); // Customize window - auto mainWin = app->findChild(); + auto mainWin = app->findChild(); auto win = mainWin->QuickWindow(); win->setProperty("title", "Gazebo"); @@ -349,14 +349,14 @@ std::unique_ptr createGui( // TODO(anyone) Most of ign-gazebo's transport API includes the world name, // which makes it complicated to mix configurations across worlds. // We could have a way to use world-agnostic topics like Gazebo-classic's ~ - auto runner = new ignition::gazebo::GuiRunner(worldsMsg.data(0)); + auto runner = new gz::sim::GuiRunner(worldsMsg.data(0)); ++runnerCount; - runner->setParent(ignition::gui::App()); + runner->setParent(gz::gui::App()); // Load plugins after runner is up if (!app->LoadConfig(_guiConfig)) { - ignwarn << "Failed to load config file[" << _guiConfig << "]." + ignwarn << "Failed to load gui config file[" << _guiConfig << "]." << std::endl; } } @@ -376,7 +376,7 @@ std::unique_ptr createGui( igndbg << "Requesting GUI from [" << service << "]..." << std::endl; // Request and block - ignition::msgs::GUI res; + gz::msgs::GUI res; executed = node.Request(service, timeout, res, result); if (!executed) @@ -385,8 +385,8 @@ std::unique_ptr createGui( ignerr << "Service call failed for [" << service << "]" << std::endl; // GUI runner - auto runner = new ignition::gazebo::GuiRunner(worldName); - runner->setParent(ignition::gui::App()); + auto runner = new gz::sim::GuiRunner(worldName); + runner->setParent(gz::gui::App()); ++runnerCount; // Load plugins after creating GuiRunner, so they can access worldName @@ -417,14 +417,14 @@ std::unique_ptr createGui( } // If no plugins have been added, load default config file - auto plugins = mainWin->findChildren(); + auto plugins = mainWin->findChildren(); if (plugins.empty()) { // Also set ~/.ignition/gazebo/gui.config as the default path if (!app->LoadConfig(defaultConfig)) { - ignerr << "Failed to load config file[" << defaultConfig << "]." - << std::endl; + ignerr << "Failed to load default config file[" + << defaultConfig << "]." << std::endl; return nullptr; } } @@ -441,7 +441,7 @@ int runGui(int &_argc, char **_argv, const char *_guiConfig) int runGui(int &_argc, char **_argv, const char *_guiConfig, const char *_sdfFile, int _waitGui) { - auto app = gazebo::gui::createGui(_argc, _argv, _guiConfig, nullptr, true, + auto app = gz::sim::gui::createGui(_argc, _argv, _guiConfig, nullptr, true, _sdfFile, _waitGui); if (nullptr != app) { diff --git a/src/gui/GuiFileHandler.cc b/src/gui/GuiFileHandler.cc index 643ef2dd7b..d88834f21d 100644 --- a/src/gui/GuiFileHandler.cc +++ b/src/gui/GuiFileHandler.cc @@ -15,19 +15,19 @@ * */ -#include +#include #include -#include -#include -#include +#include +#include +#include #include "GuiFileHandler.hh" -using namespace ignition; -using namespace gazebo; -using namespace gazebo::gui; +using namespace gz; +using namespace gz::sim; +using namespace ignition::gazebo::gui; ///////////////////////////////////////////////// void GuiFileHandler::SaveWorldAs(const QString &_fileUrl, diff --git a/src/gui/GuiFileHandler.hh b/src/gui/GuiFileHandler.hh index 981b9fb769..7577bd9f51 100644 --- a/src/gui/GuiFileHandler.hh +++ b/src/gui/GuiFileHandler.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_GUIFILEHANDLER_HH_ -#define IGNITION_GAZEBO_GUI_GUIFILEHANDLER_HH_ +#ifndef GZ_GAZEBO_GUI_GUIFILEHANDLER_HH_ +#define GZ_GAZEBO_GUI_GUIFILEHANDLER_HH_ -#include +#include #include #include -#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/GuiRunner.cc b/src/gui/GuiRunner.cc index 6077221e94..e94ebdbc7a 100644 --- a/src/gui/GuiRunner.cc +++ b/src/gui/GuiRunner.cc @@ -15,20 +15,20 @@ * */ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include // Include all components so they have first-class support -#include "ignition/gazebo/components/components.hh" -#include "ignition/gazebo/Conversions.hh" -#include "ignition/gazebo/gui/GuiRunner.hh" -#include "ignition/gazebo/gui/GuiSystem.hh" +#include "gz/sim/components/components.hh" +#include "gz/sim/Conversions.hh" +#include "gz/sim/gui/GuiRunner.hh" +#include "gz/sim/gui/GuiSystem.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; // Register SerializedStepMap to the Qt meta type system so we can pass objects // of this type in QMetaObject::invokeMethod @@ -41,7 +41,7 @@ GuiRunner::GuiRunner(const std::string &_worldName) this->setProperty("worldName", QString::fromStdString(_worldName)); - auto win = gui::App()->findChild(); + auto win = gui::App()->findChild(); auto winWorldNames = win->property("worldNames").toStringList(); winWorldNames.append(QString::fromStdString(_worldName)); win->setProperty("worldNames", winWorldNames); diff --git a/src/gui/Gui_TEST.cc b/src/gui/Gui_TEST.cc index 933af792ba..c160ce12e2 100644 --- a/src/gui/Gui_TEST.cc +++ b/src/gui/Gui_TEST.cc @@ -17,24 +17,24 @@ #include -#include - -#include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/gui/Gui.hh" -#include "ignition/gazebo/test_config.hh" +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "gz/sim/gui/Gui.hh" +#include "gz/sim/test_config.hh" #include "QuickStartHandler.hh" int gg_argc = 1; char **gg_argv = new char *[gg_argc]; -using namespace ignition; +using namespace gz; using namespace ignition::gazebo::gui; ///////////////////////////////////////////////// diff --git a/src/gui/PathManager.cc b/src/gui/PathManager.cc index a1f920519a..17ec381e80 100644 --- a/src/gui/PathManager.cc +++ b/src/gui/PathManager.cc @@ -17,20 +17,20 @@ #include "PathManager.hh" -#include +#include #include #include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; -using namespace gazebo::gui; +using namespace gz; +using namespace gz::sim; +using namespace ignition::gazebo::gui; ////////////////////////////////////////////////// void onAddResourcePaths(const msgs::StringMsg_V &_msg) diff --git a/src/gui/PathManager.hh b/src/gui/PathManager.hh index 341e382cf2..4471995e3d 100644 --- a/src/gui/PathManager.hh +++ b/src/gui/PathManager.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_PATHMANAGER_HH_ -#define IGNITION_GAZEBO_GUI_PATHMANAGER_HH_ +#ifndef GZ_GAZEBO_GUI_PATHMANAGER_HH_ +#define GZ_GAZEBO_GUI_PATHMANAGER_HH_ #include -#include +#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/QuickStartHandler.cc b/src/gui/QuickStartHandler.cc index 88a4c49f0c..31e80d0c3e 100644 --- a/src/gui/QuickStartHandler.cc +++ b/src/gui/QuickStartHandler.cc @@ -17,11 +17,11 @@ #include "QuickStartHandler.hh" -#include +#include -using namespace ignition; -using namespace gazebo; -using namespace gazebo::gui; +using namespace gz; +using namespace gz::sim; +using namespace ignition::gazebo::gui; ///////////////////////////////////////////////// QString QuickStartHandler::WorldsPath() const diff --git a/src/gui/QuickStartHandler.hh b/src/gui/QuickStartHandler.hh index 7569a490c0..088f1759c4 100644 --- a/src/gui/QuickStartHandler.hh +++ b/src/gui/QuickStartHandler.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_QUICKSTARTHANDLER_HH_ -#define IGNITION_GAZEBO_GUI_QUICKSTARTHANDLER_HH_ +#ifndef GZ_GAZEBO_GUI_QUICKSTARTHANDLER_HH_ +#define GZ_GAZEBO_GUI_QUICKSTARTHANDLER_HH_ #include #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/TmpIface.cc b/src/gui/TmpIface.cc index 3711e892bc..59ecc4d50b 100644 --- a/src/gui/TmpIface.cc +++ b/src/gui/TmpIface.cc @@ -15,9 +15,9 @@ * */ -#include +#include -#include "ignition/gazebo/gui/TmpIface.hh" +#include "gz/sim/gui/TmpIface.hh" using namespace ignition; using namespace gazebo; diff --git a/src/gui/plugins/align_tool/AlignTool.cc b/src/gui/plugins/align_tool/AlignTool.cc index 43b649840d..5203e10fea 100644 --- a/src/gui/plugins/align_tool/AlignTool.cc +++ b/src/gui/plugins/align_tool/AlignTool.cc @@ -15,8 +15,8 @@ * */ -#include -#include +#include +#include #include #include @@ -25,24 +25,24 @@ #include #include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#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 +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#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" @@ -91,7 +91,7 @@ namespace ignition::gazebo } using namespace ignition; -using namespace gazebo; +using namespace ignition::gazebo; ///////////////////////////////////////////////// AlignTool::AlignTool() @@ -99,8 +99,8 @@ AlignTool::AlignTool() { // Deselect all entities upon loading plugin gui::events::DeselectAllEntities deselectEvent(true); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &deselectEvent); } @@ -114,8 +114,8 @@ void AlignTool::LoadConfig(const tinyxml2::XMLElement *) this->title = "Align tool"; // For align tool requests - ignition::gui::App()->findChild - ()->installEventFilter(this); + gz::gui::App()->findChild + ()->installEventFilter(this); } ///////////////////////////////////////////////// @@ -529,4 +529,4 @@ bool AlignTool::eventFilter(QObject *_obj, QEvent *_event) // Register this plugin IGNITION_ADD_PLUGIN(AlignTool, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/align_tool/AlignTool.hh b/src/gui/plugins/align_tool/AlignTool.hh index f72a8ff5a8..e6c56b2dbf 100644 --- a/src/gui/plugins/align_tool/AlignTool.hh +++ b/src/gui/plugins/align_tool/AlignTool.hh @@ -15,14 +15,14 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_ALIGNTOOL_HH_ -#define IGNITION_GAZEBO_GUI_ALIGNTOOL_HH_ +#ifndef GZ_GAZEBO_GUI_ALIGNTOOL_HH_ +#define GZ_GAZEBO_GUI_ALIGNTOOL_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 84cfcf7cff..edfa7a5e4c 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -17,50 +17,50 @@ #include #include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/AngularAcceleration.hh" -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/BatterySoC.hh" -#include "ignition/gazebo/components/CastShadows.hh" -#include "ignition/gazebo/components/CenterOfVolume.hh" -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Gravity.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/LaserRetro.hh" -#include "ignition/gazebo/components/Level.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/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/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/SelfCollide.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/SourceFilePath.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 +#include +#include +#include +#include + +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/AngularAcceleration.hh" +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/BatterySoC.hh" +#include "gz/sim/components/CastShadows.hh" +#include "gz/sim/components/CenterOfVolume.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Gravity.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/LaserRetro.hh" +#include "gz/sim/components/Level.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/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/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/SelfCollide.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/SourceFilePath.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" @@ -106,11 +106,11 @@ namespace ignition::gazebo } using namespace ignition; -using namespace gazebo; +using namespace ignition::gazebo; ////////////////////////////////////////////////// template<> -void gazebo::setData(QStandardItem *_item, +void ignition::gazebo::setData(QStandardItem *_item, const math::Vector3d &_data) { if (nullptr == _item) @@ -127,7 +127,7 @@ void gazebo::setData(QStandardItem *_item, ////////////////////////////////////////////////// template<> -void gazebo::setData(QStandardItem *_item, const std::string &_data) +void ignition::gazebo::setData(QStandardItem *_item, const std::string &_data) { if (nullptr == _item) return; @@ -140,7 +140,7 @@ void gazebo::setData(QStandardItem *_item, const std::string &_data) ////////////////////////////////////////////////// template<> -void gazebo::setData(QStandardItem *_item, +void ignition::gazebo::setData(QStandardItem *_item, const std::ostringstream &_data) { if (nullptr == _item) @@ -154,7 +154,7 @@ void gazebo::setData(QStandardItem *_item, ////////////////////////////////////////////////// template<> -void gazebo::setData(QStandardItem *_item, const bool &_data) +void ignition::gazebo::setData(QStandardItem *_item, const bool &_data) { if (nullptr == _item) return; @@ -166,7 +166,7 @@ void gazebo::setData(QStandardItem *_item, const bool &_data) ////////////////////////////////////////////////// template<> -void gazebo::setData(QStandardItem *_item, const int &_data) +void ignition::gazebo::setData(QStandardItem *_item, const int &_data) { if (nullptr == _item) return; @@ -178,14 +178,14 @@ void gazebo::setData(QStandardItem *_item, const int &_data) ////////////////////////////////////////////////// template<> -void gazebo::setData(QStandardItem *_item, const Entity &_data) +void ignition::gazebo::setData(QStandardItem *_item, const Entity &_data) { setData(_item, static_cast(_data)); } ////////////////////////////////////////////////// template<> -void gazebo::setData(QStandardItem *_item, const double &_data) +void ignition::gazebo::setData(QStandardItem *_item, const double &_data) { if (nullptr == _item) return; @@ -197,7 +197,7 @@ void gazebo::setData(QStandardItem *_item, const double &_data) ////////////////////////////////////////////////// template<> -void gazebo::setData(QStandardItem *_item, const sdf::Physics &_data) +void ignition::gazebo::setData(QStandardItem *_item, const sdf::Physics &_data) { if (nullptr == _item) return; @@ -211,7 +211,7 @@ void gazebo::setData(QStandardItem *_item, const sdf::Physics &_data) } ////////////////////////////////////////////////// -void gazebo::setUnit(QStandardItem *_item, const std::string &_unit) +void ignition::gazebo::setUnit(QStandardItem *_item, const std::string &_unit) { if (nullptr == _item) return; @@ -320,8 +320,8 @@ void ComponentInspector::LoadConfig(const tinyxml2::XMLElement *) if (this->title.empty()) this->title = "Component inspector"; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); // Connect model this->Context()->setContextProperty( @@ -838,4 +838,4 @@ transport::Node &ComponentInspector::TransportNode() // Register this plugin IGNITION_ADD_PLUGIN(ComponentInspector, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/component_inspector/ComponentInspector.hh b/src/gui/plugins/component_inspector/ComponentInspector.hh index 194893a9ca..003ff41653 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.hh +++ b/src/gui/plugins/component_inspector/ComponentInspector.hh @@ -15,20 +15,20 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_HH_ -#define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_HH_ +#ifndef GZ_GAZEBO_GUI_COMPONENTINSPECTOR_HH_ +#define GZ_GAZEBO_GUI_COMPONENTINSPECTOR_HH_ #include #include #include -#include -#include +#include +#include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/components/Physics.hh" +#include "gz/sim/components/Physics.hh" #include "Types.hh" @@ -146,7 +146,7 @@ namespace gazebo /// /// ## Configuration /// None - class ComponentInspector : public gazebo::GuiSystem + class ComponentInspector : public ignition::gazebo::GuiSystem { Q_OBJECT diff --git a/src/gui/plugins/component_inspector/Pose3d.cc b/src/gui/plugins/component_inspector/Pose3d.cc index e3a9446202..32d6cb4e8c 100644 --- a/src/gui/plugins/component_inspector/Pose3d.cc +++ b/src/gui/plugins/component_inspector/Pose3d.cc @@ -17,13 +17,13 @@ #include -#include -#include +#include +#include #include "Pose3d.hh" using namespace ignition; -using namespace gazebo; +using namespace ignition::gazebo; using namespace inspector; ///////////////////////////////////////////////// diff --git a/src/gui/plugins/component_inspector/Pose3d.hh b/src/gui/plugins/component_inspector/Pose3d.hh index 890cac2590..5659f75e3f 100644 --- a/src/gui/plugins/component_inspector/Pose3d.hh +++ b/src/gui/plugins/component_inspector/Pose3d.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_POSE3D_HH_ -#define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_POSE3D_HH_ +#ifndef GZ_GAZEBO_GUI_COMPONENTINSPECTOR_POSE3D_HH_ +#define GZ_GAZEBO_GUI_COMPONENTINSPECTOR_POSE3D_HH_ -#include +#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 5e0b682027..0e5a697673 100644 --- a/src/gui/plugins/component_inspector/Types.hh +++ b/src/gui/plugins/component_inspector/Types.hh @@ -15,12 +15,12 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_TYPES_HH_ -#define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_TYPES_HH_ +#ifndef GZ_GAZEBO_GUI_COMPONENTINSPECTOR_TYPES_HH_ +#define GZ_GAZEBO_GUI_COMPONENTINSPECTOR_TYPES_HH_ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/entity_tree/EntityTree.cc b/src/gui/plugins/entity_tree/EntityTree.cc index 7eac482f15..c80ab80e6b 100644 --- a/src/gui/plugins/entity_tree/EntityTree.cc +++ b/src/gui/plugins/entity_tree/EntityTree.cc @@ -20,27 +20,27 @@ #include #include -#include -#include -#include -#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/EntityComponentManager.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" +#include +#include +#include +#include +#include + +#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/EntityComponentManager.hh" +#include "gz/sim/gui/GuiEvents.hh" namespace ignition::gazebo { @@ -58,7 +58,7 @@ namespace ignition::gazebo } using namespace ignition; -using namespace gazebo; +using namespace ignition::gazebo; ////////////////////////////////////////////////// QString entityType(Entity _entity, @@ -274,7 +274,7 @@ EntityTree::EntityTree() : GuiSystem(), dataPtr(std::make_unique()) { // Connect model - ignition::gui::App()->Engine()->rootContext()->setContextProperty( + gz::gui::App()->Engine()->rootContext()->setContextProperty( "EntityTreeModel", &this->dataPtr->treeModel); } @@ -287,8 +287,8 @@ void EntityTree::LoadConfig(const tinyxml2::XMLElement *) if (this->title.empty()) this->title = "Entity tree"; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); } ////////////////////////////////////////////////// @@ -383,8 +383,8 @@ void EntityTree::OnEntitySelectedFromQml(unsigned int _entity) { std::vector entitySet {_entity}; gui::events::EntitiesSelected event(entitySet, true); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); } @@ -392,8 +392,8 @@ void EntityTree::OnEntitySelectedFromQml(unsigned int _entity) void EntityTree::DeselectAllEntities() { gui::events::DeselectAllEntities event(true); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); } @@ -435,4 +435,4 @@ bool EntityTree::eventFilter(QObject *_obj, QEvent *_event) // Register this plugin IGNITION_ADD_PLUGIN(EntityTree, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/entity_tree/EntityTree.hh b/src/gui/plugins/entity_tree/EntityTree.hh index 4f882de9f7..503a7e5812 100644 --- a/src/gui/plugins/entity_tree/EntityTree.hh +++ b/src/gui/plugins/entity_tree/EntityTree.hh @@ -15,14 +15,14 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_ENTITYTREE_HH_ -#define IGNITION_GAZEBO_GUI_ENTITYTREE_HH_ +#ifndef GZ_GAZEBO_GUI_ENTITYTREE_HH_ +#define GZ_GAZEBO_GUI_ENTITYTREE_HH_ #include #include #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/grid_config/GridConfig.cc b/src/gui/plugins/grid_config/GridConfig.cc index 28adc956d6..1ad4fa2ee5 100644 --- a/src/gui/plugins/grid_config/GridConfig.cc +++ b/src/gui/plugins/grid_config/GridConfig.cc @@ -15,15 +15,15 @@ * */ -#include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/gui/GuiEvents.hh" +#include +#include +#include +#include +#include +#include +#include + +#include "gz/sim/gui/GuiEvents.hh" #include "GridConfig.hh" namespace ignition::gazebo @@ -63,11 +63,11 @@ namespace ignition::gazebo } using namespace ignition; -using namespace gazebo; +using namespace ignition::gazebo; ///////////////////////////////////////////////// GridConfig::GridConfig() - : ignition::gui::Plugin(), dataPtr(std::make_unique()) + : gz::gui::Plugin(), dataPtr(std::make_unique()) { } @@ -80,8 +80,8 @@ void GridConfig::LoadConfig(const tinyxml2::XMLElement *) if (this->title.empty()) this->title = "Grid config"; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); } ///////////////////////////////////////////////// @@ -186,8 +186,8 @@ void GridConfig::LoadGrid() // If we get here, most likely the render engine and scene are fully loaded, // but they don't support grids. So stop trying. - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->removeEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->removeEventFilter(this); return; } @@ -256,4 +256,4 @@ void GridConfig::OnShow(bool _checked) // Register this plugin IGNITION_ADD_PLUGIN(GridConfig, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/grid_config/GridConfig.hh b/src/gui/plugins/grid_config/GridConfig.hh index c39184e7e6..d4de86720d 100644 --- a/src/gui/plugins/grid_config/GridConfig.hh +++ b/src/gui/plugins/grid_config/GridConfig.hh @@ -15,13 +15,13 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_GRIDCONFIG_HH_ -#define IGNITION_GAZEBO_GUI_GRIDCONFIG_HH_ +#ifndef GZ_GAZEBO_GUI_GRIDCONFIG_HH_ +#define GZ_GAZEBO_GUI_GRIDCONFIG_HH_ #include -#include -#include +#include +#include namespace ignition { @@ -29,7 +29,7 @@ namespace gazebo { class GridConfigPrivate; - class GridConfig : public ignition::gui::Plugin + class GridConfig : public gz::gui::Plugin { Q_OBJECT diff --git a/src/gui/plugins/joint_position_controller/JointPositionController.cc b/src/gui/plugins/joint_position_controller/JointPositionController.cc index 10a1a13383..7cb3c7ec6e 100644 --- a/src/gui/plugins/joint_position_controller/JointPositionController.cc +++ b/src/gui/plugins/joint_position_controller/JointPositionController.cc @@ -17,24 +17,24 @@ #include #include -#include -#include -#include -#include -#include -#include -#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 +#include +#include +#include +#include +#include +#include +#include + +#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" @@ -163,8 +163,8 @@ void JointPositionController::LoadConfig( // If model name isn't set, initialization is complete. this->dataPtr->xmlModelInitialized = this->dataPtr->modelName.isEmpty(); - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); // Connect model this->Context()->setContextProperty( @@ -302,7 +302,8 @@ bool JointPositionController::eventFilter(QObject *_obj, QEvent *_event) { if (!this->dataPtr->locked) { - if (_event->type() == gazebo::gui::events::EntitiesSelected::kType) + if (_event->type() == + ignition::gazebo::gui::events::EntitiesSelected::kType) { auto event = reinterpret_cast(_event); if (event && !event->Data().empty()) @@ -311,7 +312,8 @@ bool JointPositionController::eventFilter(QObject *_obj, QEvent *_event) } } - if (_event->type() == gazebo::gui::events::DeselectAllEntities::kType) + if (_event->type() == + ignition::gazebo::gui::events::DeselectAllEntities::kType) { auto event = reinterpret_cast( _event); @@ -425,4 +427,4 @@ void JointPositionController::OnReset() // Register this plugin IGNITION_ADD_PLUGIN(JointPositionController, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/joint_position_controller/JointPositionController.hh b/src/gui/plugins/joint_position_controller/JointPositionController.hh index 3aa9ecfa57..622ab4b4d3 100644 --- a/src/gui/plugins/joint_position_controller/JointPositionController.hh +++ b/src/gui/plugins/joint_position_controller/JointPositionController.hh @@ -15,15 +15,15 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_JOINTPOSITIONCONTROLLER_HH_ -#define IGNITION_GAZEBO_GUI_JOINTPOSITIONCONTROLLER_HH_ +#ifndef GZ_GAZEBO_GUI_JOINTPOSITIONCONTROLLER_HH_ +#define GZ_GAZEBO_GUI_JOINTPOSITIONCONTROLLER_HH_ #include #include #include -#include -#include +#include +#include Q_DECLARE_METATYPE(ignition::gazebo::Entity) @@ -74,7 +74,7 @@ namespace gui /// `ignition::gazebo::systems::JointPositionController` /// for each joint to be controlled. /// - /// This plugin publishes position command messages (`ignition::msgs::Double`) + /// This plugin publishes position command messages (`gz::msgs::Double`) /// on topics in the format `/model//joint/`: Load the widget pointed at the given model, so it's not /// necessary to select it. If a model is given at startup, the plugin starts /// in locked mode. - class JointPositionController : public gazebo::GuiSystem + class JointPositionController : public ignition::gazebo::GuiSystem { Q_OBJECT diff --git a/src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc b/src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc index 72aa9b14cf..37e1a3407a 100644 --- a/src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc +++ b/src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc @@ -19,27 +19,27 @@ #ifdef _MSC_VER #pragma warning(push, 0) #endif -#include +#include #ifdef _MSC_VER #pragma warning(pop) #endif -#include -#include -#include -#include -#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/gui/GuiRunner.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include +#include + +#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/gui/GuiRunner.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/test_config.hh" #include "../../../../test/helpers/EnvTestFixture.hh" #include "JointPositionController.hh" @@ -62,8 +62,8 @@ TEST_F(JointPositionControllerGui, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Load)) ASSERT_NE(nullptr, app); app->AddPluginPath(std::string(PROJECT_BINARY_PATH) + "/lib"); - // Create GUI runner to handle gazebo::gui plugins - auto runner = new gazebo::GuiRunner("test"); + // Create GUI runner to handle ignition::gazebo::gui plugins + auto runner = new ignition::gazebo::GuiRunner("test"); runner->setParent(gui::App()); // Add plugin @@ -75,7 +75,7 @@ TEST_F(JointPositionControllerGui, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Load)) // Get plugin auto plugins = win->findChildren< - gazebo::gui::JointPositionController *>(); + ignition::gazebo::gui::JointPositionController *>(); EXPECT_EQ(plugins.size(), 1); auto plugin = plugins[0]; @@ -91,7 +91,7 @@ TEST_F(JointPositionControllerGui, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Load)) EXPECT_LT(sleep, maxSleep); EXPECT_EQ(plugin->Title(), "Joint position controller"); - EXPECT_EQ(plugin->ModelEntity(), gazebo::kNullEntity); + EXPECT_EQ(plugin->ModelEntity(), ignition::gazebo::kNullEntity); EXPECT_EQ(plugin->ModelName(), QString("No model selected")) << plugin->ModelName().toStdString(); EXPECT_FALSE(plugin->Locked()); @@ -105,24 +105,28 @@ TEST_F(JointPositionControllerGui, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PublishCommand)) { // Create a model with a joint - gazebo::EntityComponentManager ecm; + ignition::gazebo::EntityComponentManager ecm; auto modelEntity = ecm.CreateEntity(); - ecm.CreateComponent(modelEntity, gazebo::components::Model()); - ecm.CreateComponent(modelEntity, gazebo::components::Name("model_name")); + ecm.CreateComponent(modelEntity, ignition::gazebo::components::Model()); + ecm.CreateComponent(modelEntity, + ignition::gazebo::components::Name("model_name")); auto jointEntity = ecm.CreateEntity(); - ecm.CreateComponent(jointEntity, gazebo::components::Joint()); - ecm.CreateComponent(jointEntity, gazebo::components::Name("joint_name")); - ecm.CreateComponent(jointEntity, gazebo::components::ParentEntity( + ecm.CreateComponent(jointEntity, ignition::gazebo::components::Joint()); + ecm.CreateComponent(jointEntity, + ignition::gazebo::components::Name("joint_name")); + ecm.CreateComponent(jointEntity, ignition::gazebo::components::ParentEntity( modelEntity)); - ecm.CreateComponent(jointEntity, gazebo::components::JointPosition({0.1})); - ecm.CreateComponent(jointEntity, gazebo::components::JointType( + ecm.CreateComponent(jointEntity, + ignition::gazebo::components::JointPosition({0.1})); + ecm.CreateComponent(jointEntity, ignition::gazebo::components::JointType( sdf::JointType::REVOLUTE)); sdf::JointAxis jointAxis; jointAxis.SetLower(-1.0); jointAxis.SetUpper(1.0); - ecm.CreateComponent(jointEntity, gazebo::components::JointAxis(jointAxis)); + ecm.CreateComponent(jointEntity, + ignition::gazebo::components::JointAxis(jointAxis)); // Populate state message msgs::SerializedStepMap stepMsg; @@ -146,8 +150,8 @@ TEST_F(JointPositionControllerGui, ASSERT_NE(nullptr, app); app->AddPluginPath(std::string(PROJECT_BINARY_PATH) + "/lib"); - // Create GUI runner to handle gazebo::gui plugins - auto runner = new gazebo::GuiRunner("test"); + // Create GUI runner to handle ignition::gazebo::gui plugins + auto runner = new ignition::gazebo::GuiRunner("test"); runner->setParent(gui::App()); // Load plugin @@ -172,7 +176,7 @@ TEST_F(JointPositionControllerGui, // Get plugin auto plugins = win->findChildren< - gazebo::gui::JointPositionController *>(); + ignition::gazebo::gui::JointPositionController *>(); EXPECT_EQ(plugins.size(), 1); auto plugin = plugins[0]; @@ -188,7 +192,7 @@ TEST_F(JointPositionControllerGui, } EXPECT_LT(sleep, maxSleep); - EXPECT_EQ(plugin->ModelEntity(), gazebo::kNullEntity); + EXPECT_EQ(plugin->ModelEntity(), ignition::gazebo::kNullEntity); EXPECT_EQ(plugin->ModelName(), QString("No model selected")) << plugin->ModelName().toStdString(); EXPECT_FALSE(plugin->Locked()); diff --git a/src/gui/plugins/modules/EntityContextMenu.cc b/src/gui/plugins/modules/EntityContextMenu.cc index 28f177504c..a87b315071 100644 --- a/src/gui/plugins/modules/EntityContextMenu.cc +++ b/src/gui/plugins/modules/EntityContextMenu.cc @@ -17,18 +17,18 @@ #include "EntityContextMenu.hh" -#include -#include -#include +#include +#include +#include #include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition::gazebo { @@ -56,7 +56,7 @@ namespace ignition::gazebo } using namespace ignition; -using namespace gazebo; +using namespace ignition::gazebo; ///////////////////////////////////////////////// void IgnGazeboPlugin::registerTypes(const char *_uri) diff --git a/src/gui/plugins/modules/EntityContextMenu.hh b/src/gui/plugins/modules/EntityContextMenu.hh index 80de797028..b46a617b4b 100644 --- a/src/gui/plugins/modules/EntityContextMenu.hh +++ b/src/gui/plugins/modules/EntityContextMenu.hh @@ -15,10 +15,10 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_ENTITYCONTEXTMENU_HH_ -#define IGNITION_GAZEBO_GUI_ENTITYCONTEXTMENU_HH_ +#ifndef GZ_GAZEBO_GUI_ENTITYCONTEXTMENU_HH_ +#define GZ_GAZEBO_GUI_ENTITYCONTEXTMENU_HH_ -#include +#include #include #include diff --git a/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc b/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc index cd62531d73..1e00e4651b 100644 --- a/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc +++ b/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc @@ -17,8 +17,8 @@ #include "PlaybackScrubber.hh" -#include -#include +#include +#include #include #include @@ -27,18 +27,18 @@ #include #include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/components/LogPlaybackStatistics.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/components/LogPlaybackStatistics.hh" +#include "gz/sim/gui/GuiEvents.hh" namespace ignition::gazebo { @@ -69,7 +69,7 @@ namespace ignition::gazebo } using namespace ignition; -using namespace gazebo; +using namespace ignition::gazebo; ///////////////////////////////////////////////// PlaybackScrubber::PlaybackScrubber() : GuiSystem(), @@ -149,7 +149,7 @@ void PlaybackScrubber::Update(const UpdateInfo &_info, if (this->dataPtr->worldName == "") { // TODO(anyone) Only one world is supported for now - auto worldNames = ignition::gui::worldNames(); + auto worldNames = gz::gui::worldNames(); if (worldNames.size() >= 1) { this->dataPtr->worldName = worldNames[0].toStdString(); @@ -253,4 +253,4 @@ void PlaybackScrubber::OnDrop(double _value) // Register this plugin IGNITION_ADD_PLUGIN(PlaybackScrubber, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/playback_scrubber/PlaybackScrubber.hh b/src/gui/plugins/playback_scrubber/PlaybackScrubber.hh index f722669e92..47a51cfbbf 100644 --- a/src/gui/plugins/playback_scrubber/PlaybackScrubber.hh +++ b/src/gui/plugins/playback_scrubber/PlaybackScrubber.hh @@ -15,14 +15,14 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_PLAYBACK_SCRUBBER_HH_ -#define IGNITION_GAZEBO_GUI_PLAYBACK_SCRUBBER_HH_ +#ifndef GZ_GAZEBO_GUI_PLAYBACK_SCRUBBER_HH_ +#define GZ_GAZEBO_GUI_PLAYBACK_SCRUBBER_HH_ #include #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 b2e2657a3c..b237d6822b 100644 --- a/src/gui/plugins/plot_3d/Plot3D.cc +++ b/src/gui/plugins/plot_3d/Plot3D.cc @@ -15,27 +15,27 @@ * */ -#include +#include #include #include -#include +#include -#include -#include +#include +#include -#include +#include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/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" @@ -155,8 +155,8 @@ void Plot3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem) } } - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); } ///////////////////////////////////////////////// @@ -265,7 +265,8 @@ bool Plot3D::eventFilter(QObject *_obj, QEvent *_event) { if (!this->dataPtr->locked) { - if (_event->type() == gazebo::gui::events::EntitiesSelected::kType) + if (_event->type() == + ignition::gazebo::gui::events::EntitiesSelected::kType) { auto event = reinterpret_cast(_event); if (event && !event->Data().empty()) @@ -274,7 +275,8 @@ bool Plot3D::eventFilter(QObject *_obj, QEvent *_event) } } - if (_event->type() == gazebo::gui::events::DeselectAllEntities::kType) + if (_event->type() == + ignition::gazebo::gui::events::DeselectAllEntities::kType) { auto event = reinterpret_cast( _event); @@ -402,4 +404,4 @@ void Plot3D::SetMaxPoints(int _maxPoints) // Register this plugin IGNITION_ADD_PLUGIN(Plot3D, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/plot_3d/Plot3D.hh b/src/gui/plugins/plot_3d/Plot3D.hh index faf4466024..652ae61071 100644 --- a/src/gui/plugins/plot_3d/Plot3D.hh +++ b/src/gui/plugins/plot_3d/Plot3D.hh @@ -15,14 +15,14 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_3DPLOT_HH_ -#define IGNITION_GAZEBO_GUI_3DPLOT_HH_ +#ifndef GZ_GAZEBO_GUI_3DPLOT_HH_ +#define GZ_GAZEBO_GUI_3DPLOT_HH_ #include -#include +#include -#include "ignition/gui/qt.h" +#include "gz/gui/qt.h" namespace ignition { diff --git a/src/gui/plugins/plot_3d/Plot3D_TEST.cc b/src/gui/plugins/plot_3d/Plot3D_TEST.cc index 6e085c3b34..5fe35b90ec 100644 --- a/src/gui/plugins/plot_3d/Plot3D_TEST.cc +++ b/src/gui/plugins/plot_3d/Plot3D_TEST.cc @@ -19,31 +19,31 @@ #ifdef _MSC_VER #pragma warning(push, 0) #endif -#include +#include #ifdef _MSC_VER #pragma warning(pop) #endif -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#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" // Use this when forward-porting to v6 // #include "../../GuiRunner.hh" -#include "ignition/gazebo/gui/GuiRunner.hh" +#include "gz/sim/gui/GuiRunner.hh" #include "Plot3D.hh" @@ -68,8 +68,8 @@ TEST_F(Plot3D, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Load)) ASSERT_NE(nullptr, app); app->AddPluginPath(std::string(PROJECT_BINARY_PATH) + "/lib"); - // Create GUI runner to handle gazebo::gui plugins - auto runner = new gazebo::GuiRunner("test"); + // Create GUI runner to handle ignition::gazebo::gui plugins + auto runner = new ignition::gazebo::GuiRunner("test"); runner->setParent(gui::App()); // Add plugin @@ -100,7 +100,7 @@ TEST_F(Plot3D, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Load)) auto plugin = plugins[0]; EXPECT_EQ("Plot3D!", plugin->Title()); - EXPECT_EQ(gazebo::kNullEntity, plugin->TargetEntity()); + EXPECT_EQ(ignition::gazebo::kNullEntity, plugin->TargetEntity()); EXPECT_EQ(QString("banana"), plugin->TargetName()) << plugin->TargetName().toStdString(); EXPECT_EQ(QVector3D(0.1, 0.2, 0.3), plugin->Color()); diff --git a/src/gui/plugins/resource_spawner/ResourceSpawner.cc b/src/gui/plugins/resource_spawner/ResourceSpawner.cc index 6b40b7c6a6..1db342258a 100644 --- a/src/gui/plugins/resource_spawner/ResourceSpawner.cc +++ b/src/gui/plugins/resource_spawner/ResourceSpawner.cc @@ -17,8 +17,8 @@ #include "ResourceSpawner.hh" -#include -#include +#include +#include #include #include @@ -27,18 +27,18 @@ #include #include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include -#include "ignition/gazebo/gui/GuiEvents.hh" +#include "gz/sim/gui/GuiEvents.hh" namespace ignition::gazebo { @@ -59,7 +59,7 @@ namespace ignition::gazebo public: PathModel ownerModel; /// \brief Client used to download resources from Ignition Fuel. - public: std::unique_ptr + public: std::unique_ptr fuelClient = nullptr; /// \brief The map to cache resources after a search is made on an owner, @@ -74,7 +74,7 @@ namespace ignition::gazebo } using namespace ignition; -using namespace gazebo; +using namespace ignition::gazebo; ///////////////////////////////////////////////// PathModel::PathModel() : QStandardItemModel() @@ -206,14 +206,14 @@ QHash ResourceModel::roleNames() const ///////////////////////////////////////////////// ResourceSpawner::ResourceSpawner() - : ignition::gui::Plugin(), + : gz::gui::Plugin(), dataPtr(std::make_unique()) { - ignition::gui::App()->Engine()->rootContext()->setContextProperty( + gz::gui::App()->Engine()->rootContext()->setContextProperty( "ResourceList", &this->dataPtr->resourceModel); - ignition::gui::App()->Engine()->rootContext()->setContextProperty( + gz::gui::App()->Engine()->rootContext()->setContextProperty( "PathList", &this->dataPtr->pathModel); - ignition::gui::App()->Engine()->rootContext()->setContextProperty( + gz::gui::App()->Engine()->rootContext()->setContextProperty( "OwnerList", &this->dataPtr->ownerModel); this->dataPtr->fuelClient = std::make_unique(); @@ -648,11 +648,11 @@ void ResourceSpawner::OnSortChosen(const QString &_sortType) void ResourceSpawner::OnResourceSpawn(const QString &_sdfPath) { gui::events::SpawnPreviewPath event(_sdfPath.toStdString()); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); } // Register this plugin IGNITION_ADD_PLUGIN(ResourceSpawner, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/resource_spawner/ResourceSpawner.hh b/src/gui/plugins/resource_spawner/ResourceSpawner.hh index 377ad95ec5..6a378cbe81 100644 --- a/src/gui/plugins/resource_spawner/ResourceSpawner.hh +++ b/src/gui/plugins/resource_spawner/ResourceSpawner.hh @@ -15,14 +15,14 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_RESOURCE_SPAWNER_HH_ -#define IGNITION_GAZEBO_GUI_RESOURCE_SPAWNER_HH_ +#ifndef GZ_GAZEBO_GUI_RESOURCE_SPAWNER_HH_ +#define GZ_GAZEBO_GUI_RESOURCE_SPAWNER_HH_ #include #include #include -#include +#include namespace ignition { @@ -140,7 +140,7 @@ namespace gazebo /// \brief Provides interface for communicating to backend for generation /// of local models - class ResourceSpawner : public ignition::gui::Plugin + class ResourceSpawner : public gz::gui::Plugin { Q_OBJECT diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 7ee4a67ab2..a835c04776 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -33,42 +33,42 @@ #include #include -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -#include -#include -#include -#include - -#include "ignition/gazebo/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 +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +#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 @@ -167,7 +167,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public: std::string moveToTarget; /// \brief Helper object to move user camera - public: ignition::rendering::MoveToHelper moveToHelper; + public: gz::rendering::MoveToHelper moveToHelper; /// \brief Target to view collisions public: std::string viewCollisionsTarget; @@ -217,8 +217,8 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public: std::string spawnSdfPath; /// \brief The pose of the spawn preview. - public: ignition::math::Pose3d spawnPreviewPose = - ignition::math::Pose3d::Zero; + public: gz::math::Pose3d spawnPreviewPose = + gz::math::Pose3d::Zero; /// \brief The currently hovered mouse position in screen coordinates public: math::Vector2i mouseHoverPos = math::Vector2i::Zero; @@ -268,7 +268,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public: std::string createCmdService; /// \brief The starting world pose of a clicked visual. - public: ignition::math::Vector3d startWorldPos = math::Vector3d::Zero; + public: gz::math::Vector3d startWorldPos = math::Vector3d::Zero; /// \brief Flag to keep track of world pose setting used /// for button translating. @@ -383,7 +383,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { } using namespace ignition; -using namespace gazebo; +using namespace ignition::gazebo; QList RenderWindowItemPrivate::threads; @@ -776,17 +776,17 @@ void IgnRenderer::Render() } } - if (ignition::gui::App()) + if (gz::gui::App()) { - ignition::gui::events::Render event; - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::Render event; + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); // This will be deprecated on v5 and removed on v6 gui::events::Render oldEvent; - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &oldEvent); } @@ -897,9 +897,9 @@ void IgnRenderer::BroadcastHoverPos() { math::Vector3d pos = this->ScreenToScene(this->dataPtr->mouseHoverPos); - ignition::gui::events::HoverToScene hoverToSceneEvent(pos); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::HoverToScene hoverToSceneEvent(pos); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &hoverToSceneEvent); } } @@ -913,9 +913,9 @@ void IgnRenderer::BroadcastLeftClick() { math::Vector3d pos = this->ScreenToScene(this->dataPtr->mouseEvent.Pos()); - ignition::gui::events::LeftClickToScene leftClickToSceneEvent(pos); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::LeftClickToScene leftClickToSceneEvent(pos); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &leftClickToSceneEvent); } } @@ -933,9 +933,9 @@ void IgnRenderer::BroadcastRightClick() math::Vector3d pos = this->ScreenToScene(this->dataPtr->mouseEvent.Pos()); - ignition::gui::events::RightClickToScene rightClickToSceneEvent(pos); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::RightClickToScene rightClickToSceneEvent(pos); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &rightClickToSceneEvent); } } @@ -1013,17 +1013,17 @@ void IgnRenderer::HandleKeyPress(QKeyEvent *_e) // fullscreen if (_e->key() == Qt::Key_F11) { - if (ignition::gui::App()->findChild - ()->QuickWindow()->visibility() + if (gz::gui::App()->findChild + ()->QuickWindow()->visibility() == QWindow::FullScreen) { - ignition::gui::App()->findChild - ()->QuickWindow()->showNormal(); + gz::gui::App()->findChild + ()->QuickWindow()->showNormal(); } else { - ignition::gui::App()->findChild - ()->QuickWindow()->showFullScreen(); + gz::gui::App()->findChild + ()->QuickWindow()->showFullScreen(); } } @@ -1191,8 +1191,8 @@ void IgnRenderer::DeselectAllEntities(bool _sendEvent) if (_sendEvent) { gui::events::DeselectAllEntities deselectEvent; - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &deselectEvent); } } @@ -1798,8 +1798,8 @@ void IgnRenderer::UpdateSelectedEntity(const rendering::NodePtr &_node, { gui::events::EntitiesSelected selectEvent( this->dataPtr->renderUtil.SelectedEntities()); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &selectEvent); } } @@ -2561,8 +2561,8 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem) elem->QueryBoolText(&fullscreen); if (fullscreen) { - ignition::gui::App()->findChild - ()->QuickWindow()->showFullScreen(); + gz::gui::App()->findChild + ()->QuickWindow()->showFullScreen(); } } } @@ -2627,10 +2627,10 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem) ignmsg << "View collisions service on [" << this->dataPtr->viewCollisionsService << "]" << std::endl; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->QuickWindow()->installEventFilter(this); - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->QuickWindow()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); } ////////////////////////////////////////////////// @@ -3030,10 +3030,10 @@ bool Scene3D::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gui::events::DropdownMenuEnabled::kType) + gz::gui::events::DropdownMenuEnabled::kType) { auto dropdownMenuEnabledEvent = - reinterpret_cast(_event); + reinterpret_cast(_event); if (dropdownMenuEnabledEvent) { auto renderWindow = this->PluginItem()->findChild(); @@ -3210,7 +3210,7 @@ void RenderWindowItem::mousePressEvent(QMouseEvent *_e) { this->forceActiveFocus(); - auto event = ignition::gui::convert(*_e); + auto event = gz::gui::convert(*_e); event.SetPressPos(event.Pos()); this->dataPtr->mouseEvent = event; this->dataPtr->mouseEvent.SetType(common::MouseEvent::PRESS); @@ -3222,7 +3222,7 @@ void RenderWindowItem::mousePressEvent(QMouseEvent *_e) //////////////////////////////////////////////// void RenderWindowItem::mouseReleaseEvent(QMouseEvent *_e) { - auto event = ignition::gui::convert(*_e); + auto event = gz::gui::convert(*_e); event.SetPressPos(this->dataPtr->mouseEvent.PressPos()); // A release at the end of a drag @@ -3239,7 +3239,7 @@ void RenderWindowItem::mouseReleaseEvent(QMouseEvent *_e) //////////////////////////////////////////////// void RenderWindowItem::mouseMoveEvent(QMouseEvent *_e) { - auto event = ignition::gui::convert(*_e); + auto event = gz::gui::convert(*_e); if (!event.Dragging()) return; @@ -3313,5 +3313,5 @@ void RenderWindowItem::HandleKeyRelease(QKeyEvent *_e) // // Register this plugin -IGNITION_ADD_PLUGIN(gazebo::Scene3D, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(ignition::gazebo::Scene3D, + gz::gui::Plugin) diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index 37b95f5db7..869e5479da 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -15,14 +15,14 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_SCENE3D_HH_ -#define IGNITION_GAZEBO_GUI_SCENE3D_HH_ +#ifndef GZ_GAZEBO_GUI_SCENE3D_HH_ +#define GZ_GAZEBO_GUI_SCENE3D_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include @@ -30,19 +30,19 @@ #include -#include -#include -#include -#include +#include +#include +#include +#include -#include -#include +#include +#include -#include +#include -#include +#include -#include "ignition/gui/qt.h" +#include "gz/gui/qt.h" namespace ignition @@ -710,7 +710,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Called when the mouse hovers to a new position. /// \param[in] _hoverPos 2D coordinates of the hovered mouse position on /// the render window. - public: void OnHovered(const ignition::math::Vector2i &_hoverPos); + public: void OnHovered(const gz::math::Vector2i &_hoverPos); /// \brief Get whether the renderer is initialized. The renderer is /// initialized when the context is created and the render thread is diff --git a/src/gui/plugins/shapes/Shapes.cc b/src/gui/plugins/shapes/Shapes.cc index dbb134ac13..778f20bf9a 100644 --- a/src/gui/plugins/shapes/Shapes.cc +++ b/src/gui/plugins/shapes/Shapes.cc @@ -17,21 +17,21 @@ #include "Shapes.hh" -#include -#include +#include +#include #include #include #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include -#include "ignition/gazebo/gui/GuiEvents.hh" +#include "gz/sim/gui/GuiEvents.hh" namespace ignition::gazebo { @@ -41,11 +41,11 @@ namespace ignition::gazebo } using namespace ignition; -using namespace gazebo; +using namespace ignition::gazebo; ///////////////////////////////////////////////// Shapes::Shapes() - : ignition::gui::Plugin(), + : gz::gui::Plugin(), dataPtr(std::make_unique()) { } @@ -60,8 +60,8 @@ void Shapes::LoadConfig(const tinyxml2::XMLElement *) this->title = "Shapes"; // For shapes requests - ignition::gui::App()->findChild - ()->installEventFilter(this); + gz::gui::App()->findChild + ()->installEventFilter(this); } ///////////////////////////////////////////////// @@ -192,11 +192,11 @@ void Shapes::OnMode(const QString &_mode) } gui::events::SpawnPreviewModel event(modelSdfString); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); } // Register this plugin IGNITION_ADD_PLUGIN(Shapes, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/shapes/Shapes.hh b/src/gui/plugins/shapes/Shapes.hh index 3b8e75216b..7a9e7207cb 100644 --- a/src/gui/plugins/shapes/Shapes.hh +++ b/src/gui/plugins/shapes/Shapes.hh @@ -15,12 +15,12 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_SHAPES_HH_ -#define IGNITION_GAZEBO_GUI_SHAPES_HH_ +#ifndef GZ_GAZEBO_GUI_SHAPES_HH_ +#define GZ_GAZEBO_GUI_SHAPES_HH_ #include -#include +#include namespace ignition { @@ -30,7 +30,7 @@ namespace gazebo /// \brief Provides buttons for adding a box, sphere, or cylinder /// to the scene - class Shapes : public ignition::gui::Plugin + class Shapes : public gz::gui::Plugin { Q_OBJECT diff --git a/src/gui/plugins/tape_measure/TapeMeasure.cc b/src/gui/plugins/tape_measure/TapeMeasure.cc index d08189fdf7..2e44050ae5 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.cc +++ b/src/gui/plugins/tape_measure/TapeMeasure.cc @@ -15,23 +15,23 @@ * */ -#include +#include #include #include #include #include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include -#include "ignition/gazebo/gui/GuiEvents.hh" +#include "gz/sim/gui/GuiEvents.hh" #include "TapeMeasure.hh" namespace ignition::gazebo @@ -60,22 +60,22 @@ namespace ignition::gazebo /// \brief The location of the placed starting point of the tape measure /// tool, only set when the user clicks to set the point. - public: ignition::math::Vector3d startPoint = - ignition::math::Vector3d::Zero; + public: gz::math::Vector3d startPoint = + gz::math::Vector3d::Zero; /// \brief The location of the placed ending point of the tape measure /// tool, only set when the user clicks to set the point. - public: ignition::math::Vector3d endPoint = ignition::math::Vector3d::Zero; + public: gz::math::Vector3d endPoint = gz::math::Vector3d::Zero; /// \brief The color to set the marker when hovering the mouse over the /// scene. - public: ignition::math::Color - hoverColor{ignition::math::Color(0.2, 0.2, 0.2, 0.5)}; + public: gz::math::Color + hoverColor{gz::math::Color(0.2, 0.2, 0.2, 0.5)}; /// \brief The color to draw the marker when the user clicks to confirm /// its location. - public: ignition::math::Color - drawColor{ignition::math::Color(0.2, 0.2, 0.2, 1.0)}; + public: gz::math::Color + drawColor{gz::math::Color(0.2, 0.2, 0.2, 1.0)}; /// \brief A set of the currently placed markers. Used to make sure a /// non-existent marker is not deleted. @@ -91,11 +91,11 @@ namespace ignition::gazebo } using namespace ignition; -using namespace gazebo; +using namespace ignition::gazebo; ///////////////////////////////////////////////// TapeMeasure::TapeMeasure() - : ignition::gui::Plugin(), + : gz::gui::Plugin(), dataPtr(std::make_unique()) { } @@ -109,9 +109,9 @@ void TapeMeasure::LoadConfig(const tinyxml2::XMLElement *) if (this->title.empty()) this->title = "Tape measure"; - ignition::gui::App()->findChild + gz::gui::App()->findChild ()->installEventFilter(this); - ignition::gui::App()->findChild + gz::gui::App()->findChild ()->QuickWindow()->installEventFilter(this); } @@ -130,9 +130,9 @@ void TapeMeasure::Measure() // Notify Scene3D to disable the right click menu while we use it to // cancel our current measuring action - ignition::gui::events::DropdownMenuEnabled dropdownMenuEnabledEvent(false); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::DropdownMenuEnabled dropdownMenuEnabledEvent(false); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &dropdownMenuEnabledEvent); } @@ -159,9 +159,9 @@ void TapeMeasure::Reset() // Notify Scene3D that we are done using the right click, so it can // re-enable the settings menu - ignition::gui::events::DropdownMenuEnabled dropdownMenuEnabledEvent(true); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::DropdownMenuEnabled dropdownMenuEnabledEvent(true); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &dropdownMenuEnabledEvent); } @@ -232,10 +232,10 @@ void TapeMeasure::DrawLine(int _id, math::Vector3d &_startPoint, ///////////////////////////////////////////////// bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::HoverToScene::kType) + if (_event->type() == gz::gui::events::HoverToScene::kType) { auto hoverToSceneEvent = - reinterpret_cast(_event); + reinterpret_cast(_event); // This event is called in Scene3d's RenderThread, so it's safe to make // rendering calls here @@ -256,10 +256,10 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) } } } - else if (_event->type() == ignition::gui::events::LeftClickToScene::kType) + else if (_event->type() == gz::gui::events::LeftClickToScene::kType) { auto leftClickToSceneEvent = - reinterpret_cast(_event); + reinterpret_cast(_event); // This event is called in Scene3d's RenderThread, so it's safe to make // rendering calls here @@ -288,11 +288,11 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) // Notify Scene3D that we are done using the right click, so it can // re-enable the settings menu - ignition::gui::events::DropdownMenuEnabled + gz::gui::events::DropdownMenuEnabled dropdownMenuEnabledEvent(true); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &dropdownMenuEnabledEvent); } this->dataPtr->currentId = this->dataPtr->kEndPointId; @@ -317,7 +317,7 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) } } // Cancel the current action if a right click is detected - else if (_event->type() == ignition::gui::events::RightClickToScene::kType) + else if (_event->type() == gz::gui::events::RightClickToScene::kType) { if (this->dataPtr->measure) { @@ -330,4 +330,4 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) // Register this plugin IGNITION_ADD_PLUGIN(TapeMeasure, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/tape_measure/TapeMeasure.hh b/src/gui/plugins/tape_measure/TapeMeasure.hh index 0da8719f2b..56c77c038c 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.hh +++ b/src/gui/plugins/tape_measure/TapeMeasure.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_TAPEMEASURE_HH_ -#define IGNITION_GAZEBO_GUI_TAPEMEASURE_HH_ +#ifndef GZ_GAZEBO_GUI_TAPEMEASURE_HH_ +#define GZ_GAZEBO_GUI_TAPEMEASURE_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -30,7 +30,7 @@ namespace gazebo class TapeMeasurePrivate; /// \brief Provides buttons for the tape measure tool. - class TapeMeasure : public ignition::gui::Plugin + class TapeMeasure : public gz::gui::Plugin { Q_OBJECT @@ -63,8 +63,8 @@ namespace gazebo /// \param[in] _point The x, y, z coordinates of where to place the marker /// \param[in] _color The rgba color to set the marker public: void DrawPoint(int _id, - ignition::math::Vector3d &_point, - ignition::math::Color &_color); + gz::math::Vector3d &_point, + gz::math::Color &_color); /// \brief Draws a line marker. Called to display the line between the /// start and end point of the tape measure. @@ -73,9 +73,9 @@ namespace gazebo /// \param[in] _endPoint The x, y, z coordinates of the line end point /// \param[in] _color The rgba color to set the marker public: void DrawLine(int _id, - ignition::math::Vector3d &_startPoint, - ignition::math::Vector3d &_endPoint, - ignition::math::Color &_color); + gz::math::Vector3d &_startPoint, + gz::math::Vector3d &_endPoint, + gz::math::Color &_color); /// \brief Callback in Qt thread when the new measurement button is /// clicked. diff --git a/src/gui/plugins/transform_control/TransformControl.cc b/src/gui/plugins/transform_control/TransformControl.cc index e30d2e956e..67a0244ad6 100644 --- a/src/gui/plugins/transform_control/TransformControl.cc +++ b/src/gui/plugins/transform_control/TransformControl.cc @@ -17,27 +17,27 @@ #include "TransformControl.hh" -#include -#include +#include +#include #include #include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/gui/GuiEvents.hh" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "gz/sim/gui/GuiEvents.hh" namespace ignition::gazebo { @@ -70,11 +70,11 @@ namespace ignition::gazebo } using namespace ignition; -using namespace gazebo; +using namespace ignition::gazebo; ///////////////////////////////////////////////// TransformControl::TransformControl() - : ignition::gui::Plugin(), + : gz::gui::Plugin(), dataPtr(std::make_unique()) { } @@ -91,9 +91,9 @@ void TransformControl::LoadConfig(const tinyxml2::XMLElement *) // For transform requests this->dataPtr->service = "/gui/transform_mode"; - ignition::gui::App()->findChild + gz::gui::App()->findChild ()->installEventFilter(this); - ignition::gui::App()->findChild + gz::gui::App()->findChild ()->QuickWindow()->installEventFilter(this); } @@ -111,8 +111,8 @@ void TransformControl::OnSnapUpdate( this->dataPtr->xyzSnapVals, this->dataPtr->rpySnapVals, this->dataPtr->scaleSnapVals); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), &event); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); this->newSnapValues(); } @@ -276,4 +276,4 @@ double TransformControl::scaleZSnap() // Register this plugin IGNITION_ADD_PLUGIN(TransformControl, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/transform_control/TransformControl.hh b/src/gui/plugins/transform_control/TransformControl.hh index 3c8a4e5dd5..4a2baf7f67 100644 --- a/src/gui/plugins/transform_control/TransformControl.hh +++ b/src/gui/plugins/transform_control/TransformControl.hh @@ -15,12 +15,12 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_TRANSFORMCONTROL_HH_ -#define IGNITION_GAZEBO_GUI_TRANSFORMCONTROL_HH_ +#ifndef GZ_GAZEBO_GUI_TRANSFORMCONTROL_HH_ +#define GZ_GAZEBO_GUI_TRANSFORMCONTROL_HH_ #include -#include +#include namespace ignition { @@ -32,7 +32,7 @@ namespace gazebo /// /// ## Configuration /// \ : Set the service to receive transform mode requests. - class TransformControl : public ignition::gui::Plugin + class TransformControl : public gz::gui::Plugin { Q_OBJECT diff --git a/src/gui/plugins/video_recorder/VideoRecorder.cc b/src/gui/plugins/video_recorder/VideoRecorder.cc index 5249fa2c28..473b736026 100644 --- a/src/gui/plugins/video_recorder/VideoRecorder.cc +++ b/src/gui/plugins/video_recorder/VideoRecorder.cc @@ -17,18 +17,18 @@ #include "VideoRecorder.hh" -#include -#include +#include +#include #include #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include namespace ignition::gazebo { @@ -46,7 +46,7 @@ namespace ignition::gazebo } using namespace ignition; -using namespace gazebo; +using namespace ignition::gazebo; ///////////////////////////////////////////////// VideoRecorder::VideoRecorder() @@ -144,4 +144,4 @@ void VideoRecorder::OnCancel() // Register this plugin IGNITION_ADD_PLUGIN(VideoRecorder, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/video_recorder/VideoRecorder.hh b/src/gui/plugins/video_recorder/VideoRecorder.hh index b9f98e8ddf..b7d87bc87d 100644 --- a/src/gui/plugins/video_recorder/VideoRecorder.hh +++ b/src/gui/plugins/video_recorder/VideoRecorder.hh @@ -15,12 +15,12 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_VIDEORECORDER_HH_ -#define IGNITION_GAZEBO_GUI_VIDEORECORDER_HH_ +#ifndef GZ_GAZEBO_GUI_VIDEORECORDER_HH_ +#define GZ_GAZEBO_GUI_VIDEORECORDER_HH_ #include -#include +#include namespace ignition { @@ -29,7 +29,7 @@ namespace gazebo class VideoRecorderPrivate; /// \brief Provides buttons for starting and stopping video recording - class VideoRecorder : public ignition::gui::Plugin + class VideoRecorder : public gz::gui::Plugin { Q_OBJECT diff --git a/src/gui/plugins/view_angle/ViewAngle.cc b/src/gui/plugins/view_angle/ViewAngle.cc index 84bb9c7b9b..fb857ef9ad 100644 --- a/src/gui/plugins/view_angle/ViewAngle.cc +++ b/src/gui/plugins/view_angle/ViewAngle.cc @@ -17,16 +17,16 @@ #include "ViewAngle.hh" -#include -#include -#include +#include +#include +#include #include #include -#include -#include -#include +#include +#include +#include namespace ignition::gazebo { @@ -50,7 +50,7 @@ namespace ignition::gazebo } using namespace ignition; -using namespace gazebo; +using namespace ignition::gazebo; ///////////////////////////////////////////////// ViewAngle::ViewAngle() @@ -144,4 +144,4 @@ void ViewAngle::CamPoseCb(const msgs::Pose &_msg) // Register this plugin IGNITION_ADD_PLUGIN(ViewAngle, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/view_angle/ViewAngle.hh b/src/gui/plugins/view_angle/ViewAngle.hh index d58b064aed..ebe20f2225 100644 --- a/src/gui/plugins/view_angle/ViewAngle.hh +++ b/src/gui/plugins/view_angle/ViewAngle.hh @@ -15,14 +15,14 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_VIEWANGLE_HH_ -#define IGNITION_GAZEBO_GUI_VIEWANGLE_HH_ +#ifndef GZ_GAZEBO_GUI_VIEWANGLE_HH_ +#define GZ_GAZEBO_GUI_VIEWANGLE_HH_ -#include +#include #include -#include +#include namespace ignition { @@ -34,7 +34,7 @@ namespace gazebo /// /// ## Configuration /// \ : Set the service to receive view angle requests. - class ViewAngle : public ignition::gui::Plugin + class ViewAngle : public gz::gui::Plugin { Q_OBJECT diff --git a/src/ign.cc b/src/gz.cc similarity index 95% rename from src/ign.cc rename to src/gz.cc index 7d581a4c0a..91124c1ec4 100644 --- a/src/ign.cc +++ b/src/gz.cc @@ -15,29 +15,29 @@ * */ -#include "ign.hh" +#include "gz.hh" #include #include #include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#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" -using namespace ignition; +using namespace gz; ////////////////////////////////////////////////// extern "C" IGNITION_GAZEBO_VISIBLE char *ignitionGazeboVersion() @@ -137,7 +137,7 @@ extern "C" IGNITION_GAZEBO_VISIBLE int runServer(const char *_sdfString, const char *_file, const char *_recordTopics, int _waitGui) { std::string startingWorldPath{""}; - gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; // Lock until the starting world is received from Gui if (_waitGui == 1) @@ -402,7 +402,7 @@ extern "C" IGNITION_GAZEBO_VISIBLE int runServer(const char *_sdfString, } // Create the Gazebo server - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); // Run the server server.Run(true, _iterations, _run == 0); @@ -426,6 +426,6 @@ extern "C" IGNITION_GAZEBO_VISIBLE int runGui( // be converted to a const char *. The const cast is here to prevent a warning // since we do need to pass a char* to runGui char *argv = const_cast("ign-gazebo-gui"); - return gazebo::gui::runGui( + return gz::sim::gui::runGui( argc, &argv, _guiConfig, _file, _waitGui); } diff --git a/src/ign.hh b/src/gz.hh similarity index 97% rename from src/ign.hh rename to src/gz.hh index 07b47a803a..4614cb826c 100644 --- a/src/ign.hh +++ b/src/gz.hh @@ -14,10 +14,10 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_IGN_HH_ -#define IGNITION_GAZEBO_IGN_HH_ +#ifndef GZ_GAZEBO_IGN_HH_ +#define GZ_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/gz_TEST.cc similarity index 94% rename from src/ign_TEST.cc rename to src/gz_TEST.cc index 5aa862d3fa..40d39c593c 100644 --- a/src/ign_TEST.cc +++ b/src/gz_TEST.cc @@ -21,11 +21,11 @@ #include #include -#include -#include -#include +#include +#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); @@ -98,7 +98,7 @@ TEST(CmdLine, Server) TEST(CmdLine, CachedFuelWorld) { std::string projectPath = std::string(PROJECT_SOURCE_PATH) + "/test/worlds"; - ignition::common::setenv("IGN_FUEL_CACHE_PATH", projectPath.c_str()); + gz::common::setenv("IGN_FUEL_CACHE_PATH", projectPath.c_str()); std::string cmd = kIgnCommand + " -r -v 4 --iterations 5" + " https://fuel.gazebosim.org/1.0/openroboticstest/worlds/test%20world"; std::cout << "Running command [" << cmd << "]" << std::endl; @@ -177,7 +177,7 @@ TEST(CmdLine, GazeboHelpVsCompletionFlags) std::string helpOutput = customExecStr(kIgnCommand + " gazebo --help"); // Call the output function in the bash completion script - std::string scriptPath = ignition::common::joinPaths( + std::string scriptPath = gz::common::joinPaths( std::string(PROJECT_SOURCE_PATH), "src", "cmd", "gazebo.bash_completion.sh"); @@ -208,7 +208,7 @@ TEST(CmdLine, ModelHelpVsCompletionFlags) std::string helpOutput = customExecStr(kIgnModelCommand + " --help"); // Call the output function in the bash completion script - std::string scriptPath = ignition::common::joinPaths( + std::string scriptPath = gz::common::joinPaths( std::string(PROJECT_SOURCE_PATH), "src", "cmd", "model.bash_completion.sh"); diff --git a/src/network/NetworkConfig.cc b/src/network/NetworkConfig.cc index c8e68e5369..7b6f74fd0c 100644 --- a/src/network/NetworkConfig.cc +++ b/src/network/NetworkConfig.cc @@ -18,11 +18,11 @@ #include -#include "ignition/common/Console.hh" -#include "ignition/common/Util.hh" +#include "gz/common/Console.hh" +#include "gz/common/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ///////////////////////////////////////////////// NetworkConfig NetworkConfig::FromValues(const std::string &_role, diff --git a/src/network/NetworkConfig.hh b/src/network/NetworkConfig.hh index b1b0893ff4..92cf14f718 100644 --- a/src/network/NetworkConfig.hh +++ b/src/network/NetworkConfig.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_NETWORK_NETWORKCONFIG_HH_ -#define IGNITION_GAZEBO_NETWORK_NETWORKCONFIG_HH_ +#ifndef GZ_GAZEBO_NETWORK_NETWORKCONFIG_HH_ +#define GZ_GAZEBO_NETWORK_NETWORKCONFIG_HH_ #include #include -#include -#include +#include +#include #include "NetworkRole.hh" @@ -57,4 +57,4 @@ namespace ignition } // namespace gazebo } // namespace ignition -#endif // IGNITION_GAZEBO_NETWORKCONFIG_HH_ +#endif // GZ_GAZEBO_NETWORKCONFIG_HH_ diff --git a/src/network/NetworkConfig_TEST.cc b/src/network/NetworkConfig_TEST.cc index a582122647..b60ea77f48 100644 --- a/src/network/NetworkConfig_TEST.cc +++ b/src/network/NetworkConfig_TEST.cc @@ -17,16 +17,16 @@ #include -#include -#include +#include +#include #include "NetworkConfig.hh" -using namespace ignition::gazebo; +using namespace gz::sim; TEST(NetworkManager, ValueConstructor) { - ignition::common::Console::SetVerbosity(4); + gz::common::Console::SetVerbosity(4); { // Primary without number of secondaries is invalid auto config = NetworkConfig::FromValues("PRIMARY", 0); diff --git a/src/network/NetworkManager.cc b/src/network/NetworkManager.cc index 6bbc0bbd57..14a00816e8 100644 --- a/src/network/NetworkManager.cc +++ b/src/network/NetworkManager.cc @@ -19,17 +19,17 @@ #include #include -#include "ignition/common/Console.hh" -#include "ignition/common/Util.hh" -#include "ignition/gazebo/Events.hh" +#include "gz/common/Console.hh" +#include "gz/common/Util.hh" +#include "gz/sim/Events.hh" #include "NetworkManager.hh" #include "NetworkManagerPrivate.hh" #include "NetworkManagerPrimary.hh" #include "NetworkManagerSecondary.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; bool validateConfig(const NetworkConfig &_config) diff --git a/src/network/NetworkManager.hh b/src/network/NetworkManager.hh index 3250298c72..bca6b815a0 100644 --- a/src/network/NetworkManager.hh +++ b/src/network/NetworkManager.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_NETWORK_NETWORKMANAGER_HH_ -#define IGNITION_GAZEBO_NETWORK_NETWORKMANAGER_HH_ +#ifndef GZ_GAZEBO_NETWORK_NETWORKMANAGER_HH_ +#define GZ_GAZEBO_NETWORK_NETWORKMANAGER_HH_ #include #include #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include "NetworkConfig.hh" @@ -46,7 +46,7 @@ namespace ignition class NetworkManager { /// \brief Convenience type alias for NodeOptions - public: using NodeOptions = ignition::transport::NodeOptions; + public: using NodeOptions = gz::transport::NodeOptions; /// \brief Create a class derived from NetworkManager based on /// a given configuration @@ -125,4 +125,4 @@ namespace ignition } // namespace gazebo } // namespace ignition -#endif // IGNITION_GAZEBO_NETWORKMANAGER_HH_ +#endif // GZ_GAZEBO_NETWORKMANAGER_HH_ diff --git a/src/network/NetworkManagerPrimary.cc b/src/network/NetworkManagerPrimary.cc index 0dcf6b8e77..5530585a20 100644 --- a/src/network/NetworkManagerPrimary.cc +++ b/src/network/NetworkManagerPrimary.cc @@ -23,25 +23,25 @@ #include #include -#include -#include -#include +#include +#include +#include #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" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; ////////////////////////////////////////////////// diff --git a/src/network/NetworkManagerPrimary.hh b/src/network/NetworkManagerPrimary.hh index 1d01c91cf1..ce57d9720f 100644 --- a/src/network/NetworkManagerPrimary.hh +++ b/src/network/NetworkManagerPrimary.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_NETWORK_NETWORKMANAGERPRIMARY_HH_ -#define IGNITION_GAZEBO_NETWORK_NETWORKMANAGERPRIMARY_HH_ +#ifndef GZ_GAZEBO_NETWORK_NETWORKMANAGERPRIMARY_HH_ +#define GZ_GAZEBO_NETWORK_NETWORKMANAGERPRIMARY_HH_ #include #include @@ -24,10 +24,10 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include "msgs/simulation_step.pb.h" @@ -111,10 +111,10 @@ namespace ignition private: std::map secondaries; /// \brief Transport node - private: ignition::transport::Node node; + private: gz::transport::Node node; /// \brief Publisher for network step sync - private: ignition::transport::Node::Publisher simStepPub; + private: gz::transport::Node::Publisher simStepPub; /// \brief Keep track of states received from secondaries. private: std::vector secondaryStates; @@ -126,5 +126,5 @@ namespace ignition } // namespace gazebo } // namespace ignition -#endif // IGNITION_GAZEBO_NETWORKMANAGERPRIMARY_HH_ +#endif // GZ_GAZEBO_NETWORKMANAGERPRIMARY_HH_ diff --git a/src/network/NetworkManagerPrivate.hh b/src/network/NetworkManagerPrivate.hh index 314f105d0a..515dd0e8ab 100644 --- a/src/network/NetworkManagerPrivate.hh +++ b/src/network/NetworkManagerPrivate.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_NETWORK_NETWORKMANAGERPRIVATE_HH_ -#define IGNITION_GAZEBO_NETWORK_NETWORKMANAGERPRIVATE_HH_ +#ifndef GZ_GAZEBO_NETWORK_NETWORKMANAGERPRIVATE_HH_ +#define GZ_GAZEBO_NETWORK_NETWORKMANAGERPRIVATE_HH_ #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 NetworkManagerPrivate { /// \brief Network Configuration @@ -50,10 +50,10 @@ namespace ignition public: std::unique_ptr tracker; /// \brief Track connection to "PeerRemoved" Event - public: ignition::common::ConnectionPtr peerRemovedConn; + public: gz::common::ConnectionPtr peerRemovedConn; /// \brief Traack connection to "PeerStale" Event - public: ignition::common::ConnectionPtr peerStaleConn; + public: gz::common::ConnectionPtr peerStaleConn; /// \brief Function from the SimulationRunner to call for stepping. /// It will update the systems. @@ -66,11 +66,10 @@ namespace ignition public: std::atomic stopReceived {false}; /// \brief Track connection to "events::Stop" Event - public: ignition::common::ConnectionPtr stoppingConn; + public: gz::common::ConnectionPtr stoppingConn; }; } } // namespace gazebo } // namespace ignition -#endif // IGNITION_GAZEBO_NETWORKMANAGER_HH_ - +#endif // GZ_GAZEBO_NETWORKMANAGER_HH_ diff --git a/src/network/NetworkManagerSecondary.cc b/src/network/NetworkManagerSecondary.cc index 46b979fa70..845573a52b 100644 --- a/src/network/NetworkManagerSecondary.cc +++ b/src/network/NetworkManagerSecondary.cc @@ -18,24 +18,24 @@ #include #include -#include -#include -#include +#include +#include +#include #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" #include "PeerTracker.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ////////////////////////////////////////////////// NetworkManagerSecondary::NetworkManagerSecondary( diff --git a/src/network/NetworkManagerSecondary.hh b/src/network/NetworkManagerSecondary.hh index 3b4163d58a..b9d0937324 100644 --- a/src/network/NetworkManagerSecondary.hh +++ b/src/network/NetworkManagerSecondary.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_NETWORK_NETWORKMANAGERSECONDARY_HH_ -#define IGNITION_GAZEBO_NETWORK_NETWORKMANAGERSECONDARY_HH_ +#ifndef GZ_GAZEBO_NETWORK_NETWORKMANAGERSECONDARY_HH_ +#define GZ_GAZEBO_NETWORK_NETWORKMANAGERSECONDARY_HH_ #include #include #include #include -#include -#include -#include +#include +#include +#include #include "msgs/simulation_step.pb.h" #include "msgs/peer_control.pb.h" @@ -74,10 +74,10 @@ namespace ignition private: std::atomic enableSim {false}; /// \brief Transport node used for communication with simulation graph. - private: ignition::transport::Node node; + private: gz::transport::Node node; /// \brief Publish step acknowledgement messages. - private: ignition::transport::Node::Publisher stepAckPub; + private: gz::transport::Node::Publisher stepAckPub; /// \brief Collection of performers associated with this secondary. private: std::unordered_set performers; @@ -86,5 +86,5 @@ namespace ignition } // namespace gazebo } // namespace ignition -#endif // IGNITION_GAZEBO_NETWORKMANAGERSECONDARY_HH_ +#endif // GZ_GAZEBO_NETWORKMANAGERSECONDARY_HH_ diff --git a/src/network/NetworkManager_TEST.cc b/src/network/NetworkManager_TEST.cc index ec4e0408d8..1d2ba162ca 100644 --- a/src/network/NetworkManager_TEST.cc +++ b/src/network/NetworkManager_TEST.cc @@ -18,14 +18,14 @@ #include #include -#include +#include -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/EntityComponentManager.hh" #include "NetworkManager.hh" #include "NetworkManagerPrimary.hh" #include "NetworkManagerSecondary.hh" -using namespace ignition::gazebo; +using namespace gz::sim; void step(const UpdateInfo &) { @@ -34,7 +34,7 @@ void step(const UpdateInfo &) ////////////////////////////////////////////////// TEST(NetworkManager, ConfigConstructor) { - ignition::common::Console::SetVerbosity(4); + gz::common::Console::SetVerbosity(4); EntityComponentManager ecm; @@ -92,7 +92,7 @@ TEST(NetworkManager, ConfigConstructor) ////////////////////////////////////////////////// TEST(NetworkManager, EstablishComms) { - ignition::common::Console::SetVerbosity(4); + gz::common::Console::SetVerbosity(4); EntityComponentManager ecm; @@ -150,7 +150,7 @@ TEST(NetworkManager, EstablishComms) ////////////////////////////////////////////////// TEST(NetworkManager, Step) { - ignition::common::Console::SetVerbosity(4); + gz::common::Console::SetVerbosity(4); EntityComponentManager ecm; diff --git a/src/network/NetworkRole.hh b/src/network/NetworkRole.hh index 4861cf2789..d1c3292f74 100644 --- a/src/network/NetworkRole.hh +++ b/src/network/NetworkRole.hh @@ -14,11 +14,11 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_NETWORK_NETWORKROLE_HH_ -#define IGNITION_GAZEBO_NETWORK_NETWORKROLE_HH_ +#ifndef GZ_GAZEBO_NETWORK_NETWORKROLE_HH_ +#define GZ_GAZEBO_NETWORK_NETWORKROLE_HH_ -#include -#include +#include +#include namespace ignition { @@ -50,5 +50,5 @@ namespace ignition } // namespace gazebo } // namespace ignition -#endif // IGNITION_GAZEBO_NETWORKROLE_HH_ +#endif // GZ_GAZEBO_NETWORKROLE_HH_ diff --git a/src/network/PeerInfo.cc b/src/network/PeerInfo.cc index b345fde017..02f934c409 100644 --- a/src/network/PeerInfo.cc +++ b/src/network/PeerInfo.cc @@ -16,11 +16,11 @@ */ #include "PeerInfo.hh" -#include "ignition/common/Uuid.hh" -#include "ignition/transport/NetUtils.hh" +#include "gz/common/Uuid.hh" +#include "gz/transport/NetUtils.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ///////////////////////////////////////////////// PeerInfo::PeerInfo(const NetworkRole &_role): @@ -42,7 +42,7 @@ std::string PeerInfo::Namespace() const } ///////////////////////////////////////////////// -private_msgs::PeerInfo gazebo::toProto( +private_msgs::PeerInfo ignition::gazebo::toProto( const PeerInfo &_info) { private_msgs::PeerInfo proto; @@ -70,7 +70,7 @@ private_msgs::PeerInfo gazebo::toProto( } ///////////////////////////////////////////////// -PeerInfo gazebo::fromProto( +PeerInfo ignition::gazebo::fromProto( const private_msgs::PeerInfo& _proto) { PeerInfo info; diff --git a/src/network/PeerInfo.hh b/src/network/PeerInfo.hh index 2fd3ba9f71..4932b4293f 100644 --- a/src/network/PeerInfo.hh +++ b/src/network/PeerInfo.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_NETWORK_PEERINFO_HH_ -#define IGNITION_GAZEBO_NETWORK_PEERINFO_HH_ +#ifndef GZ_GAZEBO_NETWORK_PEERINFO_HH_ +#define GZ_GAZEBO_NETWORK_PEERINFO_HH_ #include -#include -#include +#include +#include #include "NetworkRole.hh" #include "msgs/peer_info.pb.h" @@ -64,5 +64,5 @@ namespace ignition } // namespace gazebo } // namespace ignition -#endif // IGNITION_GAZEBO_NETWORK_PEERINFO_HH_ +#endif // GZ_GAZEBO_NETWORK_PEERINFO_HH_ diff --git a/src/network/PeerTracker.cc b/src/network/PeerTracker.cc index e10a785e84..80053bf071 100644 --- a/src/network/PeerTracker.cc +++ b/src/network/PeerTracker.cc @@ -19,8 +19,8 @@ #include #include -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ///////////////////////////////////////////////// PeerTracker::PeerTracker( diff --git a/src/network/PeerTracker.hh b/src/network/PeerTracker.hh index e19a8d42f6..51f37707bb 100644 --- a/src/network/PeerTracker.hh +++ b/src/network/PeerTracker.hh @@ -14,20 +14,20 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_NETWORK_PEERTRACKER_HH_ -#define IGNITION_GAZEBO_NETWORK_PEERTRACKER_HH_ +#ifndef GZ_GAZEBO_NETWORK_PEERTRACKER_HH_ +#define GZ_GAZEBO_NETWORK_PEERTRACKER_HH_ #include #include #include #include -#include -#include -#include +#include +#include +#include -#include -#include +#include +#include #include "PeerInfo.hh" @@ -55,7 +55,7 @@ namespace ignition /// announcements and heartbeats from other peers. class PeerTracker { /// \brief Convenience type alias for NodeOptions - public: using NodeOptions = ignition::transport::NodeOptions; + public: using NodeOptions = gz::transport::NodeOptions; /// \brief Convenience type alias for duration public: using Duration = std::chrono::steady_clock::duration; @@ -209,18 +209,18 @@ namespace ignition private: EventManager *eventMgr; /// \brief Transport node - private: ignition::transport::Node node; + private: gz::transport::Node node; /// \brief Heartbeat publisher - private: ignition::transport::Node::Publisher heartbeatPub; + private: gz::transport::Node::Publisher heartbeatPub; /// \brief Announcement publisher - private: ignition::transport::Node::Publisher announcePub; + private: gz::transport::Node::Publisher announcePub; }; } } // namespace gazebo } // namespace ignition -#endif // IGNITION_GAZEBO_NETWORKCONFIG_HH_ +#endif // GZ_GAZEBO_NETWORKCONFIG_HH_ diff --git a/src/network/PeerTracker_TEST.cc b/src/network/PeerTracker_TEST.cc index 13b83d9924..2e63a9b3bd 100644 --- a/src/network/PeerTracker_TEST.cc +++ b/src/network/PeerTracker_TEST.cc @@ -18,19 +18,19 @@ #include #include -#include -#include -#include +#include +#include +#include #include "PeerTracker.hh" -#include "ignition/gazebo/EventManager.hh" +#include "gz/sim/EventManager.hh" -using namespace ignition::gazebo; +using namespace gz::sim; ////////////////////////////////////////////////// TEST(PeerTracker, PeerTracker) { - ignition::common::Console::SetVerbosity(4); + gz::common::Console::SetVerbosity(4); EventManager eventMgr; std::atomic peers = 0; @@ -146,7 +146,7 @@ TEST(PeerTracker, PeerTracker) ////////////////////////////////////////////////// TEST(PeerTracker, IGN_UTILS_TEST_DISABLED_ON_MAC(PeerTrackerStale)) { - ignition::common::Console::SetVerbosity(4); + gz::common::Console::SetVerbosity(4); EventManager eventMgr; // Tracker with artificially short timeout. @@ -190,15 +190,15 @@ TEST(PeerTracker, IGN_UTILS_TEST_DISABLED_ON_MAC(PeerTrackerStale)) ////////////////////////////////////////////////// TEST(PeerTracker, Partitioned) { - ignition::common::Console::SetVerbosity(4); + gz::common::Console::SetVerbosity(4); EventManager eventMgr; - auto options1 = ignition::transport::NodeOptions(); + auto options1 = gz::transport::NodeOptions(); options1.SetPartition("p1"); auto tracker1 = PeerTracker( PeerInfo(NetworkRole::SimulationPrimary), &eventMgr, options1); - auto options2 = ignition::transport::NodeOptions(); + auto options2 = gz::transport::NodeOptions(); options2.SetPartition("p2"); auto tracker2 = PeerTracker( PeerInfo(NetworkRole::SimulationPrimary), &eventMgr, options2); @@ -238,15 +238,15 @@ TEST(PeerTracker, Partitioned) ////////////////////////////////////////////////// TEST(PeerTracker, Namespaced) { - ignition::common::Console::SetVerbosity(4); + gz::common::Console::SetVerbosity(4); EventManager eventMgr; - auto options1 = ignition::transport::NodeOptions(); + auto options1 = gz::transport::NodeOptions(); options1.SetNameSpace("ns1"); auto tracker1 = PeerTracker( PeerInfo(NetworkRole::SimulationPrimary), &eventMgr, options1); - auto options2 = ignition::transport::NodeOptions(); + auto options2 = gz::transport::NodeOptions(); options2.SetNameSpace("ns2"); auto tracker2 = PeerTracker( PeerInfo(NetworkRole::SimulationPrimary), &eventMgr, options2); @@ -280,14 +280,14 @@ TEST(PeerTracker, Namespaced) #ifdef __linux__ TEST(PeerTracker, PartitionedEnv) { - ignition::common::Console::SetVerbosity(4); + gz::common::Console::SetVerbosity(4); EventManager eventMgr; - ignition::common::setenv("IGN_PARTITION", "p1"); + gz::common::setenv("IGN_PARTITION", "p1"); auto tracker1 = PeerTracker( PeerInfo(NetworkRole::SimulationPrimary), &eventMgr); - ignition::common::setenv("IGN_PARTITION", "p2"); + gz::common::setenv("IGN_PARTITION", "p2"); auto tracker2 = PeerTracker( PeerInfo(NetworkRole::SimulationPrimary), &eventMgr); @@ -298,11 +298,11 @@ TEST(PeerTracker, PartitionedEnv) EXPECT_EQ(0u, tracker1.NumPeers()); EXPECT_EQ(0u, tracker2.NumPeers()); - ignition::common::setenv("IGN_PARTITION", "p1"); + gz::common::setenv("IGN_PARTITION", "p1"); auto tracker3 = PeerTracker( PeerInfo(NetworkRole::SimulationSecondary), &eventMgr); - ignition::common::setenv("IGN_PARTITION", "p2"); + gz::common::setenv("IGN_PARTITION", "p2"); auto tracker4 = PeerTracker( PeerInfo(NetworkRole::SimulationSecondary), &eventMgr); @@ -316,6 +316,6 @@ TEST(PeerTracker, PartitionedEnv) EXPECT_EQ(1u, tracker3.NumPeers()); EXPECT_EQ(1u, tracker4.NumPeers()); - ignition::common::unsetenv("IGN_PARTITION"); + gz::common::unsetenv("IGN_PARTITION"); } #endif diff --git a/src/rendering/MarkerManager.cc b/src/rendering/MarkerManager.cc index bdd8f082a9..1c057e3720 100644 --- a/src/rendering/MarkerManager.cc +++ b/src/rendering/MarkerManager.cc @@ -22,22 +22,22 @@ #include #include -#include +#include -#include "ignition/gazebo/Events.hh" -#include "ignition/gazebo/Conversions.hh" -#include "ignition/common/Console.hh" -#include "ignition/rendering/Marker.hh" -#include "ignition/rendering/RenderingIface.hh" -#include "ignition/rendering/Scene.hh" +#include "gz/sim/Events.hh" +#include "gz/sim/Conversions.hh" +#include "gz/common/Console.hh" +#include "gz/rendering/Marker.hh" +#include "gz/rendering/RenderingIface.hh" +#include "gz/rendering/Scene.hh" -#include "ignition/gazebo/rendering/MarkerManager.hh" +#include "gz/sim/rendering/MarkerManager.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// Private data for the MarkerManager class -class ignition::gazebo::MarkerManagerPrivate +class gz::sim::MarkerManagerPrivate { /// \brief Processes a marker message. /// \param[in] _msg The message data. diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 0756702774..f35c6bedfa 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -29,53 +29,53 @@ #include #include -#include - -#include -#include -#include -#include - -#include -#include -#include -#include - -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/Camera.hh" -#include "ignition/gazebo/components/CastShadows.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/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/Pose.hh" -#include "ignition/gazebo/components/RgbdCamera.hh" -#include "ignition/gazebo/components/Scene.hh" -#include "ignition/gazebo/components/Temperature.hh" -#include "ignition/gazebo/components/ThermalCamera.hh" -#include "ignition/gazebo/components/Transparency.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/EntityComponentManager.hh" - -#include "ignition/gazebo/rendering/RenderUtil.hh" -#include "ignition/gazebo/rendering/SceneManager.hh" -#include "ignition/gazebo/rendering/MarkerManager.hh" - -#include "ignition/gazebo/Util.hh" - -using namespace ignition; -using namespace gazebo; +#include + +#include +#include +#include +#include + +#include +#include +#include +#include + +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/Camera.hh" +#include "gz/sim/components/CastShadows.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/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/Pose.hh" +#include "gz/sim/components/RgbdCamera.hh" +#include "gz/sim/components/Scene.hh" +#include "gz/sim/components/Temperature.hh" +#include "gz/sim/components/ThermalCamera.hh" +#include "gz/sim/components/Transparency.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/EntityComponentManager.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 gz; +using namespace gz::sim; // Private data class. -class ignition::gazebo::RenderUtilPrivate +class gz::sim::RenderUtilPrivate { /// True if the rendering component is initialized public: bool initialized = false; diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index aca843d96a..67c93485c4 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -28,29 +28,29 @@ #include #include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include - -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/rendering/SceneManager.hh" - -using namespace ignition; -using namespace gazebo; +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include "gz/sim/Util.hh" +#include "gz/sim/rendering/SceneManager.hh" + +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; /// \brief Private data class. -class ignition::gazebo::SceneManagerPrivate +class gz::sim::SceneManagerPrivate { /// \brief Keep track of world ID, which is equivalent to the scene's /// root visual. diff --git a/src/systems/ackermann_steering/AckermannSteering.cc b/src/systems/ackermann_steering/AckermannSteering.cc index 34d22ab1a7..dbc8225e66 100644 --- a/src/systems/ackermann_steering/AckermannSteering.cc +++ b/src/systems/ackermann_steering/AckermannSteering.cc @@ -17,29 +17,29 @@ #include "AckermannSteering.hh" -#include +#include #include #include #include #include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/CanonicalLink.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/JointVelocityCmd.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" - -using namespace ignition; -using namespace gazebo; +#include +#include +#include +#include +#include +#include + +#include "gz/sim/components/CanonicalLink.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/JointVelocityCmd.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" + +using namespace gz; +using namespace gz::sim; using namespace systems; /// \brief Velocity command. @@ -54,7 +54,7 @@ struct Commands Commands() : lin(0.0), ang(0.0) {} }; -class ignition::gazebo::systems::AckermannSteeringPrivate +class gz::sim::systems::AckermannSteeringPrivate { /// \brief Callback for velocity subscription /// \param[in] _msg Velocity message @@ -793,5 +793,9 @@ IGNITION_ADD_PLUGIN(AckermannSteering, AckermannSteering::ISystemPreUpdate, AckermannSteering::ISystemPostUpdate) +IGNITION_ADD_PLUGIN_ALIAS(AckermannSteering, + "gz::sim::systems::AckermannSteering") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(AckermannSteering, "ignition::gazebo::systems::AckermannSteering") diff --git a/src/systems/ackermann_steering/AckermannSteering.hh b/src/systems/ackermann_steering/AckermannSteering.hh index 5e1b23bb54..0eb9e2bda5 100644 --- a/src/systems/ackermann_steering/AckermannSteering.hh +++ b/src/systems/ackermann_steering/AckermannSteering.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_ACKERMANNSTEERING_HH_ -#define IGNITION_GAZEBO_SYSTEMS_ACKERMANNSTEERING_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_ACKERMANNSTEERING_HH_ +#define GZ_GAZEBO_SYSTEMS_ACKERMANNSTEERING_HH_ #include -#include +#include namespace ignition { @@ -136,8 +136,8 @@ namespace systems // Documentation inherited public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; // Documentation inherited public: void PostUpdate( diff --git a/src/systems/air_pressure/AirPressure.cc b/src/systems/air_pressure/AirPressure.cc index 4346cf1f1b..6e47bcd7bf 100644 --- a/src/systems/air_pressure/AirPressure.cc +++ b/src/systems/air_pressure/AirPressure.cc @@ -17,38 +17,38 @@ #include "AirPressure.hh" -#include +#include #include #include #include #include -#include +#include -#include +#include #include -#include +#include -#include -#include +#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; +using namespace gz; +using namespace gz::sim; using namespace systems; /// \brief Private AirPressure data class. -class ignition::gazebo::systems::AirPressurePrivate +class gz::sim::systems::AirPressurePrivate { /// \brief A map of air pressure entity to its sensor public: std::unordered_map -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/altimeter/Altimeter.cc b/src/systems/altimeter/Altimeter.cc index 1a143e0d04..c4134a4f95 100644 --- a/src/systems/altimeter/Altimeter.cc +++ b/src/systems/altimeter/Altimeter.cc @@ -17,40 +17,40 @@ #include "Altimeter.hh" -#include +#include #include #include #include #include -#include -#include +#include +#include #include -#include -#include +#include +#include -#include -#include +#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; +using namespace gz; +using namespace gz::sim; using namespace systems; /// \brief Private Altimeter data class. -class ignition::gazebo::systems::AltimeterPrivate +class gz::sim::systems::AltimeterPrivate { /// \brief A map of altimeter entity to its sensor public: std::unordered_map -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/apply_joint_force/ApplyJointForce.cc b/src/systems/apply_joint_force/ApplyJointForce.cc index 58e136d540..036cd8d0cb 100644 --- a/src/systems/apply_joint_force/ApplyJointForce.cc +++ b/src/systems/apply_joint_force/ApplyJointForce.cc @@ -19,18 +19,18 @@ #include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/components/JointForceCmd.hh" -#include "ignition/gazebo/Model.hh" +#include "gz/sim/components/JointForceCmd.hh" +#include "gz/sim/Model.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; -class ignition::gazebo::systems::ApplyJointForcePrivate +class gz::sim::systems::ApplyJointForcePrivate { /// \brief Callback for joint force subscription /// \param[in] _msg Joint force message @@ -160,5 +160,9 @@ IGNITION_ADD_PLUGIN(ApplyJointForce, ApplyJointForce::ISystemConfigure, ApplyJointForce::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(ApplyJointForce, + "gz::sim::systems::ApplyJointForce") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(ApplyJointForce, "ignition::gazebo::systems::ApplyJointForce") diff --git a/src/systems/apply_joint_force/ApplyJointForce.hh b/src/systems/apply_joint_force/ApplyJointForce.hh index 10dfabf196..9074af941e 100644 --- a/src/systems/apply_joint_force/ApplyJointForce.hh +++ b/src/systems/apply_joint_force/ApplyJointForce.hh @@ -14,10 +14,10 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_APPLYJOINTFORCE_HH_ -#define IGNITION_GAZEBO_SYSTEMS_APPLYJOINTFORCE_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_APPLYJOINTFORCE_HH_ +#define GZ_GAZEBO_SYSTEMS_APPLYJOINTFORCE_HH_ -#include +#include #include namespace ignition @@ -51,8 +51,8 @@ namespace systems // Documentation inherited public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; /// \brief Private data pointer private: std::unique_ptr dataPtr; diff --git a/src/systems/apply_link_wrench/ApplyLinkWrench.cc b/src/systems/apply_link_wrench/ApplyLinkWrench.cc index a0fa27b5fe..7ca6a3bc6c 100644 --- a/src/systems/apply_link_wrench/ApplyLinkWrench.cc +++ b/src/systems/apply_link_wrench/ApplyLinkWrench.cc @@ -14,34 +14,34 @@ * limitations under the License. * */ -#include +#include #include #include #include #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/World.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/World.hh" +#include "gz/sim/Util.hh" #include "ApplyLinkWrench.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; -class ignition::gazebo::systems::ApplyLinkWrenchPrivate +class gz::sim::systems::ApplyLinkWrenchPrivate { /// \brief Callback for wrench subscription /// \param[in] _msg Wrench message @@ -356,5 +356,9 @@ IGNITION_ADD_PLUGIN(ApplyLinkWrench, ApplyLinkWrench::ISystemConfigure, ApplyLinkWrench::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(ApplyLinkWrench, + "gz::sim::systems::ApplyLinkWrench") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(ApplyLinkWrench, "ignition::gazebo::systems::ApplyLinkWrench") diff --git a/src/systems/apply_link_wrench/ApplyLinkWrench.hh b/src/systems/apply_link_wrench/ApplyLinkWrench.hh index fc56b0cb23..3e91a543f3 100644 --- a/src/systems/apply_link_wrench/ApplyLinkWrench.hh +++ b/src/systems/apply_link_wrench/ApplyLinkWrench.hh @@ -17,7 +17,7 @@ #ifndef GZ_SIM_SYSTEMS_APPLYLINKWRENCH_HH_ #define GZ_SIM_SYSTEMS_APPLYLINKWRENCH_HH_ -#include +#include #include namespace ignition diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.cc b/src/systems/battery_plugin/LinearBatteryPlugin.cc index 0be91f91f5..e8944f54bb 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.cc +++ b/src/systems/battery_plugin/LinearBatteryPlugin.cc @@ -17,8 +17,8 @@ #include "LinearBatteryPlugin.hh" -#include -#include +#include +#include #include #include @@ -27,32 +27,32 @@ #include #include -#include -#include -#include +#include +#include +#include -#include -#include +#include +#include #include #include #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" - -using namespace ignition; -using namespace gazebo; +#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 gz; +using namespace gz::sim; using namespace systems; -class ignition::gazebo::systems::LinearBatteryPluginPrivate +class gz::sim::systems::LinearBatteryPluginPrivate { /// \brief Reset the plugin public: void Reset(); @@ -614,5 +614,9 @@ IGNITION_ADD_PLUGIN(LinearBatteryPlugin, LinearBatteryPlugin::ISystemUpdate, LinearBatteryPlugin::ISystemPostUpdate) +IGNITION_ADD_PLUGIN_ALIAS(LinearBatteryPlugin, + "gz::sim::systems::LinearBatteryPlugin") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(LinearBatteryPlugin, "ignition::gazebo::systems::LinearBatteryPlugin") diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.hh b/src/systems/battery_plugin/LinearBatteryPlugin.hh index a77440ed07..2b6c12ae47 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.hh +++ b/src/systems/battery_plugin/LinearBatteryPlugin.hh @@ -15,16 +15,16 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_LINEAR_BATTERY_PLUGIN_HH_ -#define IGNITION_GAZEBO_SYSTEMS_LINEAR_BATTERY_PLUGIN_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_LINEAR_BATTERY_PLUGIN_HH_ +#define GZ_GAZEBO_SYSTEMS_LINEAR_BATTERY_PLUGIN_HH_ #include #include #include -#include +#include -#include "ignition/gazebo/System.hh" +#include "gz/sim/System.hh" namespace ignition { @@ -79,8 +79,8 @@ namespace systems /// Documentation inherited public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; /// Documentation inherited public: void Update(const UpdateInfo &_info, diff --git a/src/systems/breadcrumbs/Breadcrumbs.cc b/src/systems/breadcrumbs/Breadcrumbs.cc index 60b0b976ef..a9326c02e2 100644 --- a/src/systems/breadcrumbs/Breadcrumbs.cc +++ b/src/systems/breadcrumbs/Breadcrumbs.cc @@ -17,34 +17,34 @@ #include "Breadcrumbs.hh" -#include +#include #include #include #include #include -#include +#include -#include -#include +#include +#include #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" - -using namespace ignition; -using namespace gazebo; +#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" + +using namespace gz; +using namespace gz::sim; using namespace systems; ////////////////////////////////////////////////// @@ -394,4 +394,7 @@ IGNITION_ADD_PLUGIN(Breadcrumbs, Breadcrumbs::ISystemConfigure, Breadcrumbs::ISystemPreUpdate) -IGNITION_ADD_PLUGIN_ALIAS(Breadcrumbs, "ignition::gazebo::systems::Breadcrumbs") +IGNITION_ADD_PLUGIN_ALIAS(Breadcrumbs, "gz::sim::systems::Breadcrumbs") + +// TODO(CH3): Deprecated, remove on version 8 +IGNITION_ADD_PLUGIN_ALIAS(Breadcrumbs, "igntion::gazebo::systems::Breadcrumbs") diff --git a/src/systems/breadcrumbs/Breadcrumbs.hh b/src/systems/breadcrumbs/Breadcrumbs.hh index a0bd9022d6..34c2faca0a 100644 --- a/src/systems/breadcrumbs/Breadcrumbs.hh +++ b/src/systems/breadcrumbs/Breadcrumbs.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_BREADCRUMBS_HH_ -#define IGNITION_GAZEBO_SYSTEMS_BREADCRUMBS_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_BREADCRUMBS_HH_ +#define GZ_GAZEBO_SYSTEMS_BREADCRUMBS_HH_ #include #include @@ -27,12 +27,12 @@ #include #include -#include -#include +#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 { @@ -97,8 +97,8 @@ namespace systems // Documentation inherited public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; /// \brief Callback to deployment topic private: void OnDeploy(const msgs::Empty &_msg); diff --git a/src/systems/buoyancy/Buoyancy.cc b/src/systems/buoyancy/Buoyancy.cc index 47b2bc0349..adbbdf6e15 100644 --- a/src/systems/buoyancy/Buoyancy.cc +++ b/src/systems/buoyancy/Buoyancy.cc @@ -14,45 +14,45 @@ * limitations under the License. * */ -#include +#include #include #include #include -#include -#include -#include +#include +#include +#include -#include +#include -#include -#include -#include +#include +#include +#include -#include +#include #include -#include "ignition/gazebo/components/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/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/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" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; -class ignition::gazebo::systems::BuoyancyPrivate +class gz::sim::systems::BuoyancyPrivate { /// \brief Get the fluid density based on a pose. This function can be /// used to adjust the fluid density based on the pose of an object in the @@ -270,5 +270,9 @@ IGNITION_ADD_PLUGIN(Buoyancy, Buoyancy::ISystemConfigure, Buoyancy::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(Buoyancy, + "gz::sim::systems::Buoyancy") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(Buoyancy, "ignition::gazebo::systems::Buoyancy") diff --git a/src/systems/buoyancy/Buoyancy.hh b/src/systems/buoyancy/Buoyancy.hh index 55d040cdb8..2c76c1ebb7 100644 --- a/src/systems/buoyancy/Buoyancy.hh +++ b/src/systems/buoyancy/Buoyancy.hh @@ -14,10 +14,10 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_BUOYANCY_HH_ -#define IGNITION_GAZEBO_SYSTEMS_BUOYANCY_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_BUOYANCY_HH_ +#define GZ_GAZEBO_SYSTEMS_BUOYANCY_HH_ -#include +#include #include namespace ignition @@ -76,8 +76,8 @@ namespace systems // Documentation inherited public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; /// \brief Private data pointer private: std::unique_ptr dataPtr; diff --git a/src/systems/camera_video_recorder/CameraVideoRecorder.cc b/src/systems/camera_video_recorder/CameraVideoRecorder.cc index 013a255a93..18d2b9ca0b 100644 --- a/src/systems/camera_video_recorder/CameraVideoRecorder.cc +++ b/src/systems/camera_video_recorder/CameraVideoRecorder.cc @@ -20,38 +20,38 @@ #include #include -#include -#include -#include -#include - -#include -#include -#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 +#include +#include +#include + +#include +#include +#include +#include + +#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" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; // Private data class. -class ignition::gazebo::systems::CameraVideoRecorderPrivate +class gz::sim::systems::CameraVideoRecorderPrivate { /// \brief Callback for the video recorder service public: bool OnRecordVideo(const msgs::VideoRecord &_msg, @@ -467,5 +467,9 @@ IGNITION_ADD_PLUGIN(CameraVideoRecorder, // Add plugin alias so that we can refer to the plugin without the version // namespace +IGNITION_ADD_PLUGIN_ALIAS(CameraVideoRecorder, + "gz::sim::systems::CameraVideoRecorder") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(CameraVideoRecorder, "ignition::gazebo::systems::CameraVideoRecorder") diff --git a/src/systems/camera_video_recorder/CameraVideoRecorder.hh b/src/systems/camera_video_recorder/CameraVideoRecorder.hh index c905301036..da15edbc5c 100644 --- a/src/systems/camera_video_recorder/CameraVideoRecorder.hh +++ b/src/systems/camera_video_recorder/CameraVideoRecorder.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_CAMERAVIDEORECORDER_SYSTEM_HH_ -#define IGNITION_GAZEBO_CAMERAVIDEORECORDER_SYSTEM_HH_ +#ifndef GZ_GAZEBO_CAMERAVIDEORECORDER_SYSTEM_HH_ +#define GZ_GAZEBO_CAMERAVIDEORECORDER_SYSTEM_HH_ #include -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/collada_world_exporter/ColladaWorldExporter.cc b/src/systems/collada_world_exporter/ColladaWorldExporter.cc index 50c2abf4c5..fff1f5337a 100644 --- a/src/systems/collada_world_exporter/ColladaWorldExporter.cc +++ b/src/systems/collada_world_exporter/ColladaWorldExporter.cc @@ -18,42 +18,42 @@ #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 "ColladaWorldExporter.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; -class ignition::gazebo::systems::ColladaWorldExporterPrivate +class gz::sim::systems::ColladaWorldExporterPrivate { // Default constructor public: ColladaWorldExporterPrivate() = default; @@ -92,7 +92,7 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate std::string name = _name->Data().empty() ? std::to_string(_entity) : _name->Data(); - math::Pose3d worldPose = gazebo::worldPose(_entity, _ecm); + math::Pose3d worldPose = gz::sim::worldPose(_entity, _ecm); common::MaterialPtr mat = std::make_shared(); auto material = _ecm.Component(_entity); @@ -262,5 +262,9 @@ IGNITION_ADD_PLUGIN(ColladaWorldExporter, System, ColladaWorldExporter::ISystemPostUpdate) +IGNITION_ADD_PLUGIN_ALIAS(ColladaWorldExporter, + "gz::sim::systems::ColladaWorldExporter") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(ColladaWorldExporter, "ignition::gazebo::systems::ColladaWorldExporter") diff --git a/src/systems/collada_world_exporter/ColladaWorldExporter.hh b/src/systems/collada_world_exporter/ColladaWorldExporter.hh index c31a175b0a..d9a32ce0b1 100644 --- a/src/systems/collada_world_exporter/ColladaWorldExporter.hh +++ b/src/systems/collada_world_exporter/ColladaWorldExporter.hh @@ -15,11 +15,11 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_COLLADAWORLDEXPORTER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_COLLADAWORLDEXPORTER_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_COLLADAWORLDEXPORTER_HH_ +#define GZ_GAZEBO_SYSTEMS_COLLADAWORLDEXPORTER_HH_ #include -#include +#include namespace ignition { diff --git a/src/systems/contact/Contact.cc b/src/systems/contact/Contact.cc index ac5bf96914..4d85889ac5 100644 --- a/src/systems/contact/Contact.cc +++ b/src/systems/contact/Contact.cc @@ -17,33 +17,33 @@ #include "Contact.hh" -#include -#include +#include +#include #include #include #include #include -#include -#include +#include +#include #include -#include +#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; +using namespace gz; +using namespace gz::sim; using namespace systems; class ContactSensor @@ -81,7 +81,7 @@ class ContactSensor public: std::vector collisionEntities; }; -class ignition::gazebo::systems::ContactPrivate +class gz::sim::systems::ContactPrivate { /// \brief Create sensors that correspond to entities in the simulation /// \param[in] _ecm Mutable reference to ECM. @@ -299,5 +299,7 @@ IGNITION_ADD_PLUGIN(Contact, System, Contact::ISystemPostUpdate ) -IGNITION_ADD_PLUGIN_ALIAS(Contact, "ignition::gazebo::systems::Contact") +IGNITION_ADD_PLUGIN_ALIAS(Contact, "gz::sim::systems::Contact") +// TODO(CH3): Deprecated, remove on version 8 +IGNITION_ADD_PLUGIN_ALIAS(Contact, "ignition::gazebo::systems::Contact") diff --git a/src/systems/contact/Contact.hh b/src/systems/contact/Contact.hh index 73e90b811e..5240666733 100644 --- a/src/systems/contact/Contact.hh +++ b/src/systems/contact/Contact.hh @@ -14,11 +14,11 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_CONTACT_HH_ -#define IGNITION_GAZEBO_SYSTEMS_CONTACT_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_CONTACT_HH_ +#define GZ_GAZEBO_SYSTEMS_CONTACT_HH_ #include -#include +#include namespace ignition { diff --git a/src/systems/detachable_joint/DetachableJoint.cc b/src/systems/detachable_joint/DetachableJoint.cc index aedaff0002..39825096c3 100644 --- a/src/systems/detachable_joint/DetachableJoint.cc +++ b/src/systems/detachable_joint/DetachableJoint.cc @@ -15,25 +15,25 @@ * */ -#include -#include +#include +#include -#include +#include #include -#include "ignition/gazebo/Model.hh" -#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 "gz/sim/Model.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 "DetachableJoint.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; ///////////////////////////////////////////////// @@ -186,5 +186,9 @@ IGNITION_ADD_PLUGIN(DetachableJoint, DetachableJoint::ISystemConfigure, DetachableJoint::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(DetachableJoint, + "gz::sim::systems::DetachableJoint") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(DetachableJoint, "ignition::gazebo::systems::DetachableJoint") diff --git a/src/systems/detachable_joint/DetachableJoint.hh b/src/systems/detachable_joint/DetachableJoint.hh index f52dc9d24a..57fdfca98b 100644 --- a/src/systems/detachable_joint/DetachableJoint.hh +++ b/src/systems/detachable_joint/DetachableJoint.hh @@ -15,17 +15,17 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_DETACHABLEJOINT_HH_ -#define IGNITION_GAZEBO_SYSTEMS_DETACHABLEJOINT_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_DETACHABLEJOINT_HH_ +#define GZ_GAZEBO_SYSTEMS_DETACHABLEJOINT_HH_ -#include +#include #include #include -#include +#include -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/System.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/System.hh" namespace ignition { @@ -70,8 +70,8 @@ namespace systems /// Documentation inherited public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) final; + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) final; /// \brief Callback for detach request topic private: void OnDetachRequest(const msgs::Empty &_msg); diff --git a/src/systems/diff_drive/DiffDrive.cc b/src/systems/diff_drive/DiffDrive.cc index d0935f5224..ae0878d663 100644 --- a/src/systems/diff_drive/DiffDrive.cc +++ b/src/systems/diff_drive/DiffDrive.cc @@ -17,28 +17,28 @@ #include "DiffDrive.hh" -#include +#include #include #include #include #include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/CanonicalLink.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/JointVelocityCmd.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" - -using namespace ignition; -using namespace gazebo; +#include +#include +#include +#include +#include +#include + +#include "gz/sim/components/CanonicalLink.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/JointVelocityCmd.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" + +using namespace gz; +using namespace gz::sim; using namespace systems; /// \brief Velocity command. @@ -53,7 +53,7 @@ struct Commands Commands() : lin(0.0), ang(0.0) {} }; -class ignition::gazebo::systems::DiffDrivePrivate +class gz::sim::systems::DiffDrivePrivate { /// \brief Callback for velocity subscription /// \param[in] _msg Velocity message @@ -561,4 +561,7 @@ IGNITION_ADD_PLUGIN(DiffDrive, DiffDrive::ISystemPreUpdate, DiffDrive::ISystemPostUpdate) +IGNITION_ADD_PLUGIN_ALIAS(DiffDrive, "gz::sim::systems::DiffDrive") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(DiffDrive, "ignition::gazebo::systems::DiffDrive") diff --git a/src/systems/diff_drive/DiffDrive.hh b/src/systems/diff_drive/DiffDrive.hh index 983970f8a7..6a02befe85 100644 --- a/src/systems/diff_drive/DiffDrive.hh +++ b/src/systems/diff_drive/DiffDrive.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_DIFFDRIVE_HH_ -#define IGNITION_GAZEBO_SYSTEMS_DIFFDRIVE_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_DIFFDRIVE_HH_ +#define GZ_GAZEBO_SYSTEMS_DIFFDRIVE_HH_ #include -#include +#include namespace ignition { @@ -97,8 +97,8 @@ namespace systems // Documentation inherited public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; // Documentation inherited public: void PostUpdate( diff --git a/src/systems/elevator/Elevator.cc b/src/systems/elevator/Elevator.cc index d78bd26bb4..ba0288902f 100644 --- a/src/systems/elevator/Elevator.cc +++ b/src/systems/elevator/Elevator.cc @@ -33,22 +33,22 @@ #include "utils/DoorTimer.hh" #include "utils/JointMonitor.hh" -#include -#include -#include - -#include -#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 +#include +#include + +#include +#include +#include + +#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 { @@ -103,7 +103,7 @@ class ElevatorPrivate : public ElevatorCommonPrivate /// then publishes the new state /// \param[in] _info Current simulation step info /// \param[in] _ecm Entity component manager - public: void UpdateState(const ignition::gazebo::UpdateInfo &_info, + public: void UpdateState(const gz::sim::UpdateInfo &_info, const EntityComponentManager &_ecm); /// \brief Callback for the door lidar scans @@ -394,7 +394,7 @@ void ElevatorPrivate::SetCabinMonitor( } ////////////////////////////////////////////////// -void ElevatorPrivate::UpdateState(const ignition::gazebo::UpdateInfo &_info, +void ElevatorPrivate::UpdateState(const gz::sim::UpdateInfo &_info, const EntityComponentManager &_ecm) { // Update state @@ -444,6 +444,9 @@ void ElevatorPrivate::OnCmdMsg(const msgs::Int32 &_msg) IGNITION_ADD_PLUGIN(Elevator, System, Elevator::ISystemConfigure, Elevator::ISystemPostUpdate) +IGNITION_ADD_PLUGIN_ALIAS(Elevator, "gz::sim::systems::Elevator") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(Elevator, "ignition::gazebo::systems::Elevator") } // namespace systems diff --git a/src/systems/elevator/Elevator.hh b/src/systems/elevator/Elevator.hh index cbb44da5b7..7fa8118377 100644 --- a/src/systems/elevator/Elevator.hh +++ b/src/systems/elevator/Elevator.hh @@ -20,12 +20,12 @@ * \date January 2021 */ -#ifndef IGNITION_GAZEBO_SYSTEMS_ELEVATOR_HH_ -#define IGNITION_GAZEBO_SYSTEMS_ELEVATOR_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_ELEVATOR_HH_ +#define GZ_GAZEBO_SYSTEMS_ELEVATOR_HH_ #include -#include +#include namespace ignition { @@ -131,4 +131,4 @@ class IGNITION_GAZEBO_VISIBLE Elevator : public System, } // namespace gazebo } // namespace ignition -#endif // IGNITION_GAZEBO_SYSTEMS_ELEVATOR_HH_ +#endif // GZ_GAZEBO_SYSTEMS_ELEVATOR_HH_ diff --git a/src/systems/elevator/ElevatorCommonPrivate.hh b/src/systems/elevator/ElevatorCommonPrivate.hh index ec787e3b91..aa066bec6b 100644 --- a/src/systems/elevator/ElevatorCommonPrivate.hh +++ b/src/systems/elevator/ElevatorCommonPrivate.hh @@ -20,14 +20,14 @@ * \date January 2021 */ -#ifndef IGNITION_GAZEBO_SYSTEMS_ELEVATOR_COMMON_PRIVATE_HH_ -#define IGNITION_GAZEBO_SYSTEMS_ELEVATOR_COMMON_PRIVATE_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_ELEVATOR_COMMON_PRIVATE_HH_ +#define GZ_GAZEBO_SYSTEMS_ELEVATOR_COMMON_PRIVATE_HH_ #include #include #include -#include +#include namespace ignition { @@ -96,4 +96,4 @@ class ElevatorCommonPrivate } // namespace gazebo } // namespace ignition -#endif // IGNITION_GAZEBO_SYSTEMS_ELEVATOR_COMMON_PRIVATE_HH_ +#endif // GZ_GAZEBO_SYSTEMS_ELEVATOR_COMMON_PRIVATE_HH_ diff --git a/src/systems/elevator/ElevatorStateMachine.hh b/src/systems/elevator/ElevatorStateMachine.hh index 6dfa7811f3..569cabe5ad 100644 --- a/src/systems/elevator/ElevatorStateMachine.hh +++ b/src/systems/elevator/ElevatorStateMachine.hh @@ -20,13 +20,13 @@ * \date January 2021 */ -#ifndef IGNITION_GAZEBO_SYSTEMS_ELEVATOR_STATE_MACHINE_HH_ -#define IGNITION_GAZEBO_SYSTEMS_ELEVATOR_STATE_MACHINE_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_ELEVATOR_STATE_MACHINE_HH_ +#define GZ_GAZEBO_SYSTEMS_ELEVATOR_STATE_MACHINE_HH_ #include -#include -#include +#include +#include #include "afsm/fsm.hpp" @@ -141,4 +141,4 @@ using ElevatorStateMachine = ::afsm::state_machine; #include "state_machine/ElevatorStateMachineImpl.hh" -#endif // IGNITION_GAZEBO_SYSTEMS_ELEVATOR_STATE_MACHINE_HH_ +#endif // GZ_GAZEBO_SYSTEMS_ELEVATOR_STATE_MACHINE_HH_ diff --git a/src/systems/elevator/state_machine/ElevatorStateMachineImpl.hh b/src/systems/elevator/state_machine/ElevatorStateMachineImpl.hh index a995a69ecd..9518317af8 100644 --- a/src/systems/elevator/state_machine/ElevatorStateMachineImpl.hh +++ b/src/systems/elevator/state_machine/ElevatorStateMachineImpl.hh @@ -25,7 +25,7 @@ #include #include -#include +#include #include "../ElevatorStateMachine.hh" diff --git a/src/systems/elevator/state_machine/StatesImpl.hh b/src/systems/elevator/state_machine/StatesImpl.hh index accd7f4a47..2c5d1abc0c 100644 --- a/src/systems/elevator/state_machine/StatesImpl.hh +++ b/src/systems/elevator/state_machine/StatesImpl.hh @@ -25,7 +25,7 @@ #include "../ElevatorStateMachine.hh" -#include +#include namespace ignition { diff --git a/src/systems/elevator/utils/DoorTimer.hh b/src/systems/elevator/utils/DoorTimer.hh index bcfeb18a2f..7cd9e03748 100644 --- a/src/systems/elevator/utils/DoorTimer.hh +++ b/src/systems/elevator/utils/DoorTimer.hh @@ -20,14 +20,14 @@ * \date January 2021 */ -#ifndef IGNITION_GAZEBO_SYSTEMS_DOOR_TIMER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_DOOR_TIMER_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_DOOR_TIMER_HH_ +#define GZ_GAZEBO_SYSTEMS_DOOR_TIMER_HH_ #include #include #include -#include +#include namespace ignition { @@ -77,4 +77,4 @@ class DoorTimer } // namespace gazebo } // namespace ignition -#endif // IGNITION_GAZEBO_SYSTEMS_DOOR_TIMER_HH_ +#endif // GZ_GAZEBO_SYSTEMS_DOOR_TIMER_HH_ diff --git a/src/systems/elevator/utils/JointMonitor.cc b/src/systems/elevator/utils/JointMonitor.cc index f2aa68a9a1..d55c270664 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 a42046b4ab..51e2e061cc 100644 --- a/src/systems/elevator/utils/JointMonitor.hh +++ b/src/systems/elevator/utils/JointMonitor.hh @@ -20,13 +20,13 @@ * \date January 2021 */ -#ifndef IGNITION_GAZEBO_SYSTEMS_JOINT_MONITOR_HH_ -#define IGNITION_GAZEBO_SYSTEMS_JOINT_MONITOR_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_JOINT_MONITOR_HH_ +#define GZ_GAZEBO_SYSTEMS_JOINT_MONITOR_HH_ #include #include -#include +#include namespace ignition { @@ -76,4 +76,4 @@ class JointMonitor } // namespace gazebo } // namespace ignition -#endif // IGNITION_GAZEBO_SYSTEMS_JOINT_MONITOR_HH_ +#endif // GZ_GAZEBO_SYSTEMS_JOINT_MONITOR_HH_ diff --git a/src/systems/imu/Imu.cc b/src/systems/imu/Imu.cc index ad62354f57..d596bb79bf 100644 --- a/src/systems/imu/Imu.cc +++ b/src/systems/imu/Imu.cc @@ -22,33 +22,33 @@ #include #include -#include +#include #include -#include - -#include -#include - -#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" - -using namespace ignition; -using namespace gazebo; +#include + +#include +#include + +#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 gz; +using namespace gz::sim; using namespace systems; /// \brief Private Imu data class. -class ignition::gazebo::systems::ImuPrivate +class gz::sim::systems::ImuPrivate { /// \brief A map of IMU entity to its IMU sensor. public: std::unordered_map -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/joint_controller/JointController.cc b/src/systems/joint_controller/JointController.cc index d7dc14fe67..291ea31ae2 100644 --- a/src/systems/joint_controller/JointController.cc +++ b/src/systems/joint_controller/JointController.cc @@ -17,25 +17,25 @@ #include "JointController.hh" -#include +#include #include -#include -#include -#include -#include +#include +#include +#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; +using namespace gz; +using namespace gz::sim; using namespace systems; -class ignition::gazebo::systems::JointControllerPrivate +class gz::sim::systems::JointControllerPrivate { /// \brief Callback for velocity subscription /// \param[in] _msg Velocity message @@ -246,5 +246,9 @@ IGNITION_ADD_PLUGIN(JointController, JointController::ISystemConfigure, JointController::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(JointController, + "gz::sim::systems::JointController") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(JointController, "ignition::gazebo::systems::JointController") diff --git a/src/systems/joint_controller/JointController.hh b/src/systems/joint_controller/JointController.hh index d3a1fb6587..104e74836d 100644 --- a/src/systems/joint_controller/JointController.hh +++ b/src/systems/joint_controller/JointController.hh @@ -14,10 +14,10 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_JOINTCONTROLLER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_JOINTCONTROLLER_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_JOINTCONTROLLER_HH_ +#define GZ_GAZEBO_SYSTEMS_JOINTCONTROLLER_HH_ -#include +#include #include namespace ignition @@ -93,8 +93,8 @@ namespace systems // Documentation inherited public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; /// \brief Private data pointer private: std::unique_ptr dataPtr; diff --git a/src/systems/joint_position_controller/JointPositionController.cc b/src/systems/joint_position_controller/JointPositionController.cc index d43b44e6e2..27c67c6dc1 100644 --- a/src/systems/joint_position_controller/JointPositionController.cc +++ b/src/systems/joint_position_controller/JointPositionController.cc @@ -17,25 +17,25 @@ #include "JointPositionController.hh" -#include +#include #include #include -#include -#include -#include -#include +#include +#include +#include +#include -#include "ignition/gazebo/components/JointForceCmd.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/Model.hh" +#include "gz/sim/components/JointForceCmd.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/Model.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; -class ignition::gazebo::systems::JointPositionControllerPrivate +class gz::sim::systems::JointPositionControllerPrivate { /// \brief Callback for position subscription /// \param[in] _msg Position message @@ -273,5 +273,9 @@ IGNITION_ADD_PLUGIN(JointPositionController, JointPositionController::ISystemConfigure, JointPositionController::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(JointPositionController, + "gz::sim::systems::JointPositionController") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(JointPositionController, "ignition::gazebo::systems::JointPositionController") diff --git a/src/systems/joint_position_controller/JointPositionController.hh b/src/systems/joint_position_controller/JointPositionController.hh index f1bd6765ed..67909d1fa8 100644 --- a/src/systems/joint_position_controller/JointPositionController.hh +++ b/src/systems/joint_position_controller/JointPositionController.hh @@ -14,11 +14,11 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_JOINTPOSITIONCONTROLLER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_JOINTPOSITIONCONTROLLER_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_JOINTPOSITIONCONTROLLER_HH_ +#define GZ_GAZEBO_SYSTEMS_JOINTPOSITIONCONTROLLER_HH_ #include -#include +#include namespace ignition { @@ -38,7 +38,7 @@ namespace systems /// The topic name is /// "/model//joint///cmd_pos" /// - /// This topic accepts ignition::msgs::Double values representing the target + /// This topic accepts gz::msgs::Double values representing the target /// position. /// /// ## System Parameters @@ -90,8 +90,8 @@ namespace systems // Documentation inherited public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; /// \brief Private data pointer private: std::unique_ptr dataPtr; diff --git a/src/systems/joint_state_publisher/JointStatePublisher.cc b/src/systems/joint_state_publisher/JointStatePublisher.cc index 65991f1933..884e086120 100644 --- a/src/systems/joint_state_publisher/JointStatePublisher.cc +++ b/src/systems/joint_state_publisher/JointStatePublisher.cc @@ -17,26 +17,26 @@ #include "JointStatePublisher.hh" -#include +#include #include #include -#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" - -using namespace ignition; -using namespace gazebo; +#include + +#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" + +using namespace gz; +using namespace gz::sim; using namespace systems; ////////////////////////////////////////////////// @@ -291,5 +291,9 @@ IGNITION_ADD_PLUGIN(JointStatePublisher, JointStatePublisher::ISystemConfigure, JointStatePublisher::ISystemPostUpdate) +IGNITION_ADD_PLUGIN_ALIAS(JointStatePublisher, + "gz::sim::systems::JointStatePublisher") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(JointStatePublisher, "ignition::gazebo::systems::JointStatePublisher") diff --git a/src/systems/joint_state_publisher/JointStatePublisher.hh b/src/systems/joint_state_publisher/JointStatePublisher.hh index 352137edae..c36ed1c82a 100644 --- a/src/systems/joint_state_publisher/JointStatePublisher.hh +++ b/src/systems/joint_state_publisher/JointStatePublisher.hh @@ -15,14 +15,14 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_STATE_PUBLISHER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_STATE_PUBLISHER_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_STATE_PUBLISHER_HH_ +#define GZ_GAZEBO_SYSTEMS_STATE_PUBLISHER_HH_ #include #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -33,7 +33,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { namespace systems { /// \brief The JointStatePub system publishes state information for - /// a model. The published message type is ignition::msgs::Model, and the + /// a model. The published message type is gz::msgs::Model, and the /// publication topic is "/world//model//state". /// /// By default the JointStatePublisher will publish all joints for @@ -69,7 +69,7 @@ namespace systems /// \param[in] _ecm The EntityComponentManager. /// \param[in] _joint The joint entity to create component for. private: void CreateComponents(EntityComponentManager &_ecm, - gazebo::Entity _joint); + gz::sim::Entity _joint); /// \brief The model private: Model model; diff --git a/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.cc b/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.cc index 962c53351c..de28a21d03 100644 --- a/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.cc +++ b/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.cc @@ -16,34 +16,34 @@ */ #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 "KineticEnergyMonitor.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; /// \brief Private data class -class ignition::gazebo::systems::KineticEnergyMonitorPrivate +class gz::sim::systems::KineticEnergyMonitorPrivate { /// \brief Link of the model. public: Entity linkEntity; @@ -167,5 +167,9 @@ IGNITION_ADD_PLUGIN(KineticEnergyMonitor, System, KineticEnergyMonitor::ISystemPostUpdate ) +IGNITION_ADD_PLUGIN_ALIAS(KineticEnergyMonitor, + "gz::sim::systems::KineticEnergyMonitor") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(KineticEnergyMonitor, "ignition::gazebo::systems::KineticEnergyMonitor") diff --git a/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.hh b/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.hh index de037608bd..962bbfbc07 100644 --- a/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.hh +++ b/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.hh @@ -15,13 +15,13 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_KINETIC_ENERGY_MONITOR_HH_ -#define IGNITION_GAZEBO_SYSTEMS_KINETIC_ENERGY_MONITOR_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_KINETIC_ENERGY_MONITOR_HH_ +#define GZ_GAZEBO_SYSTEMS_KINETIC_ENERGY_MONITOR_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -91,7 +91,7 @@ namespace systems + name="gz::sim::systems::KineticEnergyMonitor"> sphere_link 100 diff --git a/src/systems/lift_drag/LiftDrag.cc b/src/systems/lift_drag/LiftDrag.cc index cccdfff3fb..bfeb37551e 100644 --- a/src/systems/lift_drag/LiftDrag.cc +++ b/src/systems/lift_drag/LiftDrag.cc @@ -21,30 +21,30 @@ #include #include -#include -#include -#include +#include +#include +#include #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/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" - -using namespace ignition; -using namespace gazebo; +#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/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 gz; +using namespace gz::sim; using namespace systems; -class ignition::gazebo::systems::LiftDragPrivate +class gz::sim::systems::LiftDragPrivate { // Initialize the system public: void Load(const EntityComponentManager &_ecm, @@ -527,4 +527,7 @@ IGNITION_ADD_PLUGIN(LiftDrag, LiftDrag::ISystemConfigure, LiftDrag::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(LiftDrag, "gz::sim::systems::LiftDrag") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(LiftDrag, "ignition::gazebo::systems::LiftDrag") diff --git a/src/systems/lift_drag/LiftDrag.hh b/src/systems/lift_drag/LiftDrag.hh index c03eab6f15..a71191898a 100644 --- a/src/systems/lift_drag/LiftDrag.hh +++ b/src/systems/lift_drag/LiftDrag.hh @@ -15,11 +15,11 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_LIFT_DRAG_HH_ -#define IGNITION_GAZEBO_SYSTEMS_LIFT_DRAG_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_LIFT_DRAG_HH_ +#define GZ_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 811e059f3c..813417051f 100644 --- a/src/systems/log/LogPlayback.cc +++ b/src/systems/log/LogPlayback.cc @@ -17,43 +17,43 @@ #include "LogPlayback.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 +#include +#include #include #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/Pose.hh" -#include "ignition/gazebo/components/World.hh" - -using namespace ignition; -using namespace gazebo; +#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/Pose.hh" +#include "gz/sim/components/World.hh" + +using namespace gz; +using namespace gz::sim; using namespace systems; /// \brief Private LogPlayback data class. -class ignition::gazebo::systems::LogPlaybackPrivate +class gz::sim::systems::LogPlaybackPrivate { /// \brief Extract model resource files and state file from compression. /// \return True if extraction was successful. @@ -660,5 +660,9 @@ IGNITION_ADD_PLUGIN(LogPlayback, LogPlayback::ISystemConfigure, LogPlayback::ISystemUpdate) +IGNITION_ADD_PLUGIN_ALIAS(LogPlayback, + "gz::sim::systems::LogPlayback") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(LogPlayback, "ignition::gazebo::systems::LogPlayback") diff --git a/src/systems/log/LogPlayback.hh b/src/systems/log/LogPlayback.hh index 07086f63c9..954486963e 100644 --- a/src/systems/log/LogPlayback.hh +++ b/src/systems/log/LogPlayback.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_LOGPLAYBACK_HH_ -#define IGNITION_GAZEBO_SYSTEMS_LOGPLAYBACK_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_LOGPLAYBACK_HH_ +#define GZ_GAZEBO_SYSTEMS_LOGPLAYBACK_HH_ #include -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/log/LogRecord.cc b/src/systems/log/LogRecord.cc index 57ac7e7c3d..8b3b3fee87 100644 --- a/src/systems/log/LogRecord.cc +++ b/src/systems/log/LogRecord.cc @@ -18,7 +18,7 @@ #include "LogRecord.hh" #include -#include +#include #include #include @@ -26,17 +26,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 #include @@ -48,24 +48,24 @@ #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/Pose.hh" -#include "ignition/gazebo/components/SourceFilePath.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/World.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/Pose.hh" +#include "gz/sim/components/SourceFilePath.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Util.hh" -using namespace ignition; +using namespace gz; using namespace ignition::gazebo::systems; // Private data class. -class ignition::gazebo::systems::LogRecordPrivate +class gz::sim::systems::LogRecordPrivate { /// \brief Start recording /// \param[in] _logPath Path to record to. @@ -695,10 +695,14 @@ void LogRecord::PostUpdate(const UpdateInfo &_info, } IGNITION_ADD_PLUGIN(LogRecord, - gazebo::System, + gz::sim::System, LogRecord::ISystemConfigure, LogRecord::ISystemPreUpdate, LogRecord::ISystemPostUpdate) +IGNITION_ADD_PLUGIN_ALIAS(LogRecord, + "gz::sim::systems::LogRecord") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(LogRecord, "ignition::gazebo::systems::LogRecord") diff --git a/src/systems/log/LogRecord.hh b/src/systems/log/LogRecord.hh index f03edd4e35..5c45a83a10 100644 --- a/src/systems/log/LogRecord.hh +++ b/src/systems/log/LogRecord.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_LOGRECORD_HH_ -#define IGNITION_GAZEBO_SYSTEMS_LOGRECORD_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_LOGRECORD_HH_ +#define GZ_GAZEBO_SYSTEMS_LOGRECORD_HH_ #include -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/log_video_recorder/LogVideoRecorder.cc b/src/systems/log_video_recorder/LogVideoRecorder.cc index 8fe62313cd..3577000819 100644 --- a/src/systems/log_video_recorder/LogVideoRecorder.cc +++ b/src/systems/log_video_recorder/LogVideoRecorder.cc @@ -17,35 +17,35 @@ #include "LogVideoRecorder.hh" -#include -#include +#include +#include #include #include #include -#include -#include -#include -#include +#include +#include +#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; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; // Private data class. -class ignition::gazebo::systems::LogVideoRecorderPrivate +class gz::sim::systems::LogVideoRecorderPrivate { /// \brief Rewind the log public: void Rewind(); @@ -451,5 +451,9 @@ IGNITION_ADD_PLUGIN(LogVideoRecorder, // Add plugin alias so that we can refer to the plugin without the version // namespace +IGNITION_ADD_PLUGIN_ALIAS(LogVideoRecorder, + "gz::sim::systems::LogVideoRecorder") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(LogVideoRecorder, "ignition::gazebo::systems::LogVideoRecorder") diff --git a/src/systems/log_video_recorder/LogVideoRecorder.hh b/src/systems/log_video_recorder/LogVideoRecorder.hh index 29d61208d7..97f9372233 100644 --- a/src/systems/log_video_recorder/LogVideoRecorder.hh +++ b/src/systems/log_video_recorder/LogVideoRecorder.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_LOGVIDEORECORDER_SYSTEM_HH_ -#define IGNITION_GAZEBO_LOGVIDEORECORDER_SYSTEM_HH_ +#ifndef GZ_GAZEBO_LOGVIDEORECORDER_SYSTEM_HH_ +#define GZ_GAZEBO_LOGVIDEORECORDER_SYSTEM_HH_ #include #include -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudio.cc b/src/systems/logical_audio_sensor_plugin/LogicalAudio.cc index 3568bd3c4a..569c22de06 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudio.cc +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudio.cc @@ -58,8 +58,8 @@ namespace logical_audio double _sourceEmissionVolume, double _innerRadius, double _falloffDistance, - const ignition::math::Pose3d &_sourcePose, - const ignition::math::Pose3d &_targetPose) + const gz::math::Pose3d &_sourcePose, + const gz::math::Pose3d &_targetPose) { if (!_playing) return 0.0; diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudio.hh b/src/systems/logical_audio_sensor_plugin/LogicalAudio.hh index 4835cd6b88..d5a3734233 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudio.hh +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudio.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_LOGICALAUDIO_HH_ -#define IGNITION_GAZEBO_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_LOGICALAUDIO_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_LOGICALAUDIO_HH_ +#define GZ_GAZEBO_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_LOGICALAUDIO_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -67,8 +67,8 @@ namespace logical_audio double _sourceEmissionVolume, double _innerRadius, double _falloffDistance, - const ignition::math::Pose3d &_sourcePose, - const ignition::math::Pose3d &_targetPose); + const gz::math::Pose3d &_sourcePose, + const gz::math::Pose3d &_targetPose); /// \brief Set the attenuation function that matches the defined string. /// The string is not case sensitive, and must match the spelling diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc index 8844dd2773..5ed52f05e2 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc @@ -25,25 +25,25 @@ #include #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include "LogicalAudio.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; -class ignition::gazebo::systems::LogicalAudioSensorPluginPrivate +class gz::sim::systems::LogicalAudioSensorPluginPrivate { /// \brief Creates an audio source with attributes specified in an SDF file. /// \param[in] _elem A pointer to the source element in the SDF file. @@ -524,5 +524,9 @@ IGNITION_ADD_PLUGIN(LogicalAudioSensorPlugin, LogicalAudioSensorPlugin::ISystemPreUpdate, LogicalAudioSensorPlugin::ISystemPostUpdate) +IGNITION_ADD_PLUGIN_ALIAS(LogicalAudioSensorPlugin, + "gz::sim::systems::LogicalAudioSensorPlugin") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(LogicalAudioSensorPlugin, "ignition::gazebo::systems::LogicalAudioSensorPlugin") diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh index 3dcaeb67a2..7ac34c7aa9 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_HH_ -#define IGNITION_GAZEBO_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_HH_ +#define GZ_GAZEBO_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_HH_ #include -#include +#include namespace ignition { @@ -115,7 +115,7 @@ namespace systems /// Sources can be started and stopped via Ignition service calls. /// If a source is successfully created, the following services will be /// created for the source (`` is the scoped name for the source - see - /// ignition::gazebo::scopedName for more details - and `` is the value + /// gz::sim::scopedName for more details - and `` is the value /// specified in the source's `` tag from the SDF): /// * `/source_/play` /// * Starts playing the source with the specified ID. @@ -127,7 +127,7 @@ namespace systems /// Microphone detection information can be retrieved via Ignition topics. /// Whenever a microphone detects a source, it publishes a message to the /// `/mic_/detection` topic, where `` is the scoped name - /// for the microphone - see ignition::gazebo::scopedName for more details - + /// for the microphone - see gz::sim::scopedName for more details - /// and `` is the value specified in the microphone's `` tag from the /// SDF. class LogicalAudioSensorPlugin : @@ -149,8 +149,8 @@ namespace systems EventManager &_eventMgr) override; // Documentation inherited - public: void PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + public: void PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; /// Documentation inherited public: void PostUpdate(const UpdateInfo &_info, diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudio_TEST.cc b/src/systems/logical_audio_sensor_plugin/LogicalAudio_TEST.cc index b45d7d45c8..1c7a637235 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudio_TEST.cc +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudio_TEST.cc @@ -19,7 +19,7 @@ #include "LogicalAudio.hh" -namespace logical_audio = ignition::gazebo::logical_audio; +namespace logical_audio = gz::sim::logical_audio; using AttenuationFunction = logical_audio::AttenuationFunction; using AttenuationShape = logical_audio::AttenuationShape; diff --git a/src/systems/logical_camera/LogicalCamera.cc b/src/systems/logical_camera/LogicalCamera.cc index fbed671f66..37b3e599cf 100644 --- a/src/systems/logical_camera/LogicalCamera.cc +++ b/src/systems/logical_camera/LogicalCamera.cc @@ -17,7 +17,7 @@ #include "LogicalCamera.hh" -#include +#include #include #include @@ -25,33 +25,33 @@ #include #include -#include -#include +#include +#include #include -#include -#include +#include +#include -#include -#include +#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; +using namespace gz; +using namespace gz::sim; using namespace systems; /// \brief Private LogicalCamera data class. -class ignition::gazebo::systems::LogicalCameraPrivate +class gz::sim::systems::LogicalCameraPrivate { /// \brief A map of logicalCamera entities public: std::unordered_map -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/magnetometer/Magnetometer.cc b/src/systems/magnetometer/Magnetometer.cc index 02b1155a6b..be72521884 100644 --- a/src/systems/magnetometer/Magnetometer.cc +++ b/src/systems/magnetometer/Magnetometer.cc @@ -22,33 +22,33 @@ #include #include -#include +#include #include -#include +#include -#include +#include -#include -#include +#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; +using namespace gz; +using namespace gz::sim; using namespace systems; /// \brief Private Magnetometer data class. -class ignition::gazebo::systems::MagnetometerPrivate +class gz::sim::systems::MagnetometerPrivate { /// \brief A map of magnetometer entity to its sensor. public: std::unordered_map -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/multicopter_control/Common.cc b/src/systems/multicopter_control/Common.cc index 7b1960f783..55439dbda4 100644 --- a/src/systems/multicopter_control/Common.cc +++ b/src/systems/multicopter_control/Common.cc @@ -19,18 +19,18 @@ #include -#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 +#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 d0e41f7689..ec4ad21787 100644 --- a/src/systems/multicopter_control/Common.hh +++ b/src/systems/multicopter_control/Common.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_COMMON_HH_ -#define IGNITION_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_COMMON_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_COMMON_HH_ +#define GZ_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_COMMON_HH_ #include #include @@ -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 d0d48ea4b7..5c8694fb9e 100644 --- a/src/systems/multicopter_control/LeeVelocityController.hh +++ b/src/systems/multicopter_control/LeeVelocityController.hh @@ -15,12 +15,12 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_MULTICOPTER_CONTROL_LEEVELOCITYCONTROLLER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_MULTICOPTER_CONTROL_LEEVELOCITYCONTROLLER_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_MULTICOPTER_CONTROL_LEEVELOCITYCONTROLLER_HH_ +#define GZ_GAZEBO_SYSTEMS_MULTICOPTER_CONTROL_LEEVELOCITYCONTROLLER_HH_ #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 e82a327321..83ccad5115 100644 --- a/src/systems/multicopter_control/MulticopterVelocityControl.cc +++ b/src/systems/multicopter_control/MulticopterVelocityControl.cc @@ -15,37 +15,37 @@ * */ -#include -#include +#include +#include #include -#include +#include -#include -#include +#include +#include -#include -#include +#include +#include -#include +#include #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" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; using namespace multicopter_control; @@ -432,6 +432,11 @@ IGNITION_ADD_PLUGIN(MulticopterVelocityControl, MulticopterVelocityControl::ISystemConfigure, MulticopterVelocityControl::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS( + MulticopterVelocityControl, + "gz::sim::systems::MulticopterVelocityControl") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS( MulticopterVelocityControl, "ignition::gazebo::systems::MulticopterVelocityControl") diff --git a/src/systems/multicopter_control/MulticopterVelocityControl.hh b/src/systems/multicopter_control/MulticopterVelocityControl.hh index 0fe9d7ece6..9bc87e4233 100644 --- a/src/systems/multicopter_control/MulticopterVelocityControl.hh +++ b/src/systems/multicopter_control/MulticopterVelocityControl.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_HH_ -#define IGNITION_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_HH_ +#define GZ_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_HH_ #include #include #include -#include +#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" @@ -162,8 +162,8 @@ namespace systems // Documentation inherited public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; /// \brief Callback for twist messages /// The controller waits for the first twist message before publishing any @@ -182,7 +182,7 @@ namespace systems /// \param[in] _ecm Mutable reference to the EntityComponentManager /// \param[in] _vels Rotor velocities to be published private: void PublishRotorVelocities( - ignition::gazebo::EntityComponentManager &_ecm, + gz::sim::EntityComponentManager &_ecm, const Eigen::VectorXd &_vels); /// \brief Model interface diff --git a/src/systems/multicopter_control/Parameters.hh b/src/systems/multicopter_control/Parameters.hh index 149ab9d7ca..0a8a65ccc3 100644 --- a/src/systems/multicopter_control/Parameters.hh +++ b/src/systems/multicopter_control/Parameters.hh @@ -15,13 +15,13 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_PARAMETERS_HH_ -#define IGNITION_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_PARAMETERS_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_PARAMETERS_HH_ +#define GZ_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_PARAMETERS_HH_ #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 40c0bda6d5..6722f9a305 100644 --- a/src/systems/multicopter_motor_model/MulticopterMotorModel.cc +++ b/src/systems/multicopter_motor_model/MulticopterMotorModel.cc @@ -26,29 +26,29 @@ #include #include -#include +#include -#include -#include +#include +#include -#include -#include -#include +#include +#include +#include #include #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. @@ -97,8 +97,8 @@ class FirstOrderFilter { T previousState; }; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; /// \brief Constants for specifying clockwise (kCw) and counter-clockwise (kCcw) @@ -115,7 +115,7 @@ enum class MotorType { kForce }; -class ignition::gazebo::systems::MulticopterMotorModelPrivate +class gz::sim::systems::MulticopterMotorModelPrivate { /// \brief Callback for actuator commands. public: void OnActuatorMsg(const msgs::Actuators &_msg); @@ -669,5 +669,9 @@ IGNITION_ADD_PLUGIN(MulticopterMotorModel, MulticopterMotorModel::ISystemConfigure, MulticopterMotorModel::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(MulticopterMotorModel, + "gz::sim::systems::MulticopterMotorModel") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(MulticopterMotorModel, "ignition::gazebo::systems::MulticopterMotorModel") diff --git a/src/systems/multicopter_motor_model/MulticopterMotorModel.hh b/src/systems/multicopter_motor_model/MulticopterMotorModel.hh index 1c736bf505..acb7c93ca3 100644 --- a/src/systems/multicopter_motor_model/MulticopterMotorModel.hh +++ b/src/systems/multicopter_motor_model/MulticopterMotorModel.hh @@ -14,10 +14,10 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_MULTICOPTERMOTORMODEL_HH_ -#define IGNITION_GAZEBO_SYSTEMS_MULTICOPTERMOTORMODEL_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_MULTICOPTERMOTORMODEL_HH_ +#define GZ_GAZEBO_SYSTEMS_MULTICOPTERMOTORMODEL_HH_ -#include +#include #include namespace ignition @@ -52,8 +52,8 @@ namespace systems // Documentation inherited public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; /// \brief Private data pointer private: std::unique_ptr dataPtr; diff --git a/src/systems/performer_detector/PerformerDetector.cc b/src/systems/performer_detector/PerformerDetector.cc index 2c9ccd89c7..ca42dce039 100644 --- a/src/systems/performer_detector/PerformerDetector.cc +++ b/src/systems/performer_detector/PerformerDetector.cc @@ -15,30 +15,30 @@ * */ -#include +#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include #include -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" -#include "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" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; ///////////////////////////////////////////////// @@ -259,5 +259,9 @@ IGNITION_ADD_PLUGIN(PerformerDetector, PerformerDetector::ISystemConfigure, PerformerDetector::ISystemPostUpdate) +IGNITION_ADD_PLUGIN_ALIAS(PerformerDetector, + "gz::sim::systems::PerformerDetector") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(PerformerDetector, "ignition::gazebo::systems::PerformerDetector") diff --git a/src/systems/performer_detector/PerformerDetector.hh b/src/systems/performer_detector/PerformerDetector.hh index 151ad9727e..e70cf48793 100644 --- a/src/systems/performer_detector/PerformerDetector.hh +++ b/src/systems/performer_detector/PerformerDetector.hh @@ -15,18 +15,18 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_PERFORMERDETECTOR_HH_ -#define IGNITION_GAZEBO_SYSTEMS_PERFORMERDETECTOR_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_PERFORMERDETECTOR_HH_ +#define GZ_GAZEBO_SYSTEMS_PERFORMERDETECTOR_HH_ #include #include #include #include -#include +#include -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/System.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/System.hh" namespace ignition { @@ -40,9 +40,9 @@ namespace systems /// or leaves a specified region. /// /// A performer is detected when a performer's volume, which is - /// represented by an ignition::math::AxisAlignedBox, intersects with the + /// represented by an gz::math::AxisAlignedBox, intersects with the /// PerformerDetector's region, which is also represented by an - /// ignition::math::AxisAlignedBox. When a performer is detected, the system + /// gz::math::AxisAlignedBox. When a performer is detected, the system /// publishes an ignition.msgs.Pose message with the pose of the detected /// performer with respect to the model containing the PerformerDetector. The /// name and id fields of the Pose message will be set to the name and the @@ -93,8 +93,8 @@ namespace systems /// Documentation inherited public: void PostUpdate( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) final; + const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) final; /// \brief Check if the entity has already been detected /// \param [in] _entity The entity to test diff --git a/src/systems/physics/EntityFeatureMap.hh b/src/systems/physics/EntityFeatureMap.hh index e38375169e..0e0686333d 100644 --- a/src/systems/physics/EntityFeatureMap.hh +++ b/src/systems/physics/EntityFeatureMap.hh @@ -15,19 +15,19 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_PHYSICS_ENTITY_FEATURE_MAP_HH_ -#define IGNITION_GAZEBO_SYSTEMS_PHYSICS_ENTITY_FEATURE_MAP_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_PHYSICS_ENTITY_FEATURE_MAP_HH_ +#define GZ_GAZEBO_SYSTEMS_PHYSICS_ENTITY_FEATURE_MAP_HH_ #include #include #include -#include -#include -#include -#include +#include +#include +#include +#include -#include "ignition/gazebo/Entity.hh" +#include "gz/sim/Entity.hh" namespace ignition::gazebo { @@ -94,7 +94,7 @@ namespace systems::physics_system /// requested feature. public: template PhysicsEntityPtr - EntityCast(gazebo::Entity _entity) const + EntityCast(gz::sim::Entity _entity) const { // Using constexpr to limit compiler error message to the static_assert // cppcheck-suppress syntaxError diff --git a/src/systems/physics/EntityFeatureMap_TEST.cc b/src/systems/physics/EntityFeatureMap_TEST.cc index 258dc19ac0..1e09ccbc64 100644 --- a/src/systems/physics/EntityFeatureMap_TEST.cc +++ b/src/systems/physics/EntityFeatureMap_TEST.cc @@ -19,21 +19,21 @@ #include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include "../../../test/helpers/EnvTestFixture.hh" -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/EntityComponentManager.hh" -using namespace ignition; +using namespace gz; using namespace ignition::gazebo::systems::physics_system; struct MinimumFeatureList @@ -110,13 +110,13 @@ TEST_F(EntityFeatureMapFixture, AddCastRemoveEntity) // Making these entities different from 1 and 2 ensures that the implicit // conversion in ign-physics between EntityPtr and std::size_t doesn't cause // false positive tests - gazebo::Entity gazeboWorld1Entity = 123; - gazebo::Entity gazeboWorld2Entity = 456; + gz::sim::Entity gazeboWorld1Entity = 123; + gz::sim::Entity gazeboWorld2Entity = 456; WorldPtrType testWorld1 = this->engine->ConstructEmptyWorld("world1"); WorldEntityMap testMap; EXPECT_FALSE(testMap.HasEntity(gazeboWorld1Entity)); EXPECT_EQ(nullptr, testMap.Get(gazeboWorld1Entity)); - EXPECT_EQ(gazebo::kNullEntity, testMap.Get(testWorld1)); + EXPECT_EQ(gz::sim::kNullEntity, testMap.Get(testWorld1)); EXPECT_EQ(0u, testMap.TotalMapEntryCount()); testMap.AddEntity(gazeboWorld1Entity, testWorld1); @@ -165,12 +165,12 @@ TEST_F(EntityFeatureMapFixture, AddCastRemoveEntity) testMap.Remove(gazeboWorld1Entity); EXPECT_FALSE(testMap.HasEntity(gazeboWorld1Entity)); EXPECT_EQ(nullptr, testMap.Get(gazeboWorld1Entity)); - EXPECT_EQ(gazebo::kNullEntity, testMap.Get(testWorld1)); + EXPECT_EQ(gz::sim::kNullEntity, testMap.Get(testWorld1)); EXPECT_EQ(3u, testMap.TotalMapEntryCount()); testMap.Remove(testWorld2); EXPECT_FALSE(testMap.HasEntity(gazeboWorld2Entity)); EXPECT_EQ(nullptr, testMap.Get(gazeboWorld2Entity)); - EXPECT_EQ(gazebo::kNullEntity, testMap.Get(testWorld2)); + EXPECT_EQ(gz::sim::kNullEntity, testMap.Get(testWorld2)); EXPECT_EQ(0u, testMap.TotalMapEntryCount()); } diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 636f48a9b8..9885a99204 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -17,10 +17,10 @@ #include "Physics.hh" -#include -#include -#include -#include +#include +#include +#include +#include #include #include @@ -30,43 +30,43 @@ #include #include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // SDF #include @@ -78,66 +78,66 @@ #include #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/EntityComponentManager.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/JointForceCmd.hh" -#include "ignition/gazebo/components/PhysicsEnginePlugin.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/PoseCmd.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 "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/JointForceCmd.hh" +#include "gz/sim/components/PhysicsEnginePlugin.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/PoseCmd.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" // Events -#include "ignition/gazebo/physics/Events.hh" +#include "gz/sim/physics/Events.hh" #include "EntityFeatureMap.hh" -using namespace ignition; +using namespace gz; using namespace ignition::gazebo::systems; using namespace ignition::gazebo::systems::physics_system; -namespace components = ignition::gazebo::components; +namespace components = gz::sim::components; // Private data class. -class ignition::gazebo::systems::PhysicsPrivate +class gz::sim::systems::PhysicsPrivate { /// \brief This is the minimum set of features that any physics engine must /// implement to be supported by this system. @@ -2734,7 +2734,7 @@ void PhysicsPrivate::EnableContactSurfaceCustomization(const Entity &_world) using ContactPoint = GCFeatureWorld::ContactPoint; using ExtraContactData = GCFeature::ExtraContactDataT; - const auto callbackID = "ignition::gazebo::systems::Physics"; + const auto callbackID = "sim::systems::Physics"; setContactPropertiesCallbackFeature->AddContactPropertiesCallback( callbackID, [this, _world](const GCFeatureWorld::Contact &_contact, @@ -2808,8 +2808,11 @@ void PhysicsPrivate::DisableContactSurfaceCustomization(const Entity &_world) } IGNITION_ADD_PLUGIN(Physics, - gazebo::System, + gz::sim::System, Physics::ISystemConfigure, Physics::ISystemUpdate) +IGNITION_ADD_PLUGIN_ALIAS(Physics, "gz::sim::systems::Physics") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(Physics, "ignition::gazebo::systems::Physics") diff --git a/src/systems/physics/Physics.hh b/src/systems/physics/Physics.hh index 38f7f10599..6213707e1f 100644 --- a/src/systems/physics/Physics.hh +++ b/src/systems/physics/Physics.hh @@ -14,39 +14,39 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_PHYSICS_HH_ -#define IGNITION_GAZEBO_SYSTEMS_PHYSICS_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_PHYSICS_HH_ +#define GZ_GAZEBO_SYSTEMS_PHYSICS_HH_ #include #include #include -#include -#include +#include +#include // Features need to be defined ahead of entityCast -#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 namespace ignition { diff --git a/src/systems/pose_publisher/PosePublisher.cc b/src/systems/pose_publisher/PosePublisher.cc index 25e428b7b6..55f2564cfc 100644 --- a/src/systems/pose_publisher/PosePublisher.cc +++ b/src/systems/pose_publisher/PosePublisher.cc @@ -17,7 +17,7 @@ #include "PosePublisher.hh" -#include +#include #include #include @@ -28,35 +28,35 @@ #include -#include -#include -#include -#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" - -using namespace ignition; -using namespace gazebo; +#include +#include +#include +#include +#include + +#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 gz; +using namespace gz::sim; using namespace systems; /// \brief Private data class for PosePublisher -class ignition::gazebo::systems::PosePublisherPrivate +class gz::sim::systems::PosePublisherPrivate { /// \brief Initializes internal caches for entities whose poses are to be /// published and their names @@ -555,5 +555,9 @@ IGNITION_ADD_PLUGIN(PosePublisher, PosePublisher::ISystemConfigure, PosePublisher::ISystemPostUpdate) +IGNITION_ADD_PLUGIN_ALIAS(PosePublisher, + "gz::sim::systems::PosePublisher") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(PosePublisher, "ignition::gazebo::systems::PosePublisher") diff --git a/src/systems/pose_publisher/PosePublisher.hh b/src/systems/pose_publisher/PosePublisher.hh index abd794ea25..be6ba9d8db 100644 --- a/src/systems/pose_publisher/PosePublisher.hh +++ b/src/systems/pose_publisher/PosePublisher.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_POSEPUBLISHER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_POSEPUBLISHER_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_POSEPUBLISHER_HH_ +#define GZ_GAZEBO_SYSTEMS_POSEPUBLISHER_HH_ #include -#include -#include +#include +#include namespace ignition { @@ -33,8 +33,8 @@ namespace systems class PosePublisherPrivate; /// \brief Pose publisher system. Attach to an entity to publish the - /// transform of its child entities in the form of ignition::msgs::Pose - /// messages, or a single ignition::msgs::Pose_V message if + /// transform of its child entities in the form of gz::msgs::Pose + /// messages, or a single gz::msgs::Pose_V message if /// "use_pose_vector_msg" is true. /// /// The following parameters are used by the system: @@ -47,8 +47,8 @@ namespace systems /// pose of the model that contains this system is /// also published. /// use_pose_vector_msg : Set to true to publish an - /// ignition::msgs::Pose_V message instead of - /// mulitple ignition::msgs::Pose messages. + /// gz::msgs::Pose_V message instead of + /// mulitple gz::msgs::Pose messages. /// update_frequency : Frequency of pose publications in Hz. A /// negative frequency publishes as fast as /// possible (i.e, at the rate of the simulation diff --git a/src/systems/scene_broadcaster/SceneBroadcaster.cc b/src/systems/scene_broadcaster/SceneBroadcaster.cc index 67942f74d5..4e06fd4437 100644 --- a/src/systems/scene_broadcaster/SceneBroadcaster.cc +++ b/src/systems/scene_broadcaster/SceneBroadcaster.cc @@ -17,45 +17,45 @@ #include "SceneBroadcaster.hh" -#include +#include #include #include #include #include -#include -#include -#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 +#include +#include +#include + +#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 @@ -65,12 +65,12 @@ using namespace std::chrono_literals; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; // Private data class. -class ignition::gazebo::systems::SceneBroadcasterPrivate +class gz::sim::systems::SceneBroadcasterPrivate { /// \brief Type alias for the graph used to represent the scene graph. public: using SceneGraphType = math::graph::DirectedGraph< @@ -1154,5 +1154,9 @@ IGNITION_ADD_PLUGIN(SceneBroadcaster, // Add plugin alias so that we can refer to the plugin without the version // namespace +IGNITION_ADD_PLUGIN_ALIAS(SceneBroadcaster, + "gz::sim::systems::SceneBroadcaster") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(SceneBroadcaster, "ignition::gazebo::systems::SceneBroadcaster") diff --git a/src/systems/scene_broadcaster/SceneBroadcaster.hh b/src/systems/scene_broadcaster/SceneBroadcaster.hh index aced8c4bfe..508a954f61 100644 --- a/src/systems/scene_broadcaster/SceneBroadcaster.hh +++ b/src/systems/scene_broadcaster/SceneBroadcaster.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SCENEBROADCASTER_SYSTEM_HH_ -#define IGNITION_GAZEBO_SCENEBROADCASTER_SYSTEM_HH_ +#ifndef GZ_GAZEBO_SCENEBROADCASTER_SYSTEM_HH_ +#define GZ_GAZEBO_SCENEBROADCASTER_SYSTEM_HH_ #include #include -#include -#include +#include +#include namespace ignition { @@ -35,7 +35,7 @@ namespace systems /** \class SceneBroadcaster SceneBroadcaster.hh \ * ignition/gazebo/systems/SceneBroadcaster.hh **/ - /// \brief System which periodically publishes an ignition::msgs::Scene + /// \brief System which periodically publishes an gz::msgs::Scene /// message with updated information. class SceneBroadcaster: public System, diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc index 592e02d5e3..86bed8659e 100644 --- a/src/systems/sensors/Sensors.cc +++ b/src/systems/sensors/Sensors.cc @@ -22,40 +22,40 @@ #include #include -#include -#include +#include +#include #include -#include -#include - -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Atmosphere.hh" -#include "ignition/gazebo/components/Camera.hh" -#include "ignition/gazebo/components/DepthCamera.hh" -#include "ignition/gazebo/components/GpuLidar.hh" -#include "ignition/gazebo/components/RenderEngineServerPlugin.hh" -#include "ignition/gazebo/components/RgbdCamera.hh" -#include "ignition/gazebo/components/ThermalCamera.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" - -using namespace ignition; -using namespace gazebo; +#include +#include + +#include +#include +#include +#include +#include + +#include "gz/sim/components/Atmosphere.hh" +#include "gz/sim/components/Camera.hh" +#include "gz/sim/components/DepthCamera.hh" +#include "gz/sim/components/GpuLidar.hh" +#include "gz/sim/components/RenderEngineServerPlugin.hh" +#include "gz/sim/components/RgbdCamera.hh" +#include "gz/sim/components/ThermalCamera.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 gz; +using namespace gz::sim; using namespace systems; // Private data class. -class ignition::gazebo::systems::SensorsPrivate +class gz::sim::systems::SensorsPrivate { /// \brief Sensor manager object. This manages the lifecycle of the /// instantiated sensors. @@ -554,4 +554,7 @@ IGNITION_ADD_PLUGIN(Sensors, System, Sensors::ISystemPostUpdate ) +IGNITION_ADD_PLUGIN_ALIAS(Sensors, "gz::sim::systems::Sensors") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(Sensors, "ignition::gazebo::systems::Sensors") diff --git a/src/systems/sensors/Sensors.hh b/src/systems/sensors/Sensors.hh index a4d3c17cfe..0622e8fafe 100644 --- a/src/systems/sensors/Sensors.hh +++ b/src/systems/sensors/Sensors.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_SENSORS_HH_ -#define IGNITION_GAZEBO_SYSTEMS_SENSORS_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_SENSORS_HH_ +#define GZ_GAZEBO_SYSTEMS_SENSORS_HH_ #include #include -#include -#include +#include +#include #include namespace ignition diff --git a/src/systems/thermal/Thermal.cc b/src/systems/thermal/Thermal.cc index 0a5652ec50..31e502eec7 100644 --- a/src/systems/thermal/Thermal.cc +++ b/src/systems/thermal/Thermal.cc @@ -15,22 +15,22 @@ * */ -#include -#include +#include +#include -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Temperature.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Temperature.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Util.hh" #include "Thermal.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; /// \brief Private Thermal data class. -class ignition::gazebo::systems::ThermalPrivate +class gz::sim::systems::ThermalPrivate { }; @@ -63,4 +63,7 @@ IGNITION_ADD_PLUGIN(Thermal, System, Thermal::ISystemConfigure ) +IGNITION_ADD_PLUGIN_ALIAS(Thermal, "gz::sim::systems::Thermal") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(Thermal, "ignition::gazebo::systems::Thermal") diff --git a/src/systems/thermal/Thermal.hh b/src/systems/thermal/Thermal.hh index 9210a06a0f..a331bd7dae 100644 --- a/src/systems/thermal/Thermal.hh +++ b/src/systems/thermal/Thermal.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_THERMAL_HH_ -#define IGNITION_GAZEBO_SYSTEMS_THERMAL_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_THERMAL_HH_ +#define GZ_GAZEBO_SYSTEMS_THERMAL_HH_ #include -#include -#include +#include +#include namespace ignition { @@ -47,7 +47,7 @@ namespace systems public: void Configure(const Entity &_entity, const std::shared_ptr &_sdf, EntityComponentManager &_ecm, - gazebo::EventManager &_eventMgr) final; + gz::sim::EventManager &_eventMgr) final; /// \brief Private data pointer. private: std::unique_ptr dataPtr; diff --git a/src/systems/touch_plugin/TouchPlugin.cc b/src/systems/touch_plugin/TouchPlugin.cc index 3628c1876c..cab220b1b8 100644 --- a/src/systems/touch_plugin/TouchPlugin.cc +++ b/src/systems/touch_plugin/TouchPlugin.cc @@ -22,27 +22,27 @@ #include #include -#include -#include -#include +#include +#include +#include #include -#include "ignition/gazebo/components/ContactSensor.hh" -#include "ignition/gazebo/components/ContactSensorData.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Sensor.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 "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; -class ignition::gazebo::systems::TouchPluginPrivate +class gz::sim::systems::TouchPluginPrivate { // Initialize the plugin public: void Load(const EntityComponentManager &_ecm, @@ -407,4 +407,7 @@ IGNITION_ADD_PLUGIN(TouchPlugin, TouchPlugin::ISystemPreUpdate, TouchPlugin::ISystemPostUpdate) +IGNITION_ADD_PLUGIN_ALIAS(TouchPlugin, "gz::sim::systems::TouchPlugin") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(TouchPlugin, "ignition::gazebo::systems::TouchPlugin") diff --git a/src/systems/touch_plugin/TouchPlugin.hh b/src/systems/touch_plugin/TouchPlugin.hh index 251fc2e8bf..4d43459667 100644 --- a/src/systems/touch_plugin/TouchPlugin.hh +++ b/src/systems/touch_plugin/TouchPlugin.hh @@ -15,11 +15,11 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_TOUCH_PLUGIN_HH_ -#define IGNITION_GAZEBO_SYSTEMS_TOUCH_PLUGIN_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_TOUCH_PLUGIN_HH_ +#define GZ_GAZEBO_SYSTEMS_TOUCH_PLUGIN_HH_ #include -#include +#include namespace ignition { @@ -82,8 +82,8 @@ namespace systems // Documentation inherited public: void PostUpdate( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) override; + const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) override; /// \brief Private data pointer private: std::unique_ptr dataPtr; diff --git a/src/systems/track_controller/TrackController.cc b/src/systems/track_controller/TrackController.cc index fdf8d1d51a..42d66fca0b 100644 --- a/src/systems/track_controller/TrackController.cc +++ b/src/systems/track_controller/TrackController.cc @@ -23,28 +23,28 @@ #include #include -#include -#include -#include +#include +#include +#include -#include -#include +#include +#include -#include -#include +#include +#include -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/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; +using namespace gz; +using namespace gz::sim; using namespace systems; -class ignition::gazebo::systems::TrackControllerPrivate +class gz::sim::systems::TrackControllerPrivate { public : ~TrackControllerPrivate() {} /// \brief Register a collision entity to work with this system (e.g. enable @@ -618,5 +618,9 @@ IGNITION_ADD_PLUGIN(TrackController, TrackController::ISystemConfigure, TrackController::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(TrackController, + "gz::sim::systems::TrackController") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(TrackController, "ignition::gazebo::systems::TrackController") diff --git a/src/systems/track_controller/TrackController.hh b/src/systems/track_controller/TrackController.hh index f9d54a3204..e79c4863bc 100644 --- a/src/systems/track_controller/TrackController.hh +++ b/src/systems/track_controller/TrackController.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_TRACKCONTROLLER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_TRACKCONTROLLER_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_TRACKCONTROLLER_HH_ +#define GZ_GAZEBO_SYSTEMS_TRACKCONTROLLER_HH_ #include -#include -#include "ignition/gazebo/physics/Events.hh" +#include +#include "gz/sim/physics/Events.hh" namespace ignition { @@ -112,8 +112,8 @@ namespace systems // Documentation inherited public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; /// \brief Private data pointer private: std::unique_ptr dataPtr; diff --git a/src/systems/tracked_vehicle/TrackedVehicle.cc b/src/systems/tracked_vehicle/TrackedVehicle.cc index 4b3ecc64e6..41fbd3f180 100644 --- a/src/systems/tracked_vehicle/TrackedVehicle.cc +++ b/src/systems/tracked_vehicle/TrackedVehicle.cc @@ -17,7 +17,7 @@ #include "TrackedVehicle.hh" -#include +#include #include #include @@ -27,21 +27,21 @@ #include #include -#include -#include -#include -#include -#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" - -using namespace ignition; -using namespace gazebo; +#include +#include +#include +#include +#include +#include + +#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 gz; +using namespace gz::sim; using namespace systems; /// \brief Velocity command. @@ -56,7 +56,7 @@ struct Commands Commands() {} }; -class ignition::gazebo::systems::TrackedVehiclePrivate +class gz::sim::systems::TrackedVehiclePrivate { /// \brief Callback for velocity subscription /// \param[in] _msg Velocity message @@ -774,5 +774,9 @@ IGNITION_ADD_PLUGIN(TrackedVehicle, TrackedVehicle::ISystemPreUpdate, TrackedVehicle::ISystemPostUpdate) +IGNITION_ADD_PLUGIN_ALIAS(TrackedVehicle, + "gz::sim::systems::TrackedVehicle") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(TrackedVehicle, "ignition::gazebo::systems::TrackedVehicle") diff --git a/src/systems/tracked_vehicle/TrackedVehicle.hh b/src/systems/tracked_vehicle/TrackedVehicle.hh index 878c5defc9..1e7891b408 100644 --- a/src/systems/tracked_vehicle/TrackedVehicle.hh +++ b/src/systems/tracked_vehicle/TrackedVehicle.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_TRACKEDVEHICLE_HH_ -#define IGNITION_GAZEBO_SYSTEMS_TRACKEDVEHICLE_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_TRACKEDVEHICLE_HH_ +#define GZ_GAZEBO_SYSTEMS_TRACKEDVEHICLE_HH_ #include -#include +#include namespace ignition { @@ -149,8 +149,8 @@ namespace systems // Documentation inherited public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; // Documentation inherited public: void PostUpdate( diff --git a/src/systems/triggered_publisher/TriggeredPublisher.cc b/src/systems/triggered_publisher/TriggeredPublisher.cc index f9e79b14fe..ee3b20dc86 100644 --- a/src/systems/triggered_publisher/TriggeredPublisher.cc +++ b/src/systems/triggered_publisher/TriggeredPublisher.cc @@ -24,17 +24,17 @@ #include #include -#include -#include -#include +#include +#include +#include // bug https://github.com/protocolbuffers/protobuf/issues/5051 #ifdef _WIN32 #undef GetMessage #endif -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; /// \brief Base class for input matchers. @@ -667,5 +667,9 @@ IGNITION_ADD_PLUGIN(TriggeredPublisher, System, TriggeredPublisher::ISystemConfigure) +IGNITION_ADD_PLUGIN_ALIAS(TriggeredPublisher, + "gz::sim::systems::TriggeredPublisher") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(TriggeredPublisher, "ignition::gazebo::systems::TriggeredPublisher") diff --git a/src/systems/triggered_publisher/TriggeredPublisher.hh b/src/systems/triggered_publisher/TriggeredPublisher.hh index 090999e5cc..3c1a4ffdb6 100644 --- a/src/systems/triggered_publisher/TriggeredPublisher.hh +++ b/src/systems/triggered_publisher/TriggeredPublisher.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_TRIGGEREDPUBLISHER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_TRIGGEREDPUBLISHER_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_TRIGGEREDPUBLISHER_HH_ +#define GZ_GAZEBO_SYSTEMS_TRIGGEREDPUBLISHER_HH_ #include #include #include -#include -#include "ignition/gazebo/System.hh" +#include +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 4920c5cb07..bf15dd08f7 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -18,42 +18,42 @@ #include "UserCommands.hh" #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include #include -#include +#include #include #include #include -#include -#include - -#include "ignition/common/Profiler.hh" - -#include "ignition/gazebo/components/Light.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/World.hh" -#include "ignition/gazebo/Conversions.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/SdfEntityCreator.hh" -#include "ignition/gazebo/Util.hh" - -using namespace ignition; -using namespace gazebo; +#include +#include + +#include "gz/common/Profiler.hh" + +#include "gz/sim/components/Light.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/World.hh" +#include "gz/sim/Conversions.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/SdfEntityCreator.hh" +#include "gz/sim/Util.hh" + +using namespace gz; +using namespace gz::sim; using namespace systems; namespace ignition @@ -173,7 +173,7 @@ class PhysicsCommand : public UserCommandBase } /// \brief Private UserCommands data class. -class ignition::gazebo::systems::UserCommandsPrivate +class gz::sim::systems::UserCommandsPrivate { /// \brief Callback for create service /// \param[in] _req Request containing entity description. @@ -835,5 +835,9 @@ IGNITION_ADD_PLUGIN(UserCommands, System, UserCommands::ISystemPreUpdate ) +IGNITION_ADD_PLUGIN_ALIAS(UserCommands, + "gz::sim::systems::UserCommands") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(UserCommands, "ignition::gazebo::systems::UserCommands") diff --git a/src/systems/user_commands/UserCommands.hh b/src/systems/user_commands/UserCommands.hh index 95af084c96..1f013103d8 100644 --- a/src/systems/user_commands/UserCommands.hh +++ b/src/systems/user_commands/UserCommands.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_USERCOMMANDS_HH_ -#define IGNITION_GAZEBO_SYSTEMS_USERCOMMANDS_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_USERCOMMANDS_HH_ +#define GZ_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 b1b12a329d..bb8900830d 100644 --- a/src/systems/velocity_control/VelocityControl.cc +++ b/src/systems/velocity_control/VelocityControl.cc @@ -21,22 +21,22 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include -#include "ignition/gazebo/components/AngularVelocityCmd.hh" -#include "ignition/gazebo/components/LinearVelocityCmd.hh" -#include "ignition/gazebo/Model.hh" +#include "gz/sim/components/AngularVelocityCmd.hh" +#include "gz/sim/components/LinearVelocityCmd.hh" +#include "gz/sim/Model.hh" #include "VelocityControl.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace systems; -class ignition::gazebo::systems::VelocityControlPrivate +class gz::sim::systems::VelocityControlPrivate { /// \brief Callback for model velocity subscription /// \param[in] _msg Velocity message @@ -377,5 +377,9 @@ IGNITION_ADD_PLUGIN(VelocityControl, VelocityControl::ISystemPreUpdate, VelocityControl::ISystemPostUpdate) +IGNITION_ADD_PLUGIN_ALIAS(VelocityControl, + "gz::sim::systems::VelocityControl") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(VelocityControl, "ignition::gazebo::systems::VelocityControl") diff --git a/src/systems/velocity_control/VelocityControl.hh b/src/systems/velocity_control/VelocityControl.hh index 08ac7cd569..1b98147383 100644 --- a/src/systems/velocity_control/VelocityControl.hh +++ b/src/systems/velocity_control/VelocityControl.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_VELOCITYCONTROL_HH_ -#define IGNITION_GAZEBO_SYSTEMS_VELOCITYCONTROL_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_VELOCITYCONTROL_HH_ +#define GZ_GAZEBO_SYSTEMS_VELOCITYCONTROL_HH_ #include #include -#include +#include namespace ignition { @@ -64,8 +64,8 @@ namespace systems // Documentation inherited public: void PreUpdate( - const ignition::gazebo::UpdateInfo &/*_info*/, - ignition::gazebo::EntityComponentManager &_ecm) override; + const gz::sim::UpdateInfo &/*_info*/, + gz::sim::EntityComponentManager &_ecm) override; // Documentation inherited public: void PostUpdate( diff --git a/src/systems/wheel_slip/WheelSlip.cc b/src/systems/wheel_slip/WheelSlip.cc index 41826fdb63..92f82cbfef 100644 --- a/src/systems/wheel_slip/WheelSlip.cc +++ b/src/systems/wheel_slip/WheelSlip.cc @@ -21,26 +21,26 @@ #include #include -#include -#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" - -using namespace ignition; -using namespace gazebo; +#include +#include +#include + +#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" + +using namespace gz; +using namespace gz::sim; using namespace systems; // Adapted from osrf/Gazebo WheelSlipPlugin // https://osrf-migration.github.io/gazebo-gh-pages/#!/osrf/gazebo/pull-requests/2950/ -class ignition::gazebo::systems::WheelSlipPrivate +class gz::sim::systems::WheelSlipPrivate { /// \brief Initialize the plugin public: bool Load(const EntityComponentManager &_ecm, sdf::ElementPtr _sdf); @@ -364,5 +364,9 @@ IGNITION_ADD_PLUGIN(WheelSlip, WheelSlip::ISystemConfigure, WheelSlip::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(WheelSlip, + "gz::sim::systems::WheelSlip") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(WheelSlip, "ignition::gazebo::systems::WheelSlip") diff --git a/src/systems/wheel_slip/WheelSlip.hh b/src/systems/wheel_slip/WheelSlip.hh index 0400da23dc..57c1558fdc 100644 --- a/src/systems/wheel_slip/WheelSlip.hh +++ b/src/systems/wheel_slip/WheelSlip.hh @@ -15,10 +15,10 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_WHEELSLIP_HH_ -#define IGNITION_GAZEBO_SYSTEMS_WHEELSLIP_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_WHEELSLIP_HH_ +#define GZ_GAZEBO_SYSTEMS_WHEELSLIP_HH_ -#include +#include #include namespace ignition @@ -76,7 +76,7 @@ namespace systems | + name="gz::sim::systems::WheelSlip"> 0 0.1 @@ -123,8 +123,8 @@ namespace systems // Documentation inherited public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; /// \brief Private data pointer private: std::unique_ptr dataPtr; diff --git a/src/systems/wind_effects/WindEffects.cc b/src/systems/wind_effects/WindEffects.cc index 1a419b6bed..213bedc5c5 100644 --- a/src/systems/wind_effects/WindEffects.cc +++ b/src/systems/wind_effects/WindEffects.cc @@ -18,8 +18,8 @@ #include "WindEffects.hh" #include -#include -#include +#include +#include #include #include @@ -27,34 +27,34 @@ #include #include -#include -#include -#include -#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" - -using namespace ignition; -using namespace gazebo; +#include +#include +#include +#include +#include + +#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 gz; +using namespace gz::sim; using namespace systems; /// \brief Private WindEffects data class. -class ignition::gazebo::systems::WindEffectsPrivate +class gz::sim::systems::WindEffectsPrivate { /// \brief Initialize the system. /// \param[in] _ecm Mutable reference to the EntityComponentManager. @@ -569,4 +569,9 @@ IGNITION_ADD_PLUGIN(WindEffects, System, WindEffects::ISystemPreUpdate ) -IGNITION_ADD_PLUGIN_ALIAS(WindEffects, "ignition::gazebo::systems::WindEffects") +IGNITION_ADD_PLUGIN_ALIAS(WindEffects, + "gz::sim::systems::WindEffects") + +// TODO(CH3): Deprecated, remove on version 8 +IGNITION_ADD_PLUGIN_ALIAS(WindEffects, + "ignition::gazebo::systems::WindEffects") diff --git a/src/systems/wind_effects/WindEffects.hh b/src/systems/wind_effects/WindEffects.hh index 7375857b9e..8e497afb94 100644 --- a/src/systems/wind_effects/WindEffects.hh +++ b/src/systems/wind_effects/WindEffects.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_WINDEFFECTS_HH_ -#define IGNITION_GAZEBO_SYSTEMS_WINDEFFECTS_HH_ +#ifndef GZ_GAZEBO_SYSTEMS_WINDEFFECTS_HH_ +#define GZ_GAZEBO_SYSTEMS_WINDEFFECTS_HH_ #include -#include -#include +#include +#include namespace ignition { diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 86cdb3578d..b3544ba8bd 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -6,6 +6,7 @@ include_directories ( ) configure_file (test_config.hh.in ${PROJECT_BINARY_DIR}/include/ignition/gazebo/test_config.hh) +configure_file (test_config.hh.in ${PROJECT_BINARY_DIR}/include/gz/sim/test_config.hh) # Build gtest add_library(gtest STATIC gtest/src/gtest-all.cc) diff --git a/test/benchmark/each.cc b/test/benchmark/each.cc index a386633c4c..27a3172d33 100644 --- a/test/benchmark/each.cc +++ b/test/benchmark/each.cc @@ -19,20 +19,20 @@ #include -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/EntityComponentManager.hh" -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/Inertial.hh" -#include "ignition/gazebo/components/LinearAcceleration.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/World.hh" +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/Inertial.hh" +#include "gz/sim/components/LinearAcceleration.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/World.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace components; constexpr const int kEachIterations {100}; diff --git a/test/benchmark/ecm_serialize.cc b/test/benchmark/ecm_serialize.cc index e26c357a63..fb63ccfdbe 100644 --- a/test/benchmark/ecm_serialize.cc +++ b/test/benchmark/ecm_serialize.cc @@ -19,18 +19,18 @@ #include -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/EntityComponentManager.hh" -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/Inertial.hh" -#include "ignition/gazebo/components/LinearAcceleration.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/World.hh" +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/Inertial.hh" +#include "gz/sim/components/LinearAcceleration.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/World.hh" -#include "ignition/gazebo/components/Factory.hh" +#include "gz/sim/components/Factory.hh" namespace ignition @@ -66,8 +66,8 @@ IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.BoolComponent", } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace components; // NOLINTNEXTLINE diff --git a/test/helpers/EnvTestFixture.hh b/test/helpers/EnvTestFixture.hh index e73636f6ac..16d8930f71 100644 --- a/test/helpers/EnvTestFixture.hh +++ b/test/helpers/EnvTestFixture.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_TEST_HELPERS_ENVTESTFIXTURE_HH_ -#define IGNITION_GAZEBO_TEST_HELPERS_ENVTESTFIXTURE_HH_ +#ifndef GZ_GAZEBO_TEST_HELPERS_ENVTESTFIXTURE_HH_ +#define GZ_GAZEBO_TEST_HELPERS_ENVTESTFIXTURE_HH_ #include -#include -#include -#include -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include "gz/sim/test_config.hh" using namespace ignition; diff --git a/test/helpers/Relay.hh b/test/helpers/Relay.hh index f30323e4e6..1884b7a082 100644 --- a/test/helpers/Relay.hh +++ b/test/helpers/Relay.hh @@ -14,10 +14,10 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_TEST_HELPERS_RELAY_HH_ -#define IGNITION_GAZEBO_TEST_HELPERS_RELAY_HH_ +#ifndef GZ_GAZEBO_TEST_HELPERS_RELAY_HH_ +#define GZ_GAZEBO_TEST_HELPERS_RELAY_HH_ -#include +#include #include "../plugins/MockSystem.hh" @@ -37,8 +37,8 @@ namespace test /// test::Relay testSystem; /// /// // Register callbacks, for example: -/// testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, -/// const gazebo::EntityComponentManager &_ecm) +/// testSystem.OnPostUpdate([&](const gz::sim::UpdateInfo &, +/// const gz::sim::EntityComponentManager &_ecm) /// { /// // Add expectations here /// } diff --git a/test/helpers/UniqueTestDirectoryEnv.hh b/test/helpers/UniqueTestDirectoryEnv.hh index c544ac3b8f..65410fc27e 100644 --- a/test/helpers/UniqueTestDirectoryEnv.hh +++ b/test/helpers/UniqueTestDirectoryEnv.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_TEST_HELPERS_CUSTOMCACHEENV_HH_ -#define IGNITION_GAZEBO_TEST_HELPERS_CUSTOMCACHEENV_HH_ +#ifndef GZ_GAZEBO_TEST_HELPERS_CUSTOMCACHEENV_HH_ +#define GZ_GAZEBO_TEST_HELPERS_CUSTOMCACHEENV_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -47,7 +47,7 @@ namespace test /// { /// ::testing::InitGoogleTest(&_argc, _argv); /// ::testing::AddGlobalTestEnvironment( -/// new ignition::gazebo::test::UniqueTestDirectoryEnv("custom_dir_name")); +/// new gz::sim::test::UniqueTestDirectoryEnv("custom_dir_name")); /// return RUN_ALL_TESTS(); /// } /// gtest is responsible for the instance, so there is no need to delete it. diff --git a/test/integration/ackermann_steering_system.cc b/test/integration/ackermann_steering_system.cc index 6ead175dd1..db50847ed0 100644 --- a/test/integration/ackermann_steering_system.cc +++ b/test/integration/ackermann_steering_system.cc @@ -17,26 +17,26 @@ #include #include -#include +#include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" #define tol 10e-4 -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; /// \brief Test AckermannSteering system diff --git a/test/integration/air_pressure_system.cc b/test/integration/air_pressure_system.cc index 367392b08a..ccb8807bd3 100644 --- a/test/integration/air_pressure_system.cc +++ b/test/integration/air_pressure_system.cc @@ -17,23 +17,23 @@ #include -#include +#include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/components/AirPressureSensor.hh" -#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/components/AirPressureSensor.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test AirPressureTest system class AirPressureTest : public InternalFixture<::testing::Test> diff --git a/test/integration/altimeter_system.cc b/test/integration/altimeter_system.cc index f5f53fa28b..427ad08764 100644 --- a/test/integration/altimeter_system.cc +++ b/test/integration/altimeter_system.cc @@ -17,30 +17,30 @@ #include -#include +#include #include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Altimeter.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include + +#include "gz/sim/components/Altimeter.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test AltimeterTest system class AltimeterTest : public InternalFixture<::testing::Test> diff --git a/test/integration/apply_joint_force_system.cc b/test/integration/apply_joint_force_system.cc index a2cfcb5ae5..161759cfe4 100644 --- a/test/integration/apply_joint_force_system.cc +++ b/test/integration/apply_joint_force_system.cc @@ -17,27 +17,27 @@ #include -#include +#include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/JointForceCmd.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/JointForceCmd.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" #define TOL 1e-4 -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test fixture for ApplyJointForce system class ApplyJointForceTestFixture : public InternalFixture<::testing::Test> diff --git a/test/integration/apply_link_wrench_system.cc b/test/integration/apply_link_wrench_system.cc index b937bd87a8..baba5dc919 100644 --- a/test/integration/apply_link_wrench_system.cc +++ b/test/integration/apply_link_wrench_system.cc @@ -17,29 +17,29 @@ #include -#include -#include +#include +#include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" -#include "ignition/gazebo/components/ExternalWorldWrenchCmd.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/TestFixture.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/components/ExternalWorldWrenchCmd.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/TestFixture.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #define tol 10e-4 -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; /// \brief Test fixture for ApplyLinkWrench system diff --git a/test/integration/battery_plugin.cc b/test/integration/battery_plugin.cc index 7b513cec3d..3252b6f24a 100644 --- a/test/integration/battery_plugin.cc +++ b/test/integration/battery_plugin.cc @@ -19,30 +19,30 @@ #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/ServerConfig.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/components/BatterySoC.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/ServerConfig.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/components/BatterySoC.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; class BatteryPluginTest : public InternalFixture<::testing::Test> { @@ -52,7 +52,7 @@ class BatteryPluginTest : public InternalFixture<::testing::Test> InternalFixture::SetUp(); auto plugin = sm.LoadPlugin("libMockSystem.so", - "ignition::gazebo::MockSystem", + "gz::sim::MockSystem", nullptr); EXPECT_TRUE(plugin.has_value()); this->systemPtr = plugin.value(); diff --git a/test/integration/breadcrumbs.cc b/test/integration/breadcrumbs.cc index 947c2dbde8..7a167b3e38 100644 --- a/test/integration/breadcrumbs.cc +++ b/test/integration/breadcrumbs.cc @@ -17,8 +17,8 @@ #include -#include -#include +#include +#include #include #include @@ -26,24 +26,24 @@ #include #include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/test_config.hh" #include "helpers/Relay.hh" #include "helpers/UniqueTestDirectoryEnv.hh" #include "helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; class BreadcrumbsTest : public InternalFixture<::testing::Test> { diff --git a/test/integration/buoyancy.cc b/test/integration/buoyancy.cc index 8d49f83bc8..be0b08118b 100644 --- a/test/integration/buoyancy.cc +++ b/test/integration/buoyancy.cc @@ -17,27 +17,27 @@ #include -#include -#include - -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/TestFixture.hh" -#include "ignition/gazebo/components/CenterOfVolume.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Volume.hh" - -#include "ignition/gazebo/test_config.hh" +#include +#include + +#include "gz/sim/Util.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/TestFixture.hh" +#include "gz/sim/components/CenterOfVolume.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Volume.hh" + +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; class BuoyancyTest : public InternalFixture<::testing::Test> { diff --git a/test/integration/camera_sensor_background.cc b/test/integration/camera_sensor_background.cc index 48a872b6e4..2182df9678 100644 --- a/test/integration/camera_sensor_background.cc +++ b/test/integration/camera_sensor_background.cc @@ -19,16 +19,16 @@ #include -#include -#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; +using namespace gz; using namespace std::chrono_literals; std::mutex mutex; @@ -74,12 +74,12 @@ TEST_F(CameraSensorBackgroundFixture, IGN_UTILS_TEST_DISABLED_ON_MAC(RedBackground)) { // Start server - gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/camera_sensor_empty_scene.sdf"; serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); diff --git a/test/integration/camera_video_record_system.cc b/test/integration/camera_video_record_system.cc index 13396cb3df..b6a2fd6cb9 100644 --- a/test/integration/camera_video_record_system.cc +++ b/test/integration/camera_video_record_system.cc @@ -16,20 +16,20 @@ */ #include -#include -#include -#include -#include +#include +#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test CameraVideoRecorder system class CameraVideoRecorderTest : public InternalFixture<::testing::Test> diff --git a/test/integration/collada_world_exporter.cc b/test/integration/collada_world_exporter.cc index 891c448870..1f082d2b1a 100644 --- a/test/integration/collada_world_exporter.cc +++ b/test/integration/collada_world_exporter.cc @@ -17,17 +17,17 @@ #include -#include -#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" #include "helpers/UniqueTestDirectoryEnv.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ///////////////////////////////////////////////// class ColladaWorldExporterFixture : public InternalFixture<::testing::Test> diff --git a/test/integration/components.cc b/test/integration/components.cc index a5892d1682..7e947a916a 100644 --- a/test/integration/components.cc +++ b/test/integration/components.cc @@ -30,55 +30,55 @@ #include #include -#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/Camera.hh" -#include "ignition/gazebo/components/CanonicalLink.hh" -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/DetachableJoint.hh" -#include "ignition/gazebo/components/Geometry.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/JointEffortLimitsCmd.hh" -#include "ignition/gazebo/components/JointPositionLimitsCmd.hh" -#include "ignition/gazebo/components/JointVelocityLimitsCmd.hh" -#include "ignition/gazebo/components/JointType.hh" -#include "ignition/gazebo/components/JointVelocity.hh" -#include "ignition/gazebo/components/JointVelocityCmd.hh" -#include "ignition/gazebo/components/Level.hh" -#include "ignition/gazebo/components/LevelBuffer.hh" -#include "ignition/gazebo/components/LevelEntityNames.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/LinearAcceleration.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/LogicalAudio.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/ParentEntity.hh" -#include "ignition/gazebo/components/ParentLinkName.hh" -#include "ignition/gazebo/components/Performer.hh" -#include "ignition/gazebo/components/PerformerLevels.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Scene.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/Static.hh" -#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/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/Camera.hh" +#include "gz/sim/components/CanonicalLink.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/DetachableJoint.hh" +#include "gz/sim/components/Geometry.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/JointEffortLimitsCmd.hh" +#include "gz/sim/components/JointPositionLimitsCmd.hh" +#include "gz/sim/components/JointVelocityLimitsCmd.hh" +#include "gz/sim/components/JointType.hh" +#include "gz/sim/components/JointVelocity.hh" +#include "gz/sim/components/JointVelocityCmd.hh" +#include "gz/sim/components/Level.hh" +#include "gz/sim/components/LevelBuffer.hh" +#include "gz/sim/components/LevelEntityNames.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/LinearAcceleration.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/LogicalAudio.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/ParentEntity.hh" +#include "gz/sim/components/ParentLinkName.hh" +#include "gz/sim/components/Performer.hh" +#include "gz/sim/components/PerformerLevels.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Scene.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/Static.hh" +#include "gz/sim/components/ThreadPitch.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; class ComponentsTest : public InternalFixture<::testing::Test> { diff --git a/test/integration/contact_system.cc b/test/integration/contact_system.cc index 0a9014673b..d3cc5f04be 100644 --- a/test/integration/contact_system.cc +++ b/test/integration/contact_system.cc @@ -17,23 +17,23 @@ #include -#include +#include #include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; class ContactSystemTest : public InternalFixture<::testing::Test> { diff --git a/test/integration/deprecated_TEST.cc b/test/integration/deprecated_TEST.cc new file mode 100644 index 0000000000..a47d16ea3a --- /dev/null +++ b/test/integration/deprecated_TEST.cc @@ -0,0 +1,26 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include + +///////////////////////////////////////////////// +// Make sure the ignition namespace still works +TEST(Deprecated, IgnitionNamespace) +{ + ignition::gazebo::System system; +} diff --git a/test/integration/depth_camera.cc b/test/integration/depth_camera.cc index 3e36c0013f..75e1fd3d5f 100644 --- a/test/integration/depth_camera.cc +++ b/test/integration/depth_camera.cc @@ -17,24 +17,24 @@ #include -#include +#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" #define DEPTH_TOL 1e-4 -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; /// \brief Test DepthCameraTest system diff --git a/test/integration/detachable_joint.cc b/test/integration/detachable_joint.cc index 90feb230aa..aae3680a9a 100644 --- a/test/integration/detachable_joint.cc +++ b/test/integration/detachable_joint.cc @@ -16,29 +16,29 @@ */ #include -#include -#include -#include -#include - -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" - -#include "ignition/gazebo/components/LinearAcceleration.hh" -#include "ignition/gazebo/components/LinearVelocity.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/WindMode.hh" +#include +#include +#include +#include + +#include "gz/sim/Link.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" + +#include "gz/sim/components/LinearAcceleration.hh" +#include "gz/sim/components/LinearVelocity.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/WindMode.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test DetachableJoint system class DetachableJointTest : public InternalFixture<::testing::Test> diff --git a/test/integration/diff_drive_system.cc b/test/integration/diff_drive_system.cc index f073fe7ee8..2cfe4a9cee 100644 --- a/test/integration/diff_drive_system.cc +++ b/test/integration/diff_drive_system.cc @@ -16,26 +16,26 @@ */ #include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include + +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" #define tol 10e-4 -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; /// \brief Test DiffDrive system diff --git a/test/integration/each_new_removed.cc b/test/integration/each_new_removed.cc index f252d1a4fd..b5ce72be0c 100644 --- a/test/integration/each_new_removed.cc +++ b/test/integration/each_new_removed.cc @@ -20,22 +20,22 @@ #include #include -#include -#include +#include +#include #include -#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/components/Factory.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; +using namespace gz; using namespace std::chrono_literals; -using IntComponent = gazebo::components::Component; +using IntComponent = gz::sim::components::Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.IntComponent", IntComponent) @@ -46,9 +46,9 @@ class EachNewRemovedFixture : public InternalFixture<::testing::Test> ///////////////////////////////////////////////// TEST_F(EachNewRemovedFixture, EachNewEachRemovedInSystem) { - gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; - gazebo::Server server; + gz::sim::Server server; server.SetUpdatePeriod(1ns); @@ -60,12 +60,12 @@ TEST_F(EachNewRemovedFixture, EachNewEachRemovedInSystem) // Entities to be created in a system. These have to be out here so the // entityCreator can set the ids when it creates the entities and the // entityRemover system can access them easily - gazebo::Entity e1 = gazebo::kNullEntity; - gazebo::Entity e2 = gazebo::kNullEntity; + gz::sim::Entity e1 = gz::sim::kNullEntity; + gz::sim::Entity e2 = gz::sim::kNullEntity; - gazebo::test::Relay entityCreator; + gz::sim::test::Relay entityCreator; entityCreator.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const gz::sim::UpdateInfo &, gz::sim::EntityComponentManager &_ecm) { if (shouldCreateEntities) { @@ -78,9 +78,9 @@ TEST_F(EachNewRemovedFixture, EachNewEachRemovedInSystem) } }); - gazebo::test::Relay entityRemover; + gz::sim::test::Relay entityRemover; entityRemover.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const gz::sim::UpdateInfo &, gz::sim::EntityComponentManager &_ecm) { if (shouldRemoveEntities) { @@ -104,16 +104,16 @@ TEST_F(EachNewRemovedFixture, EachNewEachRemovedInSystem) { // Lambda to return. This a simple counter that uses the appropriate count // variable where count = (pre, update, post)count - auto counterImpl = [&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + auto counterImpl = [&](const gz::sim::UpdateInfo &, + const gz::sim::EntityComponentManager &_ecm) { - _ecm.EachNew([&](const gazebo::Entity &, + _ecm.EachNew([&](const gz::sim::Entity &, const IntComponent *) -> bool { ++_count.newEntities; return true; }); - _ecm.EachRemoved([&](const gazebo::Entity &, + _ecm.EachRemoved([&](const gz::sim::Entity &, const IntComponent *) -> bool { ++_count.removedEntities; @@ -123,7 +123,7 @@ TEST_F(EachNewRemovedFixture, EachNewEachRemovedInSystem) return counterImpl; }; - gazebo::test::Relay entityCounter; + gz::sim::test::Relay entityCounter; entityCounter.OnPreUpdate(counterFunc(preCount)); entityCounter.OnUpdate(counterFunc(updateCount)); entityCounter.OnPostUpdate(counterFunc(postCount)); diff --git a/test/integration/elevator_system.cc b/test/integration/elevator_system.cc index 5889143bb5..94db3719c0 100644 --- a/test/integration/elevator_system.cc +++ b/test/integration/elevator_system.cc @@ -22,16 +22,16 @@ #include -#include +#include -#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; /// \brief Test fixture for Elevator system diff --git a/test/integration/entity_erase.cc b/test/integration/entity_erase.cc index 8590c45fcf..d45235bb0d 100644 --- a/test/integration/entity_erase.cc +++ b/test/integration/entity_erase.cc @@ -17,12 +17,12 @@ #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) #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; class PhysicsSystemFixture : public InternalFixture<::testing::Test> diff --git a/test/integration/events.cc b/test/integration/events.cc index b71fb4de52..efe24ef79e 100644 --- a/test/integration/events.cc +++ b/test/integration/events.cc @@ -16,18 +16,18 @@ */ #include -#include -#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "plugins/EventTriggerSystem.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; class EventTrigger : public InternalFixture<::testing::Test> { diff --git a/test/integration/examples_build.cc b/test/integration/examples_build.cc index a84e5bfe66..9802d6ac35 100644 --- a/test/integration/examples_build.cc +++ b/test/integration/examples_build.cc @@ -18,18 +18,18 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" // File copied from // https://github.com/gazebosim/gz-gui/raw/ign-gui3/test/integration/ExamplesBuild_TEST.cc -using namespace ignition; +using namespace gz; #ifndef _WIN32 #include // NOLINT(build/include_order) @@ -80,7 +80,7 @@ bool createAndSwitchToTempDir(std::string &_newTempPath) #include // NOLINT(build/include_order) #include // NOLINT(build/include_order) #include -#include +#include ///////////////////////////////////////////////// bool createAndSwitchToTempDir(std::string &_newTempPath) diff --git a/test/integration/gpu_lidar.cc b/test/integration/gpu_lidar.cc index 8597db0348..886a8521df 100644 --- a/test/integration/gpu_lidar.cc +++ b/test/integration/gpu_lidar.cc @@ -17,23 +17,23 @@ #include -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" #define LASER_TOL 1e-4 -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test GpuLidarTest system class GpuLidarTest : public InternalFixture<::testing::Test> diff --git a/test/integration/imu_system.cc b/test/integration/imu_system.cc index d8addf7cb1..1f6e59ca76 100644 --- a/test/integration/imu_system.cc +++ b/test/integration/imu_system.cc @@ -17,32 +17,32 @@ #include -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/Gravity.hh" -#include "ignition/gazebo/components/Imu.hh" -#include "ignition/gazebo/components/LinearAcceleration.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Sensor.hh" +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/Gravity.hh" +#include "gz/sim/components/Imu.hh" +#include "gz/sim/components/LinearAcceleration.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Sensor.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" #define TOL 1e-4 -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test ImuTest system class ImuTest : public InternalFixture<::testing::Test> diff --git a/test/integration/joint_controller_system.cc b/test/integration/joint_controller_system.cc index bfbd1cc6d2..485fed7b9c 100644 --- a/test/integration/joint_controller_system.cc +++ b/test/integration/joint_controller_system.cc @@ -17,27 +17,27 @@ #include -#include +#include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Name.hh" +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Name.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" #define TOL 1e-4 -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test fixture for JointController system class JointControllerTestFixture : public InternalFixture<::testing::Test> diff --git a/test/integration/joint_position_controller_system.cc b/test/integration/joint_position_controller_system.cc index 80bd5c71e1..a57d641fd4 100644 --- a/test/integration/joint_position_controller_system.cc +++ b/test/integration/joint_position_controller_system.cc @@ -17,27 +17,27 @@ #include -#include +#include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/Name.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/Name.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" #define TOL 1e-4 -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test fixture for JointPositionController system class JointPositionControllerTestFixture diff --git a/test/integration/joint_state_publisher_system.cc b/test/integration/joint_state_publisher_system.cc index d58e59c522..36ab10013d 100644 --- a/test/integration/joint_state_publisher_system.cc +++ b/test/integration/joint_state_publisher_system.cc @@ -16,16 +16,16 @@ */ #include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; /// \brief Test JointStatePublisher system diff --git a/test/integration/kinetic_energy_monitor_system.cc b/test/integration/kinetic_energy_monitor_system.cc index 5a7fa43c5c..5553a2e43f 100644 --- a/test/integration/kinetic_energy_monitor_system.cc +++ b/test/integration/kinetic_energy_monitor_system.cc @@ -17,20 +17,20 @@ #include -#include +#include #include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test Kinetic Energy Monitor system class KineticEnergyMonitorTest : public InternalFixture<::testing::Test> diff --git a/test/integration/level_manager.cc b/test/integration/level_manager.cc index d0a6536b02..01182857ea 100644 --- a/test/integration/level_manager.cc +++ b/test/integration/level_manager.cc @@ -21,9 +21,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include #include #include @@ -32,26 +32,26 @@ #include #include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) - -#include "ignition/gazebo/components/Level.hh" -#include "ignition/gazebo/components/LevelBuffer.hh" -#include "ignition/gazebo/components/LevelEntityNames.hh" -#include "ignition/gazebo/components/Light.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/PerformerLevels.hh" -#include "ignition/gazebo/components/Pose.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) + +#include "gz/sim/components/Level.hh" +#include "gz/sim/components/LevelBuffer.hh" +#include "gz/sim/components/LevelEntityNames.hh" +#include "gz/sim/components/Light.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/PerformerLevels.hh" +#include "gz/sim/components/Pose.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; ////////////////////////////////////////////////// diff --git a/test/integration/level_manager_runtime_performers.cc b/test/integration/level_manager_runtime_performers.cc index 902b98cdfa..e96c8c8c8d 100644 --- a/test/integration/level_manager_runtime_performers.cc +++ b/test/integration/level_manager_runtime_performers.cc @@ -17,37 +17,37 @@ #include -#include -#include +#include +#include #include #include -#include -#include -#include - -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) - -#include "ignition/gazebo/components/Level.hh" -#include "ignition/gazebo/components/LevelBuffer.hh" -#include "ignition/gazebo/components/LevelEntityNames.hh" -#include "ignition/gazebo/components/Light.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/PerformerLevels.hh" -#include "ignition/gazebo/components/Pose.hh" +#include +#include +#include + +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) + +#include "gz/sim/components/Level.hh" +#include "gz/sim/components/LevelBuffer.hh" +#include "gz/sim/components/LevelEntityNames.hh" +#include "gz/sim/components/Light.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/PerformerLevels.hh" +#include "gz/sim/components/Pose.hh" #include "plugins/MockSystem.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; ////////////////////////////////////////////////// diff --git a/test/integration/lift_drag_system.cc b/test/integration/lift_drag_system.cc index 65e3b3fe57..5147152108 100644 --- a/test/integration/lift_drag_system.cc +++ b/test/integration/lift_drag_system.cc @@ -17,34 +17,34 @@ #include -#include -#include - -#include -#include -#include - -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/LinearAcceleration.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/JointForceCmd.hh" -#include "ignition/gazebo/components/Pose.hh" - -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include + +#include +#include +#include + +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/LinearAcceleration.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/JointForceCmd.hh" +#include "gz/sim/components/Pose.hh" + +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" #define TOL 1e-4 -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test fixture for LiftDrag system class LiftDragTestFixture : public InternalFixture<::testing::Test> diff --git a/test/integration/link.cc b/test/integration/link.cc index 72b361635b..8bc18b6722 100644 --- a/test/integration/link.cc +++ b/test/integration/link.cc @@ -17,31 +17,31 @@ #include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; class LinkIntegrationTest : public InternalFixture<::testing::Test> { diff --git a/test/integration/log_system.cc b/test/integration/log_system.cc index 700a4aeb0e..dd2faf6745 100644 --- a/test/integration/log_system.cc +++ b/test/integration/log_system.cc @@ -16,7 +16,7 @@ */ #include -#include +#include #include #include @@ -26,35 +26,35 @@ #include #include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include #include #include -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/LogPlaybackStatistics.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/ServerConfig.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/LogPlaybackStatistics.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/ServerConfig.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; static const std::string kBinPath(PROJECT_BINARY_PATH); @@ -335,7 +335,7 @@ TEST_F(LogSystemTest, LogDefaults) // Test case 1: // No path specified on command line. This does not go through - // ign.cc, recording should take place in the `.ignition` directory + // gz.cc, recording should take place in the `.ignition` directory { // Change log path in SDF to empty sdf::Root recordSdfRoot; @@ -371,7 +371,7 @@ TEST_F(LogSystemTest, LogDefaults) // Test case 2: // No path specified on command line (only --record, no --record-path). // No path specified in SDF. - // Run from command line, which should trigger ign.cc, which should initialize + // Run from command line, which should trigger gz.cc, which should initialize // ignLogDirectory() to default timestamp path. Both console and state logs // should be recorded here. @@ -383,7 +383,7 @@ TEST_F(LogSystemTest, LogDefaults) entryList(logPath, entriesBefore); { - // Command line triggers ign.cc, which handles initializing ignLogDirectory + // Command line triggers gz.cc, which handles initializing ignLogDirectory std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 " + "--record " + kSdfFileOpt + recordSdfPath; std::cout << "Running command [" << cmd << "]" << std::endl; @@ -436,7 +436,7 @@ TEST_F(LogSystemTest, LogPaths) // No path specified in C++ API. // LogIgnoreSdfPath is not set. // Should take SDF path. State log should be stored here. Console log is not - // initialized because ign.cc is not triggered. + // initialized because gz.cc is not triggered. { // Change log path in SDF to build directory sdf::Root recordSdfRoot; @@ -486,7 +486,7 @@ TEST_F(LogSystemTest, LogPaths) // No path specified on command line (therefore LogIgnoreSdfPath is not set). // State log should be stored in SDF path. // Console log should be stored to default timestamp path ignLogDirectory - // because ign.cc is triggered by command line. + // because gz.cc is triggered by command line. { // Change log path in SDF to build directory sdf::Root recordSdfRoot; @@ -501,7 +501,7 @@ TEST_F(LogSystemTest, LogPaths) ofs << recordSdfRoot.Element()->ToString("").c_str(); ofs.close(); - // Command line triggers ign.cc, which handles initializing ignLogDirectory + // Command line triggers gz.cc, which handles initializing ignLogDirectory std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 " + "--record " + kSdfFileOpt + tmpRecordSdfPath; std::cout << "Running command [" << cmd << "]" << std::endl; @@ -544,7 +544,7 @@ TEST_F(LogSystemTest, LogPaths) // A different path is specified via C++ API. // LogIgnoreSdfPath is not set (pure C++ API usage). // Should store state.tlog to SDF path. Console log is not initialized - // because ign.cc is not triggered. + // because gz.cc is not triggered. std::string stateLogPath = this->logDir; std::string consoleLogPath = common::joinPaths(this->logsDir, "console"); @@ -590,7 +590,7 @@ TEST_F(LogSystemTest, LogPaths) // A different path is specified via C++ API. // LogIgnoreSdfPath is set (similar to specifying a path on command line). // Should take C++ API path. State log should be stored here. Console log is - // not initialized because ign.cc is not triggered. + // not initialized because gz.cc is not triggered. const std::string sdfPath = common::joinPaths(this->logsDir, "sdfPath"); const std::string cppPath = common::joinPaths(this->logsDir, "cppPath"); { @@ -632,7 +632,7 @@ TEST_F(LogSystemTest, LogPaths) // A path is specified by --record-path on command line. // Both state and console logs should be stored here. { - // Command line triggers ign.cc, which handles initializing ignLogDirectory + // Command line triggers gz.cc, which handles initializing ignLogDirectory std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 " + "--record-path " + this->logDir + " " + kSdfFileOpt + recordSdfPath; std::cout << "Running command [" << cmd << "]" << std::endl; @@ -674,7 +674,7 @@ TEST_F(LogSystemTest, LogPaths) ofs << recordSdfRoot.Element()->ToString("").c_str(); ofs.close(); - // Command line triggers ign.cc, which handles initializing ignLogDirectory + // Command line triggers gz.cc, which handles initializing ignLogDirectory std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 " + "--record-path " + cliPath + " " + kSdfFileOpt + tmpRecordSdfPath; std::cout << "Running command [" << cmd << "]" << std::endl; @@ -1151,7 +1151,7 @@ TEST_F(LogSystemTest, LogOverwrite) // Path exists, no overwrite flag. LogRecord.cc should still overwrite by // default behavior whenever the specified path already exists. // Path is set by SDF. - // Server is run from command line, ign.cc should initialize new default + // Server is run from command line, gz.cc should initialize new default // timestamp directory, where console log should be recorded. State log should // be recorded to the path in SDF. @@ -1185,7 +1185,7 @@ TEST_F(LogSystemTest, LogOverwrite) ofs << recordSdfRoot.Element()->ToString("").c_str(); ofs.close(); - // Command line triggers ign.cc, which handles initializing ignLogDirectory + // Command line triggers gz.cc, which handles initializing ignLogDirectory std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 " + kSdfFileOpt + tmpRecordSdfPath; std::cout << "Running command [" << cmd << "]" << std::endl; @@ -1226,9 +1226,9 @@ TEST_F(LogSystemTest, LogOverwrite) // Test case 4: // Path exists, command line --log-overwrite, should overwrite by - // command-line logic in ign.cc + // command-line logic in gz.cc { - // Command line triggers ign.cc, which handles creating a unique path if + // Command line triggers gz.cc, which handles creating a unique path if // file already exists, so as to not overwrite std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 --log-overwrite " + "--record-path " + this->logDir + " " + kSdfFileOpt + recordSdfPath; @@ -1254,9 +1254,9 @@ TEST_F(LogSystemTest, LogOverwrite) // Test case 5: // Path exists, no --log-overwrite, should create new files by command-line - // logic in ign.cc + // logic in gz.cc { - // Command line triggers ign.cc, which handles creating a unique path if + // Command line triggers gz.cc, which handles creating a unique path if // file already exists, so as to not overwrite std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 " + "--record-path " + this->logDir + " " + kSdfFileOpt + recordSdfPath; @@ -1644,7 +1644,7 @@ TEST_F(LogSystemTest, LogCompressCmdLine) EXPECT_TRUE(common::exists(recordPath)); EXPECT_TRUE(common::exists(defaultCmpPath)); - // Command line triggers ign.cc, which handles creating a unique path if + // Command line triggers gz.cc, which handles creating a unique path if // file already exists, so as to not overwrite std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 --log-compress " + "--record-path " + recordPath + " " @@ -1675,7 +1675,7 @@ TEST_F(LogSystemTest, LogCompressCmdLine) EXPECT_FALSE(common::exists(recordPath)); EXPECT_TRUE(common::exists(this->AppendExtension(recordPath, "(1).zip"))); - // Command line triggers ign.cc, which handles creating a unique path if + // Command line triggers gz.cc, which handles creating a unique path if // file already exists, so as to not overwrite std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 --log-compress " + "--record-path " + recordPath + " " @@ -1721,7 +1721,7 @@ TEST_F(LogSystemTest, LogResources) #ifndef __APPLE__ // Log resources from command line { - // Command line triggers ign.cc, which handles initializing ignLogDirectory + // Command line triggers gz.cc, which handles initializing ignLogDirectory std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 " + "--record --record-resources --record-path " + recordPath + " " + kSdfFileOpt + recordSdfPath; @@ -1766,7 +1766,7 @@ TEST_F(LogSystemTest, LogResources) } // Console log is not created because ignLogDirectory() is not initialized, - // as ign.cc is not executed by command line. + // as gz.cc is not executed by command line. EXPECT_TRUE(common::exists(statePath)); // Recorded models should exist @@ -1808,7 +1808,7 @@ TEST_F(LogSystemTest, LogTopics) #ifndef __APPLE__ // Log only the /clock topic from command line { - // Command line triggers ign.cc, which handles initializing ignLogDirectory + // Command line triggers gz.cc, which handles initializing ignLogDirectory std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 " + "--record-topic /clock " + "--record-path " + recordPath + " " diff --git a/test/integration/logical_audio_sensor_plugin.cc b/test/integration/logical_audio_sensor_plugin.cc index 7fed016462..f831df8589 100644 --- a/test/integration/logical_audio_sensor_plugin.cc +++ b/test/integration/logical_audio_sensor_plugin.cc @@ -23,27 +23,27 @@ #include #include -#include -#include -#include +#include +#include +#include #include -#include -#include - -#include "ignition/gazebo/components/LogicalAudio.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/test_config.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/ServerConfig.hh" -#include "ignition/gazebo/Types.hh" +#include +#include + +#include "gz/sim/components/LogicalAudio.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/test_config.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/ServerConfig.hh" +#include "gz/sim/Types.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test LogicalAudio system plugin class LogicalAudioTest : public InternalFixture<::testing::Test> diff --git a/test/integration/logical_camera_system.cc b/test/integration/logical_camera_system.cc index f285b1f132..d722284b03 100644 --- a/test/integration/logical_camera_system.cc +++ b/test/integration/logical_camera_system.cc @@ -17,26 +17,26 @@ #include -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include -#include "ignition/gazebo/components/LogicalCamera.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#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/components/LogicalCamera.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test LogicalCameraTest system class LogicalCameraTest : public InternalFixture<::testing::Test> diff --git a/test/integration/magnetometer_system.cc b/test/integration/magnetometer_system.cc index b057caab4f..453841caec 100644 --- a/test/integration/magnetometer_system.cc +++ b/test/integration/magnetometer_system.cc @@ -17,30 +17,30 @@ #include -#include +#include -#include -#include -#include -#include +#include +#include +#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/Sensor.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/Sensor.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" #define TOL 1e-4 -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test MagnetometerTest system class MagnetometerTest : public InternalFixture<::testing::Test> diff --git a/test/integration/model.cc b/test/integration/model.cc index d3aeb14f91..d3d023e01a 100644 --- a/test/integration/model.cc +++ b/test/integration/model.cc @@ -17,28 +17,28 @@ #include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; class ModelIntegrationTest : public InternalFixture<::testing::Test> { diff --git a/test/integration/multicopter.cc b/test/integration/multicopter.cc index 8f732edb0a..1ac7d67ac2 100644 --- a/test/integration/multicopter.cc +++ b/test/integration/multicopter.cc @@ -22,28 +22,28 @@ #include -#include -#include -#include - -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointVelocity.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Model.hh" - -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include + +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointVelocity.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Model.hh" + +#include "gz/sim/Model.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; class MulticopterTest : public InternalFixture<::testing::Test> diff --git a/test/integration/network_handshake.cc b/test/integration/network_handshake.cc index 9f03ef9630..6bf985a7f7 100644 --- a/test/integration/network_handshake.cc +++ b/test/integration/network_handshake.cc @@ -18,18 +18,18 @@ #include #include #include -#include +#include -#include "ignition/msgs/world_control.pb.h" -#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/msgs/world_control.pb.h" +#include "gz/msgs/world_stats.pb.h" +#include "gz/transport/Node.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; uint64_t kIterations; @@ -137,7 +137,7 @@ TEST_F(NetworkHandshake, IGN_UTILS_TEST_DISABLED_ON_MAC(Updates)) primaryPluginInfo.SetEntityType("world"); primaryPluginInfo.SetFilename( "libignition-gazebo-scene-broadcaster-system.so"); - primaryPluginInfo.SetName("ignition::gazebo::systems::SceneBroadcaster"); + primaryPluginInfo.SetName("sim::systems::SceneBroadcaster"); primaryPluginInfo.SetSdf(pluginElem); ServerConfig configPrimary; @@ -158,7 +158,7 @@ TEST_F(NetworkHandshake, IGN_UTILS_TEST_DISABLED_ON_MAC(Updates)) secondaryPluginInfo.SetEntityName("default"); secondaryPluginInfo.SetEntityType("world"); secondaryPluginInfo.SetFilename("libignition-gazebo-physics-system.so"); - secondaryPluginInfo.SetName("ignition::gazebo::systems::Physics"); + secondaryPluginInfo.SetName("sim::systems::Physics"); secondaryPluginInfo.SetSdf(pluginElem); ServerConfig configSecondary; diff --git a/test/integration/performer_detector.cc b/test/integration/performer_detector.cc index de569a7d27..2b19639703 100644 --- a/test/integration/performer_detector.cc +++ b/test/integration/performer_detector.cc @@ -16,24 +16,24 @@ */ #include -#include +#include -#include -#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/components/Model.hh" -#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/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/PoseCmd.hh" +#include "gz/sim/test_config.hh" #include "helpers/Relay.hh" #include "helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; class PerformerDetectorTest : public InternalFixture<::testing::Test> diff --git a/test/integration/physics_system.cc b/test/integration/physics_system.cc index 1b96ce5d64..3a1a0e932a 100644 --- a/test/integration/physics_system.cc +++ b/test/integration/physics_system.cc @@ -23,8 +23,8 @@ #ifdef HAVE_DART #include #endif -#include -#include +#include +#include #include #include #include @@ -34,41 +34,41 @@ #include #include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) - -#include "ignition/gazebo/components/AxisAlignedBox.hh" -#include "ignition/gazebo/components/CanonicalLink.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/JointEffortLimitsCmd.hh" -#include "ignition/gazebo/components/JointForceCmd.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/JointPositionLimitsCmd.hh" -#include "ignition/gazebo/components/JointPositionReset.hh" -#include "ignition/gazebo/components/JointVelocity.hh" -#include "ignition/gazebo/components/JointVelocityCmd.hh" -#include "ignition/gazebo/components/JointVelocityLimitsCmd.hh" -#include "ignition/gazebo/components/JointVelocityReset.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/LinearVelocity.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/Static.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/World.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) + +#include "gz/sim/components/AxisAlignedBox.hh" +#include "gz/sim/components/CanonicalLink.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/JointEffortLimitsCmd.hh" +#include "gz/sim/components/JointForceCmd.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/JointPositionLimitsCmd.hh" +#include "gz/sim/components/JointPositionReset.hh" +#include "gz/sim/components/JointVelocity.hh" +#include "gz/sim/components/JointVelocityCmd.hh" +#include "gz/sim/components/JointVelocityLimitsCmd.hh" +#include "gz/sim/components/JointVelocityReset.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/LinearVelocity.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/Static.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; class PhysicsSystemFixture : public InternalFixture<::testing::Test> diff --git a/test/integration/play_pause.cc b/test/integration/play_pause.cc index ed7b2241f3..1ce1a37197 100644 --- a/test/integration/play_pause.cc +++ b/test/integration/play_pause.cc @@ -20,14 +20,14 @@ #include #include "ignition/msgs.hh" -#include "ignition/transport.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/transport.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; uint64_t kIterations; diff --git a/test/integration/pose_publisher_system.cc b/test/integration/pose_publisher_system.cc index 5c4ff5df51..cf267e4e20 100644 --- a/test/integration/pose_publisher_system.cc +++ b/test/integration/pose_publisher_system.cc @@ -18,28 +18,28 @@ #include #include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include + +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" #define tol 10e-4 -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test PosePublisher system class PosePublisherTest : public InternalFixture<::testing::TestWithParam> diff --git a/test/integration/rgbd_camera.cc b/test/integration/rgbd_camera.cc index 6194e3b564..1145a6348b 100644 --- a/test/integration/rgbd_camera.cc +++ b/test/integration/rgbd_camera.cc @@ -17,24 +17,24 @@ #include -#include +#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" #define DEPTH_TOL 1e-4 -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; /// \brief Test RgbdCameraTest system diff --git a/test/integration/save_world.cc b/test/integration/save_world.cc index f4792828aa..6995b10473 100644 --- a/test/integration/save_world.cc +++ b/test/integration/save_world.cc @@ -16,7 +16,7 @@ */ #include -#include +#include #include #include @@ -26,22 +26,22 @@ #include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "helpers/UniqueTestDirectoryEnv.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ///////////////////////////////////////////////// class SdfGeneratorFixture : public InternalFixture<::testing::Test> diff --git a/test/integration/scene_broadcaster_system.cc b/test/integration/scene_broadcaster_system.cc index c7900ef847..c63c8d84d6 100644 --- a/test/integration/scene_broadcaster_system.cc +++ b/test/integration/scene_broadcaster_system.cc @@ -20,16 +20,16 @@ #include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; +using namespace gz; /// \brief Test SceneBroadcaster system class SceneBroadcasterTest @@ -41,11 +41,11 @@ class SceneBroadcasterTest TEST_P(SceneBroadcasterTest, PoseInfo) { // Start server - gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_EQ(16u, *server.EntityCount()); @@ -91,11 +91,11 @@ TEST_P(SceneBroadcasterTest, PoseInfo) TEST_P(SceneBroadcasterTest, SceneInfo) { // Start server - gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_EQ(16u, *server.EntityCount()); @@ -137,11 +137,11 @@ TEST_P(SceneBroadcasterTest, SceneInfo) TEST_P(SceneBroadcasterTest, SceneGraph) { // Start server - gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_EQ(16u, *server.EntityCount()); @@ -177,11 +177,11 @@ TEST_P(SceneBroadcasterTest, SceneGraph) TEST_P(SceneBroadcasterTest, SceneTopic) { // Start server - gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_EQ(16u, *server.EntityCount()); @@ -221,11 +221,11 @@ TEST_P(SceneBroadcasterTest, SceneTopic) TEST_P(SceneBroadcasterTest, SceneTopicSensors) { // Start server - gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/altimeter_with_pose.sdf"); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_EQ(12u, *server.EntityCount()); @@ -272,11 +272,11 @@ TEST_P(SceneBroadcasterTest, SceneTopicSensors) TEST_P(SceneBroadcasterTest, DeletedTopic) { // Start server - gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); @@ -333,11 +333,11 @@ TEST_P(SceneBroadcasterTest, DeletedTopic) TEST_P(SceneBroadcasterTest, SpawnedModel) { // Start server - gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); @@ -403,11 +403,11 @@ TEST_P(SceneBroadcasterTest, SpawnedModel) TEST_P(SceneBroadcasterTest, State) { // Start server - gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_EQ(16u, *server.EntityCount()); @@ -514,11 +514,11 @@ TEST_P(SceneBroadcasterTest, State) TEST_P(SceneBroadcasterTest, StateStatic) { // Start server - gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/empty.sdf"); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_EQ(8u, *server.EntityCount()); diff --git a/test/integration/sdf_frame_semantics.cc b/test/integration/sdf_frame_semantics.cc index d8ac4ccdf0..f1076dd089 100644 --- a/test/integration/sdf_frame_semantics.cc +++ b/test/integration/sdf_frame_semantics.cc @@ -22,30 +22,30 @@ #include #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/EventManager.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/SdfEntityCreator.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/Types.hh" -#include "ignition/gazebo/test_config.hh" - -#include "ignition/gazebo/components/Collision.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/ParentEntity.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/World.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/EventManager.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/SdfEntityCreator.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/Types.hh" +#include "gz/sim/test_config.hh" + +#include "gz/sim/components/Collision.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/ParentEntity.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; class SdfFrameSemanticsTest : public InternalFixture<::testing::Test> { diff --git a/test/integration/sdf_include.cc b/test/integration/sdf_include.cc index 3e9eea8005..4590bddccf 100644 --- a/test/integration/sdf_include.cc +++ b/test/integration/sdf_include.cc @@ -17,15 +17,15 @@ #include #include -#include -#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include +#include +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; class SdfInclude : public InternalFixture<::testing::Test> { diff --git a/test/integration/sensors_system.cc b/test/integration/sensors_system.cc index 29cb445733..e0dd0e0fe4 100644 --- a/test/integration/sensors_system.cc +++ b/test/integration/sensors_system.cc @@ -24,27 +24,27 @@ #include #include -#include -#include +#include +#include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/EventManager.hh" -#include "ignition/gazebo/SdfEntityCreator.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/Types.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/EventManager.hh" +#include "gz/sim/SdfEntityCreator.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/Types.hh" +#include "gz/sim/test_config.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/World.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/World.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; +using namespace gz; using namespace std::chrono_literals; -namespace components = ignition::gazebo::components; +namespace components = gz::sim::components; ////////////////////////////////////////////////// class SensorsFixture : public InternalFixture> @@ -54,18 +54,18 @@ class SensorsFixture : public InternalFixture> InternalFixture::SetUp(); auto plugin = sm.LoadPlugin("libMockSystem.so", - "ignition::gazebo::MockSystem", + "gz::sim::MockSystem", nullptr); EXPECT_TRUE(plugin.has_value()); this->systemPtr = plugin.value(); - this->mockSystem = static_cast( - systemPtr->QueryInterface()); + this->mockSystem = static_cast( + systemPtr->QueryInterface()); } - public: gazebo::SystemPluginPtr systemPtr; - public: gazebo::MockSystem *mockSystem; + public: gz::sim::SystemPluginPtr systemPtr; + public: gz::sim::MockSystem *mockSystem; - private: gazebo::SystemLoader sm; + private: gz::sim::SystemLoader sm; }; ////////////////////////////////////////////////// @@ -113,7 +113,7 @@ void testDefaultTopics() /// are removed and then added back TEST_F(SensorsFixture, IGN_UTILS_TEST_DISABLED_ON_MAC(HandleRemovedEntities)) { - gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; const std::string sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/sensor.sdf"; @@ -125,12 +125,12 @@ TEST_F(SensorsFixture, IGN_UTILS_TEST_DISABLED_ON_MAC(HandleRemovedEntities)) const sdf::World *sdfWorld = root.WorldByIndex(0); const sdf::Model *sdfModel = sdfWorld->ModelByIndex(0); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); // A pointer to the ecm. This will be valid once we run the mock system - gazebo::EntityComponentManager *ecm = nullptr; + gz::sim::EntityComponentManager *ecm = nullptr; this->mockSystem->preUpdateCallback = - [&ecm](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&ecm](const gz::sim::UpdateInfo &, gz::sim::EntityComponentManager &_ecm) { ecm = &_ecm; }; @@ -143,8 +143,8 @@ TEST_F(SensorsFixture, IGN_UTILS_TEST_DISABLED_ON_MAC(HandleRemovedEntities)) // We won't use the event manager but it's required to create an // SdfEntityCreator - gazebo::EventManager dummyEventMgr; - gazebo::SdfEntityCreator creator(*ecm, dummyEventMgr); + gz::sim::EventManager dummyEventMgr; + gz::sim::SdfEntityCreator creator(*ecm, dummyEventMgr); unsigned int runs = 100; unsigned int runIterations = 2; @@ -153,7 +153,7 @@ TEST_F(SensorsFixture, IGN_UTILS_TEST_DISABLED_ON_MAC(HandleRemovedEntities)) { auto modelEntity = ecm->EntityByComponents( components::Model(), components::Name(sdfModel->Name())); - EXPECT_NE(gazebo::kNullEntity, modelEntity); + EXPECT_NE(gz::sim::kNullEntity, modelEntity); // Remove the first model in the world creator.RequestRemoveEntity(modelEntity, true); @@ -166,7 +166,7 @@ TEST_F(SensorsFixture, IGN_UTILS_TEST_DISABLED_ON_MAC(HandleRemovedEntities)) components::Name(sdfModel->Name())); // Since the model is removed, we should get a null entity - EXPECT_EQ(gazebo::kNullEntity, modelEntity); + EXPECT_EQ(gz::sim::kNullEntity, modelEntity); } // Create the model again @@ -181,7 +181,7 @@ TEST_F(SensorsFixture, IGN_UTILS_TEST_DISABLED_ON_MAC(HandleRemovedEntities)) { auto modelEntity = ecm->EntityByComponents(components::Model(), components::Name(sdfModel->Name())); - EXPECT_NE(gazebo::kNullEntity, modelEntity); + EXPECT_NE(gz::sim::kNullEntity, modelEntity); } } } diff --git a/test/integration/thermal_system.cc b/test/integration/thermal_system.cc index f7d5f0a0df..b20de5034a 100644 --- a/test/integration/thermal_system.cc +++ b/test/integration/thermal_system.cc @@ -16,25 +16,25 @@ */ #include -#include -#include -#include -#include +#include +#include +#include +#include -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Temperature.hh" -#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/components/Name.hh" +#include "gz/sim/components/Temperature.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" #define tol 10e-4 -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test Thermal system class ThermalTest : public InternalFixture<::testing::Test> diff --git a/test/integration/touch_plugin.cc b/test/integration/touch_plugin.cc index f74e8972a9..2187922a29 100644 --- a/test/integration/touch_plugin.cc +++ b/test/integration/touch_plugin.cc @@ -16,18 +16,18 @@ */ #include -#include -#include -#include -#include +#include +#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test TouchPlugin system class TouchPluginTest : public InternalFixture<::testing::Test> @@ -249,7 +249,7 @@ TEST_F(TouchPluginTest, SpawnedEntities) + name="gz::sim::systems::TouchPlugin"> green_box_for_white white_touches_only_green diff --git a/test/integration/tracked_vehicle_system.cc b/test/integration/tracked_vehicle_system.cc index 5bfb76c2d9..418f57a0f3 100644 --- a/test/integration/tracked_vehicle_system.cc +++ b/test/integration/tracked_vehicle_system.cc @@ -16,34 +16,34 @@ */ #include -#include -#include -#include -#include -#include -#include -#include "ignition/gazebo/components/PhysicsEnginePlugin.hh" -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include +#include +#include "gz/sim/components/PhysicsEnginePlugin.hh" +#include +#include +#include +#include +#include +#include + +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" #define tol 10e-4 -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; #define EXPECT_ANGLE_NEAR(a1, a2, tol) \ diff --git a/test/integration/triggered_publisher.cc b/test/integration/triggered_publisher.cc index 70201336ed..671492cdb7 100644 --- a/test/integration/triggered_publisher.cc +++ b/test/integration/triggered_publisher.cc @@ -17,29 +17,29 @@ #include -#include -#include -#include +#include +#include +#include #include #include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; class TriggeredPublisherTest : public InternalFixture<::testing::Test> diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index 2bbab80fc2..fd94fd0a80 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -17,29 +17,29 @@ #include -#include - -#include -#include -#include -#include - -#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/Physics.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include + +#include +#include +#include +#include + +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Physics.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ////////////////////////////////////////////////// class UserCommandsTest : public InternalFixture<::testing::Test> diff --git a/test/integration/velocity_control_system.cc b/test/integration/velocity_control_system.cc index 1482d261ca..1700fd21dd 100644 --- a/test/integration/velocity_control_system.cc +++ b/test/integration/velocity_control_system.cc @@ -16,25 +16,25 @@ */ #include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include + +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; using namespace std::chrono_literals; /// \brief Test VelocityControl system diff --git a/test/integration/wheel_slip.cc b/test/integration/wheel_slip.cc index 4e3daeee72..b56a9221ef 100644 --- a/test/integration/wheel_slip.cc +++ b/test/integration/wheel_slip.cc @@ -17,42 +17,42 @@ #include -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include #include #include -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/Geometry.hh" -#include "ignition/gazebo/components/Gravity.hh" -#include "ignition/gazebo/components/Inertial.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointVelocity.hh" -#include "ignition/gazebo/components/JointVelocityCmd.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/LinearVelocity.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/SlipComplianceCmd.hh" -#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/components/Collision.hh" +#include "gz/sim/components/Geometry.hh" +#include "gz/sim/components/Gravity.hh" +#include "gz/sim/components/Inertial.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointVelocity.hh" +#include "gz/sim/components/JointVelocityCmd.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/LinearVelocity.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/SlipComplianceCmd.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test DiffDrive system class WheelSlipTest : public InternalFixture<::testing::Test> diff --git a/test/integration/wind_effects.cc b/test/integration/wind_effects.cc index 2190994474..3ce96b091e 100644 --- a/test/integration/wind_effects.cc +++ b/test/integration/wind_effects.cc @@ -16,28 +16,28 @@ */ #include -#include -#include -#include -#include - -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" - -#include "ignition/gazebo/components/LinearAcceleration.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/WindMode.hh" +#include +#include +#include +#include + +#include "gz/sim/Link.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" + +#include "gz/sim/components/LinearAcceleration.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/WindMode.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; /// \brief Test WindEffects system class WindEffectsTest : public InternalFixture<::testing::Test> @@ -70,7 +70,7 @@ class LinkComponentRecorder : linkName(std::move(_linkName)) { auto plugin = loader.LoadPlugin("libMockSystem.so", - "ignition::gazebo::MockSystem", nullptr); + "gz::sim::MockSystem", nullptr); EXPECT_TRUE(plugin.has_value()); this->systemPtr = plugin.value(); diff --git a/test/integration/world.cc b/test/integration/world.cc index 9657d53eb7..fdff97719d 100644 --- a/test/integration/world.cc +++ b/test/integration/world.cc @@ -19,31 +19,31 @@ #include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include "../helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; class WorldIntegrationTest : public InternalFixture<::testing::Test> { diff --git a/test/performance/each.cc b/test/performance/each.cc index d67f343ac1..8c9fb006d0 100644 --- a/test/performance/each.cc +++ b/test/performance/each.cc @@ -17,15 +17,15 @@ #include -#include +#include -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/components/Name.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/components/Name.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; void warmstart() { diff --git a/test/performance/level_manager.cc b/test/performance/level_manager.cc index 2a55f3ffd2..6361511669 100644 --- a/test/performance/level_manager.cc +++ b/test/performance/level_manager.cc @@ -19,16 +19,16 @@ #include #include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; TEST(LevelManagerPerfrormance, LevelVsNoLevel) { diff --git a/test/performance/sdf_runner.cc b/test/performance/sdf_runner.cc index 5262971cb7..febaaaaeb1 100644 --- a/test/performance/sdf_runner.cc +++ b/test/performance/sdf_runner.cc @@ -18,17 +18,17 @@ #include #include -#include -#include +#include +#include -#include "ignition/transport/Node.hh" +#include "gz/transport/Node.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ////////////////////////////////////////////////// int main(int _argc, char** _argv) diff --git a/test/plugins/EventTriggerSystem.cc b/test/plugins/EventTriggerSystem.cc index 029988eb16..c2f4d9b17c 100644 --- a/test/plugins/EventTriggerSystem.cc +++ b/test/plugins/EventTriggerSystem.cc @@ -1,9 +1,14 @@ #include "EventTriggerSystem.hh" -#include +#include +#include -IGNITION_ADD_PLUGIN(ignition::gazebo::EventTriggerSystem, - ignition::gazebo::System, - ignition::gazebo::EventTriggerSystem::ISystemConfigure, - ignition::gazebo::EventTriggerSystem::ISystemUpdate) +using namespace gz; +using namespace gz::sim; +IGNITION_ADD_PLUGIN(EventTriggerSystem, + System, + EventTriggerSystem::ISystemConfigure, + EventTriggerSystem::ISystemUpdate) + +IGNITION_ADD_PLUGIN_ALIAS(EventTriggerSystem, "gz::sim::EventTriggerSystem") diff --git a/test/plugins/EventTriggerSystem.hh b/test/plugins/EventTriggerSystem.hh index 4ad37f592c..f3d21a2569 100644 --- a/test/plugins/EventTriggerSystem.hh +++ b/test/plugins/EventTriggerSystem.hh @@ -14,21 +14,21 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_TEST_EVENTTRIGGERSYSTEM_HH_ -#define IGNITION_GAZEBO_TEST_EVENTTRIGGERSYSTEM_HH_ +#ifndef GZ_GAZEBO_TEST_EVENTTRIGGERSYSTEM_HH_ +#define GZ_GAZEBO_TEST_EVENTTRIGGERSYSTEM_HH_ -#include -#include "ignition/gazebo/Events.hh" -#include "ignition/gazebo/System.hh" +#include +#include "gz/sim/Events.hh" +#include "gz/sim/System.hh" namespace ignition { namespace gazebo { class IGNITION_GAZEBO_VISIBLE EventTriggerSystem : - public gazebo::System, - public gazebo::ISystemConfigure, - public gazebo::ISystemUpdate + public gz::sim::System, + public gz::sim::ISystemConfigure, + public gz::sim::ISystemUpdate { // needed for linter public: EventTriggerSystem() = default; diff --git a/test/plugins/MockSystem.cc b/test/plugins/MockSystem.cc index d7602c5c38..42a0ad32b2 100644 --- a/test/plugins/MockSystem.cc +++ b/test/plugins/MockSystem.cc @@ -1,10 +1,15 @@ #include "MockSystem.hh" -#include +#include +#include -IGNITION_ADD_PLUGIN(ignition::gazebo::MockSystem, ignition::gazebo::System, - ignition::gazebo::MockSystem::ISystemConfigure, - ignition::gazebo::MockSystem::ISystemPreUpdate, - ignition::gazebo::MockSystem::ISystemUpdate, - ignition::gazebo::MockSystem::ISystemPostUpdate) +using namespace gz; +using namespace gz::sim; +IGNITION_ADD_PLUGIN(MockSystem, System, + MockSystem::ISystemConfigure, + MockSystem::ISystemPreUpdate, + MockSystem::ISystemUpdate, + MockSystem::ISystemPostUpdate) + +IGNITION_ADD_PLUGIN_ALIAS(MockSystem, "gz::sim::MockSystem") diff --git a/test/plugins/MockSystem.hh b/test/plugins/MockSystem.hh index d6c3df31cb..9c0ad7c5da 100644 --- a/test/plugins/MockSystem.hh +++ b/test/plugins/MockSystem.hh @@ -14,21 +14,21 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_TEST_MOCKSYSTEM_HH_ -#define IGNITION_GAZEBO_TEST_MOCKSYSTEM_HH_ +#ifndef GZ_GAZEBO_TEST_MOCKSYSTEM_HH_ +#define GZ_GAZEBO_TEST_MOCKSYSTEM_HH_ #include -#include "ignition/gazebo/System.hh" +#include "gz/sim/System.hh" namespace ignition { namespace gazebo { class IGNITION_GAZEBO_VISIBLE MockSystem : - public gazebo::System, - public gazebo::ISystemConfigure, - public gazebo::ISystemPreUpdate, - public gazebo::ISystemUpdate, - public gazebo::ISystemPostUpdate + public gz::sim::System, + public gz::sim::ISystemConfigure, + public gz::sim::ISystemPreUpdate, + public gz::sim::ISystemUpdate, + public gz::sim::ISystemPostUpdate { public: size_t configureCallCount {0}; public: size_t preUpdateCallCount {0}; @@ -36,11 +36,11 @@ namespace ignition { public: size_t postUpdateCallCount {0}; public: using CallbackType = std::function; + const gz::sim::UpdateInfo &, gz::sim::EntityComponentManager &)>; public: using CallbackTypeConst = - std::function; + std::function; public: std::function &, @@ -61,24 +61,24 @@ namespace ignition { this->configureCallback(_entity, _sdf, _ecm, _eventMgr); } - public: void PreUpdate(const gazebo::UpdateInfo &_info, - gazebo::EntityComponentManager &_ecm) override final + public: void PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override final { ++this->preUpdateCallCount; if (this->preUpdateCallback) this->preUpdateCallback(_info, _ecm); } - public: void Update(const gazebo::UpdateInfo &_info, - gazebo::EntityComponentManager &_ecm) override final + public: void Update(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override final { ++this->updateCallCount; if (this->updateCallback) this->updateCallback(_info, _ecm); } - public: void PostUpdate(const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) override final + public: void PostUpdate(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) override final { ++this->postUpdateCallCount; if (this->postUpdateCallback) diff --git a/test/plugins/Null.cc b/test/plugins/Null.cc index 41cb503e29..85c051e003 100644 --- a/test/plugins/Null.cc +++ b/test/plugins/Null.cc @@ -15,7 +15,7 @@ * */ #include "Null.hh" -#include +#include using namespace ignition::gazebo::systems; @@ -55,10 +55,13 @@ void Null::PostUpdate(const UpdateInfo &/*_info*/, } IGNITION_ADD_PLUGIN(Null, - ignition::gazebo::System, + gz::sim::System, Null::ISystemConfigure, Null::ISystemPreUpdate, Null::ISystemUpdate, Null::ISystemPostUpdate) +IGNITION_ADD_PLUGIN_ALIAS(Null, "gz::sim::systems::Null") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(Null, "ignition::gazebo::systems::Null") diff --git a/test/plugins/Null.hh b/test/plugins/Null.hh index d26f2dcd40..f40061ce59 100644 --- a/test/plugins/Null.hh +++ b/test/plugins/Null.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_NULL_SYSTEM_HH_ -#define IGNITION_GAZEBO_NULL_SYSTEM_HH_ +#ifndef GZ_GAZEBO_NULL_SYSTEM_HH_ +#define GZ_GAZEBO_NULL_SYSTEM_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/test/plugins/TestModelSystem.cc b/test/plugins/TestModelSystem.cc index cb80403eff..5f08e5a8c4 100644 --- a/test/plugins/TestModelSystem.cc +++ b/test/plugins/TestModelSystem.cc @@ -16,9 +16,14 @@ */ #include "TestModelSystem.hh" -#include +#include +#include -IGNITION_ADD_PLUGIN(ignition::gazebo::TestModelSystem, - ignition::gazebo::System, - ignition::gazebo::TestModelSystem::ISystemConfigure) +using namespace gz; +using namespace gz::sim; +IGNITION_ADD_PLUGIN(TestModelSystem, + System, + TestModelSystem::ISystemConfigure) + +IGNITION_ADD_PLUGIN_ALIAS(TestModelSystem, "gz::sim::TestModelSystem") diff --git a/test/plugins/TestModelSystem.hh b/test/plugins/TestModelSystem.hh index e87fd1624f..8a11f39024 100644 --- a/test/plugins/TestModelSystem.hh +++ b/test/plugins/TestModelSystem.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_TEST_TESTMODELSYSTEM_HH_ -#define IGNITION_GAZEBO_TEST_TESTMODELSYSTEM_HH_ +#ifndef GZ_GAZEBO_TEST_TESTMODELSYSTEM_HH_ +#define GZ_GAZEBO_TEST_TESTMODELSYSTEM_HH_ -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include namespace ignition { diff --git a/test/plugins/TestSensorSystem.cc b/test/plugins/TestSensorSystem.cc index a4a63869ef..8e55ecdab5 100644 --- a/test/plugins/TestSensorSystem.cc +++ b/test/plugins/TestSensorSystem.cc @@ -16,9 +16,14 @@ */ #include "TestSensorSystem.hh" -#include +#include +#include -IGNITION_ADD_PLUGIN(ignition::gazebo::TestSensorSystem, - ignition::gazebo::System, - ignition::gazebo::TestSensorSystem::ISystemConfigure) +using namespace gz; +using namespace gz::sim; +IGNITION_ADD_PLUGIN(TestSensorSystem, + System, + TestSensorSystem::ISystemConfigure) + +IGNITION_ADD_PLUGIN_ALIAS(TestSensorSystem, "gz::sim::TestSensorSystem") diff --git a/test/plugins/TestSensorSystem.hh b/test/plugins/TestSensorSystem.hh index dcfc654e3d..ef37fd7b13 100644 --- a/test/plugins/TestSensorSystem.hh +++ b/test/plugins/TestSensorSystem.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_TEST_TESTSENSORSYSTEM_HH_ -#define IGNITION_GAZEBO_TEST_TESTSENSORSYSTEM_HH_ +#ifndef GZ_GAZEBO_TEST_TESTSENSORSYSTEM_HH_ +#define GZ_GAZEBO_TEST_TESTSENSORSYSTEM_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { diff --git a/test/plugins/TestSystem.cc b/test/plugins/TestSystem.cc index 2c362db0b8..1197e2e1bf 100644 --- a/test/plugins/TestSystem.cc +++ b/test/plugins/TestSystem.cc @@ -17,10 +17,10 @@ #include "TestSystem.hh" -#include +#include -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace gz::sim; ///////////////////////////////////////////////// TestSystem::TestSystem() @@ -34,4 +34,7 @@ TestSystem::~TestSystem() = default; // Register this plugin IGNITION_ADD_PLUGIN(TestSystem, System) +IGNITION_ADD_PLUGIN_ALIAS(TestSystem, "gz::sim::TestSystem") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(TestSystem, "ignition::gazebo::TestSystem") diff --git a/test/plugins/TestSystem.hh b/test/plugins/TestSystem.hh index f675d21321..ae088759cb 100644 --- a/test/plugins/TestSystem.hh +++ b/test/plugins/TestSystem.hh @@ -14,11 +14,11 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_TEST_TESTSYSTEM_HH_ -#define IGNITION_GAZEBO_TEST_TESTSYSTEM_HH_ +#ifndef GZ_GAZEBO_TEST_TESTSYSTEM_HH_ +#define GZ_GAZEBO_TEST_TESTSYSTEM_HH_ -#include -#include +#include +#include namespace ignition { diff --git a/test/plugins/TestWorldSystem.cc b/test/plugins/TestWorldSystem.cc index fcfc7280a1..d925f3b235 100644 --- a/test/plugins/TestWorldSystem.cc +++ b/test/plugins/TestWorldSystem.cc @@ -16,10 +16,15 @@ */ #include "TestWorldSystem.hh" -#include +#include +#include -IGNITION_ADD_PLUGIN(ignition::gazebo::TestWorldSystem, - ignition::gazebo::System, - ignition::gazebo::TestWorldSystem::ISystemConfigure, - ignition::gazebo::TestWorldSystem::ISystemUpdate) +using namespace gz; +using namespace gz::sim; +IGNITION_ADD_PLUGIN(TestWorldSystem, + System, + TestWorldSystem::ISystemConfigure, + TestWorldSystem::ISystemUpdate) + +IGNITION_ADD_PLUGIN_ALIAS(TestWorldSystem, "gz::sim::TestWorldSystem") diff --git a/test/plugins/TestWorldSystem.hh b/test/plugins/TestWorldSystem.hh index bed1e9c9ad..d61f8259c6 100644 --- a/test/plugins/TestWorldSystem.hh +++ b/test/plugins/TestWorldSystem.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_TEST_TESTWORLDSYSTEM_HH_ -#define IGNITION_GAZEBO_TEST_TESTWORLDSYSTEM_HH_ +#ifndef GZ_GAZEBO_TEST_TESTWORLDSYSTEM_HH_ +#define GZ_GAZEBO_TEST_TESTWORLDSYSTEM_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { @@ -61,7 +61,7 @@ class TestWorldSystem : components::WorldPluginComponent(value)); } - public: void Update(const gazebo::UpdateInfo &_info, + public: void Update(const gz::sim::UpdateInfo &_info, EntityComponentManager &) override { std::cout << "iteration " << _info.iterations << std::endl; diff --git a/test/test_config.hh.in b/test/test_config.hh.in index e80b8c4440..241e3e25d7 100644 --- a/test/test_config.hh.in +++ b/test/test_config.hh.in @@ -14,11 +14,11 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_TEST_CONFIG_HH_ -#define IGNITION_GAZEBO_TEST_CONFIG_HH_ +#ifndef GZ_GAZEBO_TEST_CONFIG_HH_ +#define GZ_GAZEBO_TEST_CONFIG_HH_ #include -#include +#include #define PROJECT_SOURCE_PATH "${PROJECT_SOURCE_DIR}" #define PROJECT_BINARY_PATH "${CMAKE_BINARY_DIR}" @@ -50,12 +50,12 @@ struct TestWorldSansPhysics "" "" + " name='gz::sim::systems::SceneBroadcaster'>" "" "" + " name='gz::sim::systems::UserCommands'>" "" "" ""; diff --git a/test/worlds/ackermann_steering.sdf b/test/worlds/ackermann_steering.sdf index f93f0750e0..43c0636703 100644 --- a/test/worlds/ackermann_steering.sdf +++ b/test/worlds/ackermann_steering.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::Physics"> @@ -369,7 +369,7 @@ + name="gz::sim::systems::AckermannSteering"> front_left_wheel_joint rear_left_wheel_joint front_right_wheel_joint diff --git a/test/worlds/ackermann_steering_custom_frame_id.sdf b/test/worlds/ackermann_steering_custom_frame_id.sdf index 0ea704d323..5e1175267a 100644 --- a/test/worlds/ackermann_steering_custom_frame_id.sdf +++ b/test/worlds/ackermann_steering_custom_frame_id.sdf @@ -8,15 +8,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -413,7 +413,7 @@ + name="gz::sim::systems::AckermannSteering"> front_left_wheel_joint rear_left_wheel_joint front_right_wheel_joint diff --git a/test/worlds/ackermann_steering_custom_topics.sdf b/test/worlds/ackermann_steering_custom_topics.sdf index d86dbc3cfe..a4eb596a3d 100644 --- a/test/worlds/ackermann_steering_custom_topics.sdf +++ b/test/worlds/ackermann_steering_custom_topics.sdf @@ -8,15 +8,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -413,7 +413,7 @@ + name="gz::sim::systems::AckermannSteering"> front_left_wheel_joint rear_left_wheel_joint front_right_wheel_joint diff --git a/test/worlds/ackermann_steering_limited_joints_pub.sdf b/test/worlds/ackermann_steering_limited_joints_pub.sdf index 7e29c8f173..ca2c408418 100644 --- a/test/worlds/ackermann_steering_limited_joints_pub.sdf +++ b/test/worlds/ackermann_steering_limited_joints_pub.sdf @@ -8,15 +8,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -413,7 +413,7 @@ + name="gz::sim::systems::AckermannSteering"> front_left_wheel_joint rear_left_wheel_joint front_right_wheel_joint @@ -433,7 +433,7 @@ + name="gz::sim::systems::JointStatePublisher"> left_wheel_joint right_wheel_joint diff --git a/test/worlds/ackermann_steering_slow_odom.sdf b/test/worlds/ackermann_steering_slow_odom.sdf index 725d387dd0..099f7a097a 100644 --- a/test/worlds/ackermann_steering_slow_odom.sdf +++ b/test/worlds/ackermann_steering_slow_odom.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::Physics"> @@ -369,7 +369,7 @@ + name="gz::sim::systems::AckermannSteering"> front_left_wheel_joint rear_left_wheel_joint front_right_wheel_joint diff --git a/test/worlds/air_pressure.sdf b/test/worlds/air_pressure.sdf index d61a95aac3..3687457cfc 100644 --- a/test/worlds/air_pressure.sdf +++ b/test/worlds/air_pressure.sdf @@ -7,7 +7,7 @@ + name="gz::sim::systems::AirPressure"> diff --git a/test/worlds/altimeter.sdf b/test/worlds/altimeter.sdf index 7e93238220..12813a9ca9 100644 --- a/test/worlds/altimeter.sdf +++ b/test/worlds/altimeter.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Altimeter"> @@ -76,7 +76,7 @@ + name="gz::sim::systems::KineticEnergyMonitor"> link 2 diff --git a/test/worlds/altimeter_with_pose.sdf b/test/worlds/altimeter_with_pose.sdf index b008b5d453..ae96682e14 100644 --- a/test/worlds/altimeter_with_pose.sdf +++ b/test/worlds/altimeter_with_pose.sdf @@ -7,15 +7,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Altimeter"> + name="gz::sim::systems::SceneBroadcaster"> @@ -81,7 +81,7 @@ + name="gz::sim::systems::KineticEnergyMonitor"> link 2 diff --git a/test/worlds/apply_joint_force.sdf b/test/worlds/apply_joint_force.sdf index e9943f8016..5c61efdc06 100644 --- a/test/worlds/apply_joint_force.sdf +++ b/test/worlds/apply_joint_force.sdf @@ -7,7 +7,7 @@ + name="gz::sim::systems::Physics"> @@ -108,7 +108,7 @@ + name="gz::sim::systems::ApplyJointForce"> j1 diff --git a/test/worlds/apply_link_wrench.sdf b/test/worlds/apply_link_wrench.sdf index fadb21f284..72076c1df5 100644 --- a/test/worlds/apply_link_wrench.sdf +++ b/test/worlds/apply_link_wrench.sdf @@ -5,11 +5,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::ApplyLinkWrench"> model1 model diff --git a/test/worlds/battery.sdf b/test/worlds/battery.sdf index 3e5ea846a8..67b51e2758 100644 --- a/test/worlds/battery.sdf +++ b/test/worlds/battery.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -43,7 +43,7 @@ + name="gz::sim::systems::LinearBatteryPlugin"> linear_battery 12.592 12.694 diff --git a/test/worlds/benchmark.sdf.erb b/test/worlds/benchmark.sdf.erb index 025580c270..2445a59e82 100644 --- a/test/worlds/benchmark.sdf.erb +++ b/test/worlds/benchmark.sdf.erb @@ -218,11 +218,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -477,7 +477,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint right_wheel_joint 1.25 @@ -487,7 +487,7 @@ <% end %> - + <% vehicles.each do |vehicle| %> <%= vehicle[:name] %> diff --git a/test/worlds/breadcrumbs.sdf b/test/worlds/breadcrumbs.sdf index bbc2bac8e6..f5af549047 100644 --- a/test/worlds/breadcrumbs.sdf +++ b/test/worlds/breadcrumbs.sdf @@ -8,15 +8,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -378,7 +378,7 @@ + name="gz::sim::systems::DiffDrive"> front_left_wheel_joint rear_left_wheel_joint front_right_wheel_joint @@ -386,7 +386,7 @@ 1.25 0.3 - + 3 @@ -428,7 +428,7 @@ - + 3 0.5 @@ -472,7 +472,7 @@ - + -1 /fuel_deploy @@ -488,7 +488,7 @@ - + 3 @@ -538,7 +538,7 @@ - + 3 @@ -589,7 +589,7 @@ - + 3 false /no_rename_deploy @@ -614,7 +614,7 @@ - + 3 true /rename_deploy @@ -640,7 +640,7 @@ - + vehicle_blue diff --git a/test/worlds/breadcrumbs_levels.sdf b/test/worlds/breadcrumbs_levels.sdf index a8b9fde158..be93c60e40 100644 --- a/test/worlds/breadcrumbs_levels.sdf +++ b/test/worlds/breadcrumbs_levels.sdf @@ -8,15 +8,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -43,7 +43,7 @@ - + 3 15 true @@ -94,7 +94,7 @@ - + sphere diff --git a/test/worlds/buoyancy.sdf.in b/test/worlds/buoyancy.sdf.in index 56673ff773..7f671d273d 100644 --- a/test/worlds/buoyancy.sdf.in +++ b/test/worlds/buoyancy.sdf.in @@ -8,20 +8,20 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Buoyancy"> 1000 diff --git a/test/worlds/camera_sensor_empty_scene.sdf b/test/worlds/camera_sensor_empty_scene.sdf index 013cced7a1..a429a46553 100644 --- a/test/worlds/camera_sensor_empty_scene.sdf +++ b/test/worlds/camera_sensor_empty_scene.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre2 1 0 0 1 diff --git a/test/worlds/camera_video_record.sdf b/test/worlds/camera_video_record.sdf index 9465521888..265296726a 100644 --- a/test/worlds/camera_video_record.sdf +++ b/test/worlds/camera_video_record.sdf @@ -9,19 +9,19 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Sensors"> ogre2 @@ -298,7 +298,7 @@ + name="gz::sim::systems::CameraVideoRecorder"> camera/record_video diff --git a/test/worlds/canonical.sdf b/test/worlds/canonical.sdf index 145c958809..eebff0acd5 100644 --- a/test/worlds/canonical.sdf +++ b/test/worlds/canonical.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/center_of_volume.sdf b/test/worlds/center_of_volume.sdf index 0972ca554d..f2511e7706 100644 --- a/test/worlds/center_of_volume.sdf +++ b/test/worlds/center_of_volume.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Buoyancy"> 1000 diff --git a/test/worlds/collada_world_exporter.sdf b/test/worlds/collada_world_exporter.sdf index 01f7ea7da4..b422b1095b 100644 --- a/test/worlds/collada_world_exporter.sdf +++ b/test/worlds/collada_world_exporter.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::ColladaWorldExporter"> diff --git a/test/worlds/contact.sdf b/test/worlds/contact.sdf index 10c4afb1da..223347189c 100644 --- a/test/worlds/contact.sdf +++ b/test/worlds/contact.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Contact"> diff --git a/test/worlds/conveyor.sdf b/test/worlds/conveyor.sdf index f33ba10c3f..ebe6784421 100644 --- a/test/worlds/conveyor.sdf +++ b/test/worlds/conveyor.sdf @@ -10,15 +10,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -140,7 +140,7 @@ + name="gz::sim::systems::TrackController"> base_link 2.0 0.5 diff --git a/test/worlds/demo_joint_types.sdf b/test/worlds/demo_joint_types.sdf index 31058e5d98..4913e912f7 100644 --- a/test/worlds/demo_joint_types.sdf +++ b/test/worlds/demo_joint_types.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/depth_camera_sensor.sdf b/test/worlds/depth_camera_sensor.sdf index 7791ad3dbc..658af7855e 100644 --- a/test/worlds/depth_camera_sensor.sdf +++ b/test/worlds/depth_camera_sensor.sdf @@ -11,11 +11,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre2 diff --git a/test/worlds/detachable_joint.sdf b/test/worlds/detachable_joint.sdf index ac3be7c50a..afe0a7efac 100644 --- a/test/worlds/detachable_joint.sdf +++ b/test/worlds/detachable_joint.sdf @@ -6,7 +6,7 @@ + name="gz::sim::systems::Physics"/> true @@ -45,7 +45,7 @@ - + body M2 body @@ -120,7 +120,7 @@ - + body1 __model__ body2 diff --git a/test/worlds/diff_drive.sdf b/test/worlds/diff_drive.sdf index bfd7352a00..08f9b0fcea 100644 --- a/test/worlds/diff_drive.sdf +++ b/test/worlds/diff_drive.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::Physics"> @@ -222,7 +222,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint right_wheel_joint 1.25 @@ -236,7 +236,7 @@ + name="gz::sim::systems::JointStatePublisher"> diff --git a/test/worlds/diff_drive_custom_frame_id.sdf b/test/worlds/diff_drive_custom_frame_id.sdf index 1fdd850ec0..282356cbb2 100644 --- a/test/worlds/diff_drive_custom_frame_id.sdf +++ b/test/worlds/diff_drive_custom_frame_id.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::Physics"> @@ -222,7 +222,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint right_wheel_joint 1.25 @@ -236,7 +236,7 @@ + name="gz::sim::systems::JointStatePublisher"> diff --git a/test/worlds/diff_drive_custom_tf_topic.sdf b/test/worlds/diff_drive_custom_tf_topic.sdf index 03a4091024..4f1bcc077d 100644 --- a/test/worlds/diff_drive_custom_tf_topic.sdf +++ b/test/worlds/diff_drive_custom_tf_topic.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::Physics"> @@ -221,7 +221,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint right_wheel_joint 1.25 @@ -234,7 +234,7 @@ + name="gz::sim::systems::JointStatePublisher"> diff --git a/test/worlds/diff_drive_custom_topics.sdf b/test/worlds/diff_drive_custom_topics.sdf index 06f8080108..c17fdb49bc 100644 --- a/test/worlds/diff_drive_custom_topics.sdf +++ b/test/worlds/diff_drive_custom_topics.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::Physics"> @@ -222,7 +222,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint right_wheel_joint 1.25 diff --git a/test/worlds/diff_drive_limited_joint_pub.sdf b/test/worlds/diff_drive_limited_joint_pub.sdf index 978975105b..20efaf68bd 100644 --- a/test/worlds/diff_drive_limited_joint_pub.sdf +++ b/test/worlds/diff_drive_limited_joint_pub.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::Physics"> @@ -222,7 +222,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint right_wheel_joint 1.25 @@ -234,7 +234,7 @@ + name="gz::sim::systems::JointStatePublisher"> left_wheel_joint right_wheel_joint diff --git a/test/worlds/diff_drive_skid.sdf b/test/worlds/diff_drive_skid.sdf index b4ae8dee22..065d120c80 100644 --- a/test/worlds/diff_drive_skid.sdf +++ b/test/worlds/diff_drive_skid.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::Physics"> @@ -312,7 +312,7 @@ + name="gz::sim::systems::DiffDrive"> front_left_wheel_joint rear_left_wheel_joint front_right_wheel_joint diff --git a/test/worlds/elevator.sdf b/test/worlds/elevator.sdf index 9fcc36902d..86363ef97e 100644 --- a/test/worlds/elevator.sdf +++ b/test/worlds/elevator.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::Physics"> @@ -761,7 +761,7 @@ + name="gz::sim::systems::JointPositionController"> door_0 60 0 @@ -821,7 +821,7 @@ + name="gz::sim::systems::JointPositionController"> door_1 60 0 @@ -881,7 +881,7 @@ + name="gz::sim::systems::JointPositionController"> door_2 60 0 @@ -941,7 +941,7 @@ + name="gz::sim::systems::JointPositionController"> door_3 60 0 @@ -1125,7 +1125,7 @@ + name="gz::sim::systems::JointPositionController"> lift 4000000 2000 @@ -1275,7 +1275,7 @@ + name="gz::sim::systems::Elevator"> diff --git a/test/worlds/empty.sdf b/test/worlds/empty.sdf index d700350605..5d1c943e2e 100644 --- a/test/worlds/empty.sdf +++ b/test/worlds/empty.sdf @@ -7,19 +7,19 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Contact"> diff --git a/test/worlds/event_trigger.sdf b/test/worlds/event_trigger.sdf index a0f4aa5e40..c28e4dc160 100644 --- a/test/worlds/event_trigger.sdf +++ b/test/worlds/event_trigger.sdf @@ -7,7 +7,7 @@ + name="gz::sim::EventTriggerSystem"> diff --git a/test/worlds/falling.sdf b/test/worlds/falling.sdf index cc09166afb..d5ee26492e 100644 --- a/test/worlds/falling.sdf +++ b/test/worlds/falling.sdf @@ -7,7 +7,7 @@ + name="gz::sim::systems::Physics"> diff --git a/test/worlds/friction.sdf b/test/worlds/friction.sdf index 42f4c6da26..b12ee1a339 100644 --- a/test/worlds/friction.sdf +++ b/test/worlds/friction.sdf @@ -7,19 +7,19 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Contact"> diff --git a/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.sdf b/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.sdf new file mode 100644 index 0000000000..b9386ade65 --- /dev/null +++ b/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.sdf @@ -0,0 +1,5 @@ + + + + + diff --git a/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.world b/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.world new file mode 100644 index 0000000000..b9386ade65 --- /dev/null +++ b/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.world @@ -0,0 +1,5 @@ + + + + + diff --git a/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/thumbnails/1.png b/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/thumbnails/1.png new file mode 100644 index 0000000000000000000000000000000000000000..a72d5aa96bff8d0820bac6184f5e3d8370725889 GIT binary patch literal 6279 zcmc(kWmpu^zsCnf=@3y`8WAJ}q(i!-k(83|j-^GULt0vPX;@YomJ&gbTpFoGL_lHz z=~}qseRbd5cmMm`d7d-#%sl7J%sKOm&+j|2+M3EFgtUYJ0FbDvDCmO6Rj_5@-v##@ zQaice0oPkjRUaSRg7Ix)z;gl*6=QDzAnpCva5A__>A;ILK8i*@dhT{U{#IVLfWN;# zucMo@x3!grEw8(meeSL#EdWsCsw&9p2jpRvARY@d`FQ(`_z`6)I>o$`;_x(adiBgT z?xcJTYYEph4##@O`G(0Qmu5kXrauzXG`TeDVwWSuA(1<`dy?!T(H7Q_Z$25zFzc5( z@A`&alTtOa`m&Tw4a%!aLGS@r<<<`wmoah;wJ9s2%+SKFqc5l7c%~LBD>zIsvlby( z$P0W|iD^H7fZ2yA>K^m^FZ?XU8-_yk>W|bp+Yo(yV%%6b&1o!`| z(-vm;%e(3-L{)ngVw+pHwXXWWkc8~HkGpl&ZtDyFPg4Hpi!!Qf)x*_fs626RPl?M0 zJxgklw`)eXhiWg21^PYvFgqyhm&10oPSn#OQaAfBKMMNN|2f;AVz7w6l8A%zkh|~D zUp9S^-wog*6tN#(hL6WWRmgFf?TiF&nKrsLcvAO~wCs<*=L37Me$CV9TzrlRbh$nV zc7+Nny&Dg?nA%jYf{RcRI_50oCi4YQk>WR%&Mqk~5eZIk4cvX%j7mp^> zItYi!kvdn}Nqoge%pyh!Hlt8T6k%z3YZ!;)3%y6HnU-Oe;mwiuQqgGRg}Au1(@i-B z)|G+^@4K&{UVPEUz1W19&9W`JF>I2cj3lFc{WgCT~@{&sb=GR_P3I2JK+>5JKHn(WEvNjWJB+t+{klr1vx#vS-iGAT1(KjnS;Xr#{e zykw2I=T9F;|3R6383S6;-8zOOqYtsIf=wyJi+C&YHRW?DydGog2tkTrd$ta?BB`(h z5#;xIlw+-^MLyLvc-;cR2?V&4L^)uNot4nR?5#j?q(r6Nx?MrWpi^VuUk~hxA%ks_ zCqych?R{k&m;EcnjKftr#^paWJLeKQl+#eoRLl~_0#Q?bEnH-B9=~UHl=BhLdz>-i zxIVK{5WL%X76<^2j*c#Hm|x3`js!74b#eFdgy!h3rg<5Emj@~EMeFj|HQ%*%jaF^d z6eSJ&y+6?>yhXPagahD*n=1Fh@RF}hgUMGJqyt){Pz9&X74%7wm=Vl~fBujL^6{a9 zPJ%{L`opZwe9o9y{a5;8iFa9>{WKaf_!Ab2>znIYdZPx5y-J@SIw?B7=gw$)oSYXN z%{E|LA-P!)EZRxh?->X&F46s)yUB+<1;_M0$5duzajS8o)f?fOW$_<1)^l~m$cgp) zW}nd}ghC+0&;8!qUQ#%{7v-6I=GY~F0girOd^o0GLNi%fTnH)9ve@UX77gR!d%|c~ zpOt>T)=}Obo8PRd)9lIj?F3BGLya08dD-$70H&MGR z7w9iXyb#8PVR8AQ56q!+*?RW8d105qrTzn#Ex}@_!%W-dgV=v<{I8CKlbcD?M;^HC zH{01%GY;9)N2GeqI1HbBKYzP9iQrspl$KMBK?NUV-@p;@o1$^cox9D za~EdUhH5d1Iam(|Y0zc)&|wYcKr6PMZ~V ziUHuNp)19T+RVg+Hb~~OA$LV=mE!}K02iM!Oh=>Am1pzexm0y!O=pd~=}aw&L$z~z zwwv0G5m!94+)txzm$uJ|b0jY0AujV;h*DJ#zgvU>%*=DjvS-IkOPNj2;PuI~?;QHC z-Dd5LGE1612W{I4(U$#Q<7Dh`{#`t|$$~4}ySpB%!182I(1an%^L|}@ouOnn9r0an zU02g4gv+3dK(or43R|l8W^$If$=)4^4mp7gX11U2^gP7hY|BWUpL&s%&y;88o5Jyw zldnq`81oLKVbdvvp;wd77nWl2GR7@`BQM%C!59VrKfmVX>*{sP8P5@f#ja*2aBQ6Y zJ|obfd=3ClhaM&-B|o$?5xksCs4A>Fzmk^sHa+}HW+HtS$V6=!PZZa`R@fDUUD9f7 zXm0-l3vp@U2}**NzuMDqb#$-r)@YL^Yrc8m{M=+Vmi00ErM`c!nC_sL3(gmKTUc-d z$~4_jNR~Xn8fEtrca+0+uC8WecqI5C@PZsS#5?Ga8;l3)l!}m7T(5R$lwjSWf2Xp` zLYdu7KN#{`n7+D%jiN{QVxi@CfqlVic`Agtq@{4SDg2>xm)MA;`xxCvaw>sHIp+H0 zleKYTGYaB63==l$0?fkt;-Ug)BUT&yxpptN1#*X3XMDDcW!*oirvBap@<(y07b5Ie zm>527|2(Ey&)S<{K0qvCu3rlN5Ovjr)a4WKA2JK4dtS!Z?{?mfVT!z%zYx)#6TZb{9(H`Z(cE@lVqoGR z)zi;PINsLyHs5}2bWma->nf*z0(=_1aY}O$by2zgaNVheKkGrFl12olgMK7eHOF*< zIl@0zV|`!(I)Ro9DzJwiE3(|H3v21>mD;Ew#=R8;+AuqQgeGnZ+bbItxWVO1rO5y* zbE^#{cS%d*%$$!oKYF~Xr7047d40?AGqk(9I{jI<7Zd**2hHbS{3pS1pQvK2k|hOS zOi;u+ZLm~GkEtj1o)LUR>1hDfaFMpk;|!t$!u94rI<;skg(@!;QV=0zcAla?TEBrk z*n!#exg7iDGt*n~Y7l)Rd4tT(rgHU{-*kyJh z4iG@qQA%efqB#s%e?$=7a}MR~LlYf*v+p{y?J#H5w8d6!Ztgu{pk@$VEyI#TF!h@M zQA;gee$y2E`jxqF3AEvB;~Zv(vP~c%#i4hn44Vi5FF#aJ-1&PN8AqNrU6@xOsfhO{ z@VxHX?2p`UcfQpR%qM6j2%kAD->YzGGz#l9DMUl|^0l;3FT)J3)wv(XL8A!xeP4!G zc!L-@Z7_2!l#w;~^fJp?&ZV3lcp>k&2<+Eqo@64?MQFrf@GlWN0_f+8=7IxB1TtXl zS3D8={o@xWc#0>jb8WvvuHI#mUAwq=?TFZG7Mx@4nws@?2ECQ4zRj~@hY#B!V`4@h zs@>Qqm~R(_vxc7k=>1WNm@qxz>6f0>&dKfwItjc#4U(rQSP-bEO{Ven;iWLe;H#!e z1LVIh(ig@j|6<9cuYdk=3Q_sTF3_M)ml6XJEyhqLij8IQo5nkPUmr8`#;~bgOglA3 zgF}IE&bZ&{L0d%b9hWnLr%*n!95aZ`Q(n$pnnL>I3^To&oWY5~SOwq9=u3491~{0% zX@QoUat$Wxv8W%~+4>+?1X4`j2F~Os8Ku|E4y1W4>{OfEEzER626Wb`@mh}YiePQl zH=n%sA)6)DP|iv`WxOt{q0b|w2bE&srtSv2e>TrbIpf%5$zNykY^&*n>Zohljkd?> z6FfrnultD6fv&#EX~ko>+!g3I(CnkzIkz*sGj!Z|?5>XZOcdR-1scp&RDKU%B&$_h z&?j`B!9i}+2(fxzi zX>f&Nqnfeu*aruO!S?ockBL|RoRx7+kzVC@b z!qavKeq58|b{iV%clrJPnL>9ENSnwJ*s$WTeO-w)`}diW!Bq2zH2P2&xs?CLkW>!` zc-beRT=jzgCw_Df!43aFbneOPOWO>!2e*Kq5VR1#fOdNM$naG{Fg~~VAUy#JgS~=$9RFStd$?S)laJ?$jSpQ7=(v`2QRHLR+(Jk=zBNoP3Qdiu2Q3aV<8A1 zC%+Zl40dz>%BBm_CM-VI4F2_ebJ?ePq0wr%!LIKsXB@Q2y&NIbsd?p5UtC^136>P9 zwzCb~D-alJFP>-C(bqbbR~D_T9; z@o^1iIQP(l8w8y^*v$nCp{0op_0E#EuPrSNAN#yqYW0P4hY6D7dPY~?=ukH5iY=w1 zGq=1WqDkqIvZ=)uTzK-`gasRV7hO*W`H%%_9mihCyr5z$e&7XCtmFCgcI@AmH6 zX(X6tib~znN_bEEOk~$`Q2-6>^xnN>S$CsZL+^6czN?)zHSyd%9;roz|bfv0+p&U@VzLuOw5t(rbD-uev@x9Ni-;3PZQ)m-U zpvg=K*Q}z;8VsFhB${crmp-YVv)RpT=H}teAahp_4h6G`Wq?b-Hyr_YE%OQfN>yKN zb2~AE+-f(L6bGAcA55yo-L_NML&M~D^7*pV?w}3{+;1;xfa`+;fXYPe7Y{4mFt^ar zTfhrJpQlEx#;x3P8TP0{ZOZ3F9?k&^GK+fvu>UmhjVma8eAii55jTb!Am}qe+T9Mk z7^&NdyD-6=M5Rnr(+f`$yBcd`U`$XKKet5)?I@(>4d-zX_qm&H{Bpdo1A+H&an++1{m)FO!TCC4AhTAnQz+p z5&WCyEWiuT(7)AJ;`X4za7=Q7Q7=KkMNGAZ3S}BT^0-zsv}L&%(7A$lntk}L=#%vi zvAhXv>8R(%X3%UsUVjZ4=pEmJAA5{D2u*5TlBuqBvMwCL8+u3 zW$kfW93yFpSQLV4ungzWq=KX_;`ee@qj98(q-&^Al=Kr*wq3;hjpoGNQyp|cyUbvm zf~oz2g#ybx0ms{b!={7SPy5}gpglWkCE$BKBJVie&5r{=qKXSat2(0@IvIX-cT>pP zWY39=TRn+U{Mv1Cy!L3sAANNKQcqrasDGIMTr`~V`W?Ovb zXPgXN(-wVF+}qO|%hER_QC1YA)lEw-3(JCIhs~!|VQS6Xj74#V#wMFC9doplxXjmb z!8cA8?pCN;e^k(VVSntm{Dz$Q} z_2+toAWIlAA@Hf8+-KU)>(zr-qaJKme4wTi#)ltq@8`^_ae*Sr7!2=@68Q!qexQ07 zrmn7Tt+zCT)qbV3W)m^&yo6m^zNe@|;^F*fufRKORLcMKu!k#yYwB~?iVR-Jv4M5yUBp8lDp=ah^2fBIsfLn)r7+w);92 z`qfgi*9-R2=fgvD*>j!8E*qhaV9gEL8LMUd9$g*#r$KxJ*3XCyO@wi5R(x@jYro#w zMj^~xHx4I5vFSlh$-&vM;b%=Vt;^{_T%g%mZv=qm-ja>yUuIwG`VRIEFEeDQBt?ZS zpDG|fM;}j!Hc>=EunkdKS1K`Hl4+yVuZ*GZ-vj{8IKnIpx9RM$N~Z0TjYvU1lCexH z)AVK97Fr$h*wM~Wwb_O$=H4hTT-mXzX{SQXszb^Rs^;(VqGD3npwdAAgfroL3NDN8 qfBO1Q!WMn0_@Asx{tu+@v#?6*EEdsJA9C=g0idd=sZb+l8S!6Umjes{ literal 0 HcmV?d00001 diff --git a/test/worlds/gpu_lidar_sensor.sdf b/test/worlds/gpu_lidar_sensor.sdf index 463314ebf0..fa943ad4ab 100644 --- a/test/worlds/gpu_lidar_sensor.sdf +++ b/test/worlds/gpu_lidar_sensor.sdf @@ -11,11 +11,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre2 diff --git a/test/worlds/imu.sdf b/test/worlds/imu.sdf index e2983ccb31..25756809ee 100644 --- a/test/worlds/imu.sdf +++ b/test/worlds/imu.sdf @@ -8,11 +8,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Imu"> diff --git a/test/worlds/joint_controller.sdf b/test/worlds/joint_controller.sdf index c16f46af9f..08d9b4331a 100644 --- a/test/worlds/joint_controller.sdf +++ b/test/worlds/joint_controller.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -153,7 +153,7 @@ + name="gz::sim::systems::JointController"> j1 5.0 @@ -231,7 +231,7 @@ + name="gz::sim::systems::JointController"> j1 true 0.2 diff --git a/test/worlds/joint_position_controller.sdf b/test/worlds/joint_position_controller.sdf index cc52a7cea7..58f16d7045 100644 --- a/test/worlds/joint_position_controller.sdf +++ b/test/worlds/joint_position_controller.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -153,7 +153,7 @@ + name="gz::sim::systems::JointPositionController"> j1 1 0.1 diff --git a/test/worlds/level_performance.sdf b/test/worlds/level_performance.sdf index 2ba3d61de0..c90d546474 100644 --- a/test/worlds/level_performance.sdf +++ b/test/worlds/level_performance.sdf @@ -13,11 +13,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -6052,7 +6052,7 @@ - + vehicle_red diff --git a/test/worlds/levels.sdf b/test/worlds/levels.sdf index ce2568ec70..38f0c26bda 100644 --- a/test/worlds/levels.sdf +++ b/test/worlds/levels.sdf @@ -7,7 +7,7 @@ + name="gz::sim::systems::SceneBroadcaster"> @@ -1404,7 +1404,7 @@ - + sphere diff --git a/test/worlds/levels_no_performers.sdf b/test/worlds/levels_no_performers.sdf index a83859439d..5cd3f23bb5 100644 --- a/test/worlds/levels_no_performers.sdf +++ b/test/worlds/levels_no_performers.sdf @@ -7,7 +7,7 @@ + name="gz::sim::systems::SceneBroadcaster"> @@ -1404,7 +1404,7 @@ - + 40 0 2.5 0 0 0 diff --git a/test/worlds/lift_drag.sdf b/test/worlds/lift_drag.sdf index 2ee782834c..e087d0044b 100644 --- a/test/worlds/lift_drag.sdf +++ b/test/worlds/lift_drag.sdf @@ -9,7 +9,7 @@ + name="gz::sim::systems::Physics"> @@ -172,7 +172,7 @@ + name="gz::sim::systems::LiftDrag"> 0.1 4.000 20.0 @@ -190,7 +190,7 @@ + name="gz::sim::systems::LiftDrag"> 0.1 4.000 20.0 diff --git a/test/worlds/lights.sdf b/test/worlds/lights.sdf index 4729965c09..7cbcccc2cd 100644 --- a/test/worlds/lights.sdf +++ b/test/worlds/lights.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/log_playback.sdf b/test/worlds/log_playback.sdf index d9f69e79bd..93ba7030ef 100644 --- a/test/worlds/log_playback.sdf +++ b/test/worlds/log_playback.sdf @@ -6,11 +6,11 @@ + name='gz::sim::systems::SceneBroadcaster'> + name='gz::sim::systems::LogPlayback'> /tmp/log diff --git a/test/worlds/log_record_dbl_pendulum.sdf b/test/worlds/log_record_dbl_pendulum.sdf index 6aa86c0955..6f84085626 100644 --- a/test/worlds/log_record_dbl_pendulum.sdf +++ b/test/worlds/log_record_dbl_pendulum.sdf @@ -14,19 +14,19 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::LogRecord"> diff --git a/test/worlds/log_record_resources.sdf b/test/worlds/log_record_resources.sdf index 2c596b9d9d..ad0849ae51 100644 --- a/test/worlds/log_record_resources.sdf +++ b/test/worlds/log_record_resources.sdf @@ -15,15 +15,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::LogRecord"> diff --git a/test/worlds/logical_audio_sensor_plugin.sdf b/test/worlds/logical_audio_sensor_plugin.sdf index 4bc8537dba..3d50c0fee9 100644 --- a/test/worlds/logical_audio_sensor_plugin.sdf +++ b/test/worlds/logical_audio_sensor_plugin.sdf @@ -11,7 +11,7 @@ + name="gz::sim::systems::LogicalAudioSensorPlugin"> 1 linear @@ -31,7 +31,7 @@ + name="gz::sim::systems::LogicalAudioSensorPlugin"> 2 0.5 0 0 0 0 0 @@ -46,7 +46,7 @@ + name="gz::sim::systems::LogicalAudioSensorPlugin"> 1 diff --git a/test/worlds/logical_audio_sensor_plugin_services.sdf b/test/worlds/logical_audio_sensor_plugin_services.sdf index 47b4ec6fc3..b2ab3cea6f 100644 --- a/test/worlds/logical_audio_sensor_plugin_services.sdf +++ b/test/worlds/logical_audio_sensor_plugin_services.sdf @@ -11,7 +11,7 @@ + name="gz::sim::systems::LogicalAudioSensorPlugin"> 1 0 0 0 0 0 0 @@ -32,7 +32,7 @@ + name="gz::sim::systems::LogicalAudioSensorPlugin"> 2 0 0 0 0 0 0 diff --git a/test/worlds/logical_camera_sensor.sdf b/test/worlds/logical_camera_sensor.sdf index 9ec9feeaed..7af2fc0b60 100644 --- a/test/worlds/logical_camera_sensor.sdf +++ b/test/worlds/logical_camera_sensor.sdf @@ -8,11 +8,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::LogicalCamera"> ogre2 diff --git a/test/worlds/magnetometer.sdf b/test/worlds/magnetometer.sdf index c6a17181a1..5ccb1aac88 100644 --- a/test/worlds/magnetometer.sdf +++ b/test/worlds/magnetometer.sdf @@ -8,11 +8,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Magnetometer"> diff --git a/test/worlds/mesh.sdf b/test/worlds/mesh.sdf index ac782d24be..1beeff5052 100644 --- a/test/worlds/mesh.sdf +++ b/test/worlds/mesh.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/multiple_worlds.sdf b/test/worlds/multiple_worlds.sdf index 7c8717c596..8b2353ffb1 100644 --- a/test/worlds/multiple_worlds.sdf +++ b/test/worlds/multiple_worlds.sdf @@ -3,11 +3,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -54,7 +54,7 @@ + name="gz::sim::systems::Physics"> @@ -104,11 +104,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/nested_model.sdf b/test/worlds/nested_model.sdf index 06063d67eb..371a433817 100644 --- a/test/worlds/nested_model.sdf +++ b/test/worlds/nested_model.sdf @@ -7,12 +7,12 @@ + name="gz::sim::systems::Physics"> libignition-physics-tpe-plugin.so + name="gz::sim::systems::SceneBroadcaster"> @@ -62,7 +62,7 @@ + name="gz::sim::systems::PosePublisher"> true false false diff --git a/test/worlds/nondefault_canonical.sdf b/test/worlds/nondefault_canonical.sdf index 26c2650949..61a55a1765 100644 --- a/test/worlds/nondefault_canonical.sdf +++ b/test/worlds/nondefault_canonical.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/performer_detector.sdf b/test/worlds/performer_detector.sdf index 20889c3ac4..0c52ef33a9 100644 --- a/test/worlds/performer_detector.sdf +++ b/test/worlds/performer_detector.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> @@ -310,7 +310,7 @@ + name="gz::sim::systems::DiffDrive"> front_left_wheel_joint rear_left_wheel_joint front_right_wheel_joint @@ -325,7 +325,7 @@ 4.0 0 2.5 0 0 0 + name="gz::sim::systems::PerformerDetector"> /performer_detector no_value @@ -358,7 +358,7 @@ 5 3 2.5 0 0 0 + name="gz::sim::systems::PerformerDetector"> /performer_detector @@ -369,7 +369,7 @@ - + vehicle_blue diff --git a/test/worlds/performers.sdf b/test/worlds/performers.sdf index ec194696e9..82d3290023 100644 --- a/test/worlds/performers.sdf +++ b/test/worlds/performers.sdf @@ -94,7 +94,7 @@ - + sphere diff --git a/test/worlds/plugins.sdf b/test/worlds/plugins.sdf index 466215d186..cd3777a252 100644 --- a/test/worlds/plugins.sdf +++ b/test/worlds/plugins.sdf @@ -7,21 +7,21 @@ + name="gz::sim::TestWorldSystem"> 0.123 + name="gz::sim::TestModelSystem"> 987 + name="gz::sim::TestSensorSystem"> 456 diff --git a/test/worlds/pose_publisher.sdf b/test/worlds/pose_publisher.sdf index 2bacec9d5d..d60e54de6a 100644 --- a/test/worlds/pose_publisher.sdf +++ b/test/worlds/pose_publisher.sdf @@ -8,11 +8,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Imu"> true @@ -259,7 +259,7 @@ + name="gz::sim::systems::PosePublisher"> true true false @@ -474,7 +474,7 @@ + name="gz::sim::systems::PosePublisher"> true true false @@ -489,7 +489,7 @@ + name="gz::sim::systems::PosePublisher"> true false false @@ -503,7 +503,7 @@ + name="gz::sim::systems::PosePublisher"> true false false diff --git a/test/worlds/quadcopter.sdf b/test/worlds/quadcopter.sdf index c5531c2ee5..3b072635ab 100644 --- a/test/worlds/quadcopter.sdf +++ b/test/worlds/quadcopter.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -251,7 +251,7 @@ + name="gz::sim::systems::MulticopterMotorModel"> X3 rotor_0_joint rotor_0 @@ -271,7 +271,7 @@ + name="gz::sim::systems::MulticopterMotorModel"> X3 rotor_1_joint rotor_1 @@ -291,7 +291,7 @@ + name="gz::sim::systems::MulticopterMotorModel"> X3 rotor_2_joint rotor_2 @@ -311,7 +311,7 @@ + name="gz::sim::systems::MulticopterMotorModel"> X3 rotor_3_joint rotor_3 diff --git a/test/worlds/quadcopter_velocity_control.sdf b/test/worlds/quadcopter_velocity_control.sdf index 6a4d08b813..f1e0a96af1 100644 --- a/test/worlds/quadcopter_velocity_control.sdf +++ b/test/worlds/quadcopter_velocity_control.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -251,7 +251,7 @@ + name="gz::sim::systems::MulticopterMotorModel"> X3 rotor_0_joint rotor_0 @@ -271,7 +271,7 @@ + name="gz::sim::systems::MulticopterMotorModel"> X3 rotor_1_joint rotor_1 @@ -291,7 +291,7 @@ + name="gz::sim::systems::MulticopterMotorModel"> X3 rotor_2_joint rotor_2 @@ -311,7 +311,7 @@ + name="gz::sim::systems::MulticopterMotorModel"> X3 rotor_3_joint rotor_3 @@ -331,7 +331,7 @@ + name="gz::sim::systems::MulticopterVelocityControl"> X3 gazebo/command/twist enable diff --git a/test/worlds/resource_paths.sdf b/test/worlds/resource_paths.sdf index 84f44e79ab..5d59425491 100644 --- a/test/worlds/resource_paths.sdf +++ b/test/worlds/resource_paths.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::Physics"> model://scheme_resource_uri diff --git a/test/worlds/revolute_joint.sdf b/test/worlds/revolute_joint.sdf index 6f918c9ea6..b9c16b3fcd 100644 --- a/test/worlds/revolute_joint.sdf +++ b/test/worlds/revolute_joint.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/revolute_joint_equilibrium.sdf b/test/worlds/revolute_joint_equilibrium.sdf index 1af50f31cc..a796131e16 100644 --- a/test/worlds/revolute_joint_equilibrium.sdf +++ b/test/worlds/revolute_joint_equilibrium.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/rgbd_camera_sensor.sdf b/test/worlds/rgbd_camera_sensor.sdf index 6aee476435..c98b18bb2d 100644 --- a/test/worlds/rgbd_camera_sensor.sdf +++ b/test/worlds/rgbd_camera_sensor.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre2 diff --git a/test/worlds/save_world.sdf b/test/worlds/save_world.sdf index b66cf1de07..979ab24907 100644 --- a/test/worlds/save_world.sdf +++ b/test/worlds/save_world.sdf @@ -7,15 +7,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::UserCommands"> @@ -24,17 +24,17 @@ - https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack + https://fuel.gazebosim.org/1.0/openroboticstest/models/backpack backpack1 1 0 0 0 0 0 - https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack + https://fuel.gazebosim.org/1.0/openroboticstest/models/backpack backpack2 1 2 3 0.1 0.2 0.3 - https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/2 + https://fuel.gazebosim.org/1.0/openroboticstest/models/backpack/3 backpack3 2 0 0 0.1 0.2 0.3 diff --git a/test/worlds/sensor.sdf b/test/worlds/sensor.sdf index 68ccfcd989..3dcb648e86 100644 --- a/test/worlds/sensor.sdf +++ b/test/worlds/sensor.sdf @@ -7,12 +7,12 @@ + name="gz::sim::systems::Sensors"> ogre2 + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/server_invalid.config b/test/worlds/server_invalid.config index d0371fc23f..48cc6ec97a 100644 --- a/test/worlds/server_invalid.config +++ b/test/worlds/server_invalid.config @@ -6,7 +6,7 @@ Example server configuration that is NOT valid entity_name="default" entity_type="world" filename="TestWorldSystem" - name="ignition::gazebo::TestWorldSystem"> + name="gz::sim::TestWorldSystem"> 0.123 diff --git a/test/worlds/server_valid.config b/test/worlds/server_valid.config index 7c55928937..39217fd30f 100644 --- a/test/worlds/server_valid.config +++ b/test/worlds/server_valid.config @@ -7,21 +7,21 @@ Example server configuration that is valid entity_name="default" entity_type="world" filename="TestWorldSystem" - name="ignition::gazebo::TestWorldSystem"> + name="gz::sim::TestWorldSystem"> 0.123 + name="gz::sim::TestModelSystem"> 987 + name="gz::sim::TestSensorSystem"> 456 diff --git a/test/worlds/server_valid2.config b/test/worlds/server_valid2.config index e52be4382b..598077a39a 100644 --- a/test/worlds/server_valid2.config +++ b/test/worlds/server_valid2.config @@ -7,14 +7,14 @@ Example server configuration that is valid entity_name="*" entity_type="world" filename="TestWorldSystem" - name="ignition::gazebo::TestWorldSystem"> + name="gz::sim::TestWorldSystem"> 0.123 + name="gz::sim::TestModelSystem"> 987 diff --git a/test/worlds/static_diff_drive_vehicle.sdf b/test/worlds/static_diff_drive_vehicle.sdf index ddadbde39c..568ff93366 100644 --- a/test/worlds/static_diff_drive_vehicle.sdf +++ b/test/worlds/static_diff_drive_vehicle.sdf @@ -9,11 +9,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> true @@ -212,7 +212,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint right_wheel_joint 1.25 diff --git a/test/worlds/thermal.sdf b/test/worlds/thermal.sdf index b350944823..ad27869e8b 100644 --- a/test/worlds/thermal.sdf +++ b/test/worlds/thermal.sdf @@ -12,16 +12,16 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre2 + name="gz::sim::systems::SceneBroadcaster"> @@ -110,7 +110,7 @@ + name="gz::sim::systems::Thermal"> 200.0 @@ -152,7 +152,7 @@ + name="gz::sim::systems::Thermal"> 600.0 @@ -196,7 +196,7 @@ + name="gz::sim::systems::Thermal"> 400.0 diff --git a/test/worlds/tire_drum.sdf b/test/worlds/tire_drum.sdf index 1a812108c3..e013e474cd 100644 --- a/test/worlds/tire_drum.sdf +++ b/test/worlds/tire_drum.sdf @@ -210,7 +210,7 @@ + name="gz::sim::systems::WheelSlip"> 0.1 0.01 diff --git a/test/worlds/touch_plugin.sdf b/test/worlds/touch_plugin.sdf index d108699e92..8cee70204b 100644 --- a/test/worlds/touch_plugin.sdf +++ b/test/worlds/touch_plugin.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Contact"> @@ -61,7 +61,7 @@ + name="gz::sim::systems::TouchPlugin"> green_box_for_white white_touches_only_green @@ -116,7 +116,7 @@ + name="gz::sim::systems::TouchPlugin"> green_box_for_red_yellow red_and_yellow_touch_only_green @@ -149,7 +149,7 @@ + name="gz::sim::systems::TouchPlugin"> green_box_for_blue blue_touches_only_green diff --git a/test/worlds/tracked_vehicle_simple.sdf b/test/worlds/tracked_vehicle_simple.sdf index cbe39175b6..3fce1b7b5b 100644 --- a/test/worlds/tracked_vehicle_simple.sdf +++ b/test/worlds/tracked_vehicle_simple.sdf @@ -9,9 +9,9 @@ 0 1000 - - - + + + 1 1 1 1 0.8 0.8 0.8 1 @@ -1065,7 +1065,7 @@ - + left_track front_left_flipper rear_left_flipper @@ -1076,32 +1076,32 @@ 0.18094 0.5 - + left_track -1.0 1.0 - + right_track -1.0 1.0 - + front_left_flipper -1.0 1.0 - + rear_left_flipper -1.0 1.0 - + front_right_flipper -1.0 1.0 - + rear_right_flipper -1.0 1.0 diff --git a/test/worlds/triball_drift.sdf b/test/worlds/triball_drift.sdf index d574e2a2b6..aa54763604 100644 --- a/test/worlds/triball_drift.sdf +++ b/test/worlds/triball_drift.sdf @@ -5,15 +5,15 @@ 1 0 -9.8 + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -911,7 +911,7 @@ + name="gz::sim::systems::WheelSlip"> 0.25 1 diff --git a/test/worlds/triggered_publisher.sdf b/test/worlds/triggered_publisher.sdf index bdfa514d66..01903c3f2c 100644 --- a/test/worlds/triggered_publisher.sdf +++ b/test/worlds/triggered_publisher.sdf @@ -5,19 +5,19 @@ 0 - + - + data: true - + data: false @@ -27,7 +27,7 @@ - + data: true @@ -36,7 +36,7 @@ - + data: 0 @@ -45,7 +45,7 @@ - + data: 0 @@ -54,7 +54,7 @@ - + data: -5 @@ -75,7 +75,7 @@ - + 1.0 2.0 @@ -83,7 +83,7 @@ - + 1.0 2.0 @@ -91,7 +91,7 @@ - + { @@ -102,7 +102,7 @@ - + { @@ -120,28 +120,28 @@ - + data: 0, data: 1 - + data: 0.5 - + 0.5 - + "value1" @@ -149,14 +149,14 @@ - + data: 0, data: 1 - + diff --git a/test/worlds/trisphere_cycle_wheel_slip.sdf b/test/worlds/trisphere_cycle_wheel_slip.sdf index b086b05a0f..a610f2386e 100644 --- a/test/worlds/trisphere_cycle_wheel_slip.sdf +++ b/test/worlds/trisphere_cycle_wheel_slip.sdf @@ -6,15 +6,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -444,7 +444,7 @@ + name="gz::sim::systems::WheelSlip"> 0.15 0 @@ -786,7 +786,7 @@ + name="gz::sim::systems::WheelSlip"> 1 1 diff --git a/test/worlds/velocity_control.sdf b/test/worlds/velocity_control.sdf index ae7bb605fc..fc5f29da64 100644 --- a/test/worlds/velocity_control.sdf +++ b/test/worlds/velocity_control.sdf @@ -18,15 +18,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -309,7 +309,7 @@ + name="gz::sim::systems::VelocityControl"> caster @@ -485,7 +485,7 @@ + name="gz::sim::systems::VelocityControl"> 0.3 0 0 0 0 -0.1 diff --git a/test/worlds/wind_effects.sdf b/test/worlds/wind_effects.sdf index d237053c7f..95a5e377ae 100644 --- a/test/worlds/wind_effects.sdf +++ b/test/worlds/wind_effects.sdf @@ -9,16 +9,16 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::WindEffects"> 1 diff --git a/tutorials/battery.md b/tutorials/battery.md index aacfaff581..574748a891 100644 --- a/tutorials/battery.md +++ b/tutorials/battery.md @@ -19,7 +19,7 @@ model: ... + name="gz::sim::systems::LinearBatteryPlugin"> linear_battery 4.2 @@ -107,7 +107,7 @@ By default, two Ignition Transport services are available for managing charging: * `/model//battery//recharge/start`: Enable recharging. * `/model//battery//recharge/stop`: Disable recharging. -Both services accept an `ignition::msgs::Boolean` parameter. +Both services accept an `gz::msgs::Boolean` parameter. ## Try out an example diff --git a/tutorials/collada_world_exporter.md b/tutorials/collada_world_exporter.md index 7e452d736a..8a3ffb84f3 100644 --- a/tutorials/collada_world_exporter.md +++ b/tutorials/collada_world_exporter.md @@ -11,7 +11,7 @@ loader. ``` + name="gz::sim::systems::ColladaWorldExporter"> ``` diff --git a/tutorials/create_system_plugins.md b/tutorials/create_system_plugins.md index 2a3b07eec3..02676f17d1 100644 --- a/tutorials/create_system_plugins.md +++ b/tutorials/create_system_plugins.md @@ -12,19 +12,19 @@ there are currently three additional available interfaces: 1. ISystemPreUpdate 1. Has read-write access to world entities and components. - 2. This is where systems say what they'd like to happen at time ignition::gazebo::UpdateInfo::simTime. + 2. This is where systems say what they'd like to happen at time gz::sim::UpdateInfo::simTime. 3. Can be used to modify state before physics runs, for example for applying control signals or performing network synchronization. 2. ISystemUpdate 1. Has read-write access to world entities and components. - 2. Used for physics simulation step (i.e., simulates what happens at time ignition::gazebo::UpdateInfo::simTime). + 2. Used for physics simulation step (i.e., simulates what happens at time gz::sim::UpdateInfo::simTime). 3. ISystemPostUpdate 1. Has read-only access to world entities and components. - 2. Captures everything that happened at time ignition::gazebo::UpdateInfo::simTime. + 2. Captures everything that happened at time gz::sim::UpdateInfo::simTime. 3. Used to read out results at the end of a simulation step to be used for sensor or controller updates. -It's important to note that ignition::gazebo::UpdateInfo::simTime does not refer to the current time, but the time reached after the `PreUpdate` and `Update` calls have finished. +It's important to note that gz::sim::UpdateInfo::simTime does not refer to the current time, but the time reached after the `PreUpdate` and `Update` calls have finished. So, if any of the `*Update` functions are called with simulation paused, time does not advance, which means the time reached after `PreUpdate` and `Update` is the same as the starting time. -This explains why ignition::gazebo::UpdateInfo::simTime is initially 0 if simulation is started paused, while ignition::gazebo::UpdateInfo::simTime is initially ignition::gazebo::UpdateInfo::dt if simulation is started un-paused. +This explains why gz::sim::UpdateInfo::simTime is initially 0 if simulation is started paused, while gz::sim::UpdateInfo::simTime is initially gz::sim::UpdateInfo::dt if simulation is started un-paused. Systems that are only used to read the current state of the world (sensors, graphics, and rendering) should implement `ISystemPostUpdate`. diff --git a/tutorials/gui_config.md b/tutorials/gui_config.md index 58569d10a4..b91abddb53 100644 --- a/tutorials/gui_config.md +++ b/tutorials/gui_config.md @@ -80,7 +80,7 @@ favorite editor and save this file as `fuel_preview.sdf`: + name="gz::sim::systems::SceneBroadcaster"> diff --git a/tutorials/levels.md b/tutorials/levels.md index f8f1f98df5..0806b43c3d 100644 --- a/tutorials/levels.md +++ b/tutorials/levels.md @@ -144,8 +144,8 @@ The concepts of levels and performers are specific to Ignition Gazebo, thus, putting them directly under the `` tag would diminish the generality of SDF. A new tag, ``, has been proposed for such circumstances but has not been implemented yet. Therefore, for now, the `` and `` -tags will be added to a `` tag. -The plugin name `ignition::gazebo` will be fixed so that a simulation runner +tags will be added to a `` tag. +The plugin name `gz::sim` will be fixed so that a simulation runner would know to check for that name in each plugin tag. ### @@ -224,7 +224,7 @@ The name of the add performer service is `/world//level/set_performer`. Make sure to replace `` with the name of simulated world. The service request is an ignition:msgs::StringMsg message, and the response is an -ignition::msgs::Boolean message. The response is true when the peformer was +gz::msgs::Boolean message. The response is true when the peformer was successfuly added. #### Example @@ -298,7 +298,7 @@ the figure - + R1 diff --git a/tutorials/log.md b/tutorials/log.md index 70e77222c0..3cb7035696 100644 --- a/tutorials/log.md +++ b/tutorials/log.md @@ -42,16 +42,16 @@ Other options for recording: ### From C++ API All features available through the command line are also available through -[ignition::gazebo::ServerConfig](https://gazebosim.org/api/gazebo/2.0/classignition_1_1gazebo_1_1ServerConfig.html). +[gz::sim::ServerConfig](https://gazebosim.org/api/gazebo/2.0/classignition_1_1gazebo_1_1ServerConfig.html). When instantiating a server programmatically, logging options can be passed to the constructor, for example: ``` -ignition::gazebo::ServerConfig serverConfig; +gz::sim::ServerConfig serverConfig; serverConfig.SetUseLogRecord(true); serverConfig.SetLogRecordPath("custom_path"); -ignition::gazebo::Server server(serverConfig); +gz::sim::Server server(serverConfig); ``` ### From plugin in SDF @@ -63,7 +63,7 @@ Recording can be specified in the SDF, under `` tag: ... + name="gz::sim::systems::LogRecord"> rotor_0 @@ -844,25 +844,25 @@ plugin once for the entire model and the `ApplyJointForce` plugin once for each + name="gz::sim::systems::JointStatePublisher"> + name="gz::sim::systems::ApplyJointForce"> rotor_0_joint + name="gz::sim::systems::ApplyJointForce"> rotor_1_joint + name="gz::sim::systems::ApplyJointForce"> rotor_2_joint + name="gz::sim::systems::ApplyJointForce"> rotor_3_joint ``` diff --git a/tutorials/migration_link_api.md b/tutorials/migration_link_api.md index aadb9c59ed..6fa1679941 100644 --- a/tutorials/migration_link_api.md +++ b/tutorials/migration_link_api.md @@ -9,7 +9,7 @@ view of the architecture differences before using this guide. This tutorial is meant to serve as a reference guide for developers migrating functions from the -[gazebo::phyiscs::Link](http://osrf-distributions.s3.amazonaws.com/gazebo/api/11.0.0/classgazebo_1_1physics_1_1Link.html) +[sim::phyiscs::Link](http://osrf-distributions.s3.amazonaws.com/gazebo/api/11.0.0/classgazebo_1_1physics_1_1Link.html) class. If you're trying to use some API which doesn't have an equivalent on Ignition @@ -18,7 +18,7 @@ yet, feel free to ## Link API -Gazebo-classic's `gazebo::physics::Link` provides lots of functionality, which +Gazebo-classic's `sim::physics::Link` provides lots of functionality, which can be divided in these categories: * **Properties**: Setting / getting properties @@ -55,15 +55,15 @@ components (properties) into entities such as links. Classic | Ignition -- | -- -AddForce | `ignition::gazebo::Link::AddWorldForce` +AddForce | `gz::sim::Link::AddWorldForce` AddForceAtRelativePosition | TODO AddForceAtWorldPosition | TODO AddLinkForce | TODO AddRelativeForce | TODO AddRelativeTorque | TODO -AddTorque | `ignition::gazebo::Link::AddWorldWrench` +AddTorque | `gz::sim::Link::AddWorldWrench` AddType | `ecm.CreateComponent(entity, Type())` -Battery | Use this system: `ignition::gazebo::systems::LinearBatteryPlugin` +Battery | Use this system: `gz::sim::systems::LinearBatteryPlugin` BoundingBox | TODO CollisionBoundingBox | TODO DirtyPose | Not supported @@ -71,24 +71,24 @@ FillMsg | TODO GetAngularDamping | TODO GetEnabled | TODO GetGravityMode | TODO -GetId | `ignition::gazebo::Link::Entity` -GetInertial | `ignition::gazebo::Link::WorldInertialPose` / `ignition::gazebo::Link::WorldInertialMatrix` +GetId | `gz::sim::Link::Entity` +GetInertial | `gz::sim::Link::WorldInertialPose` / `gz::sim::Link::WorldInertialMatrix` GetKinematic | TODO GetLinearDamping | TODO -GetName | `ignition::gazebo::Link::Name` +GetName | `gz::sim::Link::Name` GetSDF | TODO GetSDFDom | TODO GetSaveable | Not supported -GetScopedName | `ignition::gazebo::scopedName` +GetScopedName | `gz::sim::scopedName` GetSelfCollide | See model API GetSensorName | See sensor API -GetType | `ignition::gazebo::entityType` +GetType | `gz::sim::entityType` GetWorldEnergy | TODO -GetWorldEnergyKinetic | `ignition::gazebo::Link::WorldKineticEnergy` +GetWorldEnergyKinetic | `gz::sim::Link::WorldKineticEnergy` GetWorldEnergyPotential | TODO -HasType | `gazebo::components::Link::typeId == entityTypeId(entity, ecm)` +HasType | `sim::components::Link::typeId == entityTypeId(entity, ecm)` InitialRelativePose | TODO -IsCanonicalLink | `ignition::gazebo::Link::IsCanonical` +IsCanonicalLink | `gz::sim::Link::IsCanonical` IsSelected | Selection is client-specific, not porting IsStatic | See model API MoveFrame | TODO @@ -136,22 +136,22 @@ SetWindMode | TODO SetWorldPose | TODO SetWorldTwist | TODO StopAnimation | TODO -TypeStr | `ignition::gazebo::entityTypeStr` +TypeStr | `gz::sim::entityTypeStr` URI | TODO UpdateParameters | TODO VisualPose | See visual API -WindMode | `ignition::gazebo::Link::WindMode` +WindMode | `gz::sim::Link::WindMode` WorldAngularAccel | TODO WorldAngularMomentum | TODO -WorldAngularVel | `ignition::gazebo::Link::WorldAngularVelocity` +WorldAngularVel | `gz::sim::Link::WorldAngularVelocity` WorldCoGLinearVel | TODO WorldCoGPose | TODO WorldForce | TODO -WorldInertiaMatrix | `ignition::gazebo::Link::WorldInertialMatrix` -WorldInertialPose | `ignition::gazebo::Link::WorldInertialPose` -WorldLinearAccel | `ignition::gazebo::Link::WorldLinearAcceleration` -WorldLinearVel | `ignition::gazebo::Link::WorldLinearVelocity` -WorldPose | `ignition::gazebo::Link::WorldPose` +WorldInertiaMatrix | `gz::sim::Link::WorldInertialMatrix` +WorldInertialPose | `gz::sim::Link::WorldInertialPose` +WorldLinearAccel | `gz::sim::Link::WorldLinearAcceleration` +WorldLinearVel | `gz::sim::Link::WorldLinearVelocity` +WorldPose | `gz::sim::Link::WorldPose` WorldTorque | TODO WorldWindLinearVel | TODO @@ -170,28 +170,28 @@ they deal with entity IDs. Classic | Ignition -- | -- -BatteryCount | Use this system: `ignition::gazebo::systems::LinearBatteryPlugin` +BatteryCount | Use this system: `gz::sim::systems::LinearBatteryPlugin` FindAllConnectedLinksHelper | TODO -GetByName | Use type-specific `ignition::gazebo::Link::*ByName` -GetChild | Use type-specific `ignition::gazebo::Link::*ByName` -GetChildCollision | `ignition::gazebo::Link::CollisionByName` -GetChildCount | Use type-specific `ignition::gazebo::Link::*Count` +GetByName | Use type-specific `gz::sim::Link::*ByName` +GetChild | Use type-specific `gz::sim::Link::*ByName` +GetChildCollision | `gz::sim::Link::CollisionByName` +GetChildCount | Use type-specific `gz::sim::Link::*Count` GetChildJoint | TODO GetChildJointsLinks | See joint API GetChildLink | Not supported -GetCollision | `ignition::gazebo::Link::CollisionByName` -GetCollisions | `ignition::gazebo::Link::Collisions` -GetModel | `ignition::gazebo::Link::ParentModel` -GetParent | `ignition::gazebo::EntiyComponentManager::ParentEntity` -GetParentId | `ignition::gazebo::EntiyComponentManager::ParentEntity` +GetCollision | `gz::sim::Link::CollisionByName` +GetCollisions | `gz::sim::Link::Collisions` +GetModel | `gz::sim::Link::ParentModel` +GetParent | `gz::sim::EntiyComponentManager::ParentEntity` +GetParentId | `gz::sim::EntiyComponentManager::ParentEntity` GetParentJoints | TODO GetParentJointsLinks | See joint API -GetParentModel | `ignition::gazebo::Link::ParentModel` -GetSensorCount | `ignition::gazebo::Link::SensorCount` +GetParentModel | `gz::sim::Link::ParentModel` +GetSensorCount | `gz::sim::Link::SensorCount` GetVisualMessage | See visual API -GetWorld | `ignition::gazebo::worldEntity` -VisualId | `ignition::gazebo::Link::VisualByName` -Visuals | `ignition::gazebo::Link::Visuals` +GetWorld | `gz::sim::worldEntity` +VisualId | `gz::sim::Link::VisualByName` +Visuals | `gz::sim::Link::Visuals` --- @@ -238,8 +238,8 @@ Classic | Ignition -- | -- Fini | N/A Init | N/A -Load | `ignition::gazebo::SdfEntityCreator::CreateEntities` -LoadJoints | `ignition::gazebo::SdfEntityCreator::CreateEntities` +Load | `gz::sim::SdfEntityCreator::CreateEntities` +LoadJoints | `gz::sim::SdfEntityCreator::CreateEntities` LoadPlugins | TODO Reset | TODO ResetPhysicsStates | TODO diff --git a/tutorials/migration_model_api.md b/tutorials/migration_model_api.md index bd4ecbbb63..c766ba40e8 100644 --- a/tutorials/migration_model_api.md +++ b/tutorials/migration_model_api.md @@ -9,7 +9,7 @@ view of the architecture differences before using this guide. This tutorial is meant to serve as a reference guide for developers migrating functions from the -[gazebo::physics::Model](http://osrf-distributions.s3.amazonaws.com/gazebo/api/11.0.0/classgazebo_1_1physics_1_1Model.html) +[sim::physics::Model](http://osrf-distributions.s3.amazonaws.com/gazebo/api/11.0.0/classgazebo_1_1physics_1_1Model.html) class. If you're trying to use some API which doesn't have an equivalent on Ignition @@ -18,7 +18,7 @@ yet, feel free to ## Model API -Gazebo-classic's `gazebo::physics::Model` provides lots of functionality, which +Gazebo-classic's `sim::physics::Model` provides lots of functionality, which can be divided in these categories: * **Properties**: Setting / getting properties @@ -61,23 +61,23 @@ CollisionBoundingBox | TODO DirtyPose | Not supported FillMsg | TODO GetAutoDisable | TODO -GetId | `ignition::gazebo::Model::Entity` -GetName | `ignition::gazebo::Model::Name` +GetId | `gz::sim::Model::Entity` +GetName | `gz::sim::Model::Name` GetPluginCount | TODO GetSDF | TODO GetSDFDom | TODO GetSaveable | Not supported -GetScopedName | `ignition::gazebo::scopedName` -GetSelfCollide | `ignition::gazebo::Model::SelfCollide` -GetType | `ignition::gazebo::entityType` +GetScopedName | `gz::sim::scopedName` +GetSelfCollide | `gz::sim::Model::SelfCollide` +GetType | `gz::sim::entityType` GetWorldEnergy | TODO GetWorldEnergyKinetic | TODO GetWorldEnergyPotential | TODO -HasType | `gazebo::components::Model::typeId == entityTypeId(entity, ecm)` +HasType | `sim::components::Model::typeId == entityTypeId(entity, ecm)` InitialRelativePose | TODO IsCanonicalLink | See link API IsSelected | Selection is client-specific, not porting -IsStatic | `ignition::gazebo::Model::Static` +IsStatic | `gz::sim::Model::Static` PluginInfo | TODO Print | TODO ProcessMsg | TODO @@ -112,19 +112,19 @@ SetSelfCollide | TODO SetState | TODO SetStatic | TODO SetWindMode | TODO -SetWorldPose | `ignition::gazebo::Model::SetWorldPoseCmd` +SetWorldPose | `gz::sim::Model::SetWorldPoseCmd` SetWorldTwist | TODO StopAnimation | TODO -TypeStr | `ignition::gazebo::entityTypeStr` +TypeStr | `gz::sim::entityTypeStr` URI | TODO UnscaledSDF | TODO UpdateParameters | TODO -WindMode | `ignition::gazebo::Model::WindMode` +WindMode | `gz::sim::Model::WindMode` WorldAngularAccel | TODO WorldAngularVel | TODO WorldLinearAccel | TODO WorldLinearVel | TODO -WorldPose | `ignition::gazebo::worldPose` +WorldPose | `gz::sim::worldPose` --- @@ -141,25 +141,25 @@ they deal with entity IDs. Classic | Ignition -- | -- -GetByName | Use type-specific `ignition::gazebo::Model::*ByName` -GetChild | Use type-specific `ignition::gazebo::Model::*ByName` +GetByName | Use type-specific `gz::sim::Model::*ByName` +GetChild | Use type-specific `gz::sim::Model::*ByName` GetChildCollision | See link API -GetChildCount | Use type-specific `ignition::gazebo::Model::*Count` -GetChildLink | `ignition::gazebo::Model::LinkByName` +GetChildCount | Use type-specific `gz::sim::Model::*Count` +GetChildLink | `gz::sim::Model::LinkByName` GetGripper | TODO GetGripperCount | TODO -GetJoint | `ignition::gazebo::Model::JointByName` -GetJointCount | `ignition::gazebo::Model::JointCount` -GetJoints | `ignition::gazebo::Model::Joints` -GetLink | `ignition::gazebo::Model::LinkByName` -GetLinks | const `ignition::gazebo::Model::Links` -GetParent | `ignition::gazebo::EntiyComponentManager::ParentEntity` -GetParentId | `ignition::gazebo::EntiyComponentManager::ParentEntity` -GetParentModel | `ignition::gazebo::EntiyComponentManager::ParentEntity` +GetJoint | `gz::sim::Model::JointByName` +GetJointCount | `gz::sim::Model::JointCount` +GetJoints | `gz::sim::Model::Joints` +GetLink | `gz::sim::Model::LinkByName` +GetLinks | const `gz::sim::Model::Links` +GetParent | `gz::sim::EntiyComponentManager::ParentEntity` +GetParentId | `gz::sim::EntiyComponentManager::ParentEntity` +GetParentModel | `gz::sim::EntiyComponentManager::ParentEntity` GetSensorCount | See link API -GetWorld | const `ignition::gazebo::Model::World` -NestedModel | `ignition::gazebo::Model::NestedModelByName` -NestedModels | const `ignition::gazebo::Model::NestedModels` +GetWorld | const `gz::sim::Model::World` +NestedModel | `gz::sim::Model::NestedModelByName` +NestedModels | const `gz::sim::Model::NestedModels` --- @@ -198,8 +198,8 @@ Classic | Ignition -- | -- Fini | N/A Init | N/A -Load | `ignition::gazebo::SdfEntityCreator::CreateEntities` -LoadJoints | `ignition::gazebo::SdfEntityCreator::CreateEntities` +Load | `gz::sim::SdfEntityCreator::CreateEntities` +LoadJoints | `gz::sim::SdfEntityCreator::CreateEntities` LoadPlugins | TODO Reset | TODO ResetPhysicsStates | TODO @@ -216,7 +216,7 @@ logic that should be performed from within a system. Classic | Ignition -- | -- -GetJointController | Use this system: `ignition::gazebo::systems::JointController` +GetJointController | Use this system: `gz::sim::systems::JointController` GetNearestEntityBelow | Requires a system PlaceOnEntity | Involves Requires a system PlaceOnNearestEntityBelow | Requires a system diff --git a/tutorials/migration_plugins.md b/tutorials/migration_plugins.md index 51880f9817..ae0b4114e5 100644 --- a/tutorials/migration_plugins.md +++ b/tutorials/migration_plugins.md @@ -100,13 +100,13 @@ GZ_REGISTER_MODEL_PLUGIN(MyPlugin) On Ignition Gazebo, that would be implemented as follows: ```cpp -#include -#include -#include -#include +#include +#include +#include +#include -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; // Inherit from System and 2 extra interfaces: @@ -148,13 +148,13 @@ class MyPlugin // Register plugin IGNITION_ADD_PLUGIN(MyPlugin, - ignition::gazebo::System, + gz::sim::System, MyPlugin::ISystemConfigure, MyPlugin::ISystemPostUpdate) // Add plugin alias so that we can refer to the plugin without the version // namespace -IGNITION_ADD_PLUGIN_ALIAS(MyPlugin, "ignition::gazebo::systems::MyPlugin") +IGNITION_ADD_PLUGIN_ALIAS(MyPlugin, "gz::sim::systems::MyPlugin") ``` The example above uses headers like `Model.hh` and `Util.hh`, which offer @@ -164,16 +164,16 @@ entities and components. Let's take a look at how to do the same just using the ECM's API: ```cpp -#include -#include -#include -#include -#include -#include -#include - -using namespace ignition; -using namespace gazebo; +#include +#include +#include +#include +#include +#include +#include + +using namespace gz; +using namespace sim; using namespace systems; // Inherit from System and 2 extra interfaces: @@ -230,11 +230,11 @@ class MyPlugin }; IGNITION_ADD_PLUGIN(MyPlugin, - ignition::gazebo::System, + gz::sim::System, MyPlugin::ISystemConfigure, MyPlugin::ISystemPostUpdate) -IGNITION_ADD_PLUGIN_ALIAS(MyPlugin, "ignition::gazebo::systems::MyPlugin") +IGNITION_ADD_PLUGIN_ALIAS(MyPlugin, "gz::sim::systems::MyPlugin") ``` In summary, the key differences between Gazebo Classic and Ignition Gazebo are: @@ -249,7 +249,7 @@ In summary, the key differences between Gazebo Classic and Ignition Gazebo are: * Plugins don't have direct access to physics objects such as `physics::Model`. Instead, they can either deal directly with entities and their components by calling functions in the ECM, or using convenient objects such as - `ignition::gazebo::Model` which wrap the ECM interface. + `gz::sim::Model` which wrap the ECM interface. All these changes are meant to give plugin developers more flexibility to only use the features they need, and several layers of abstraction which diff --git a/tutorials/migration_sdf.md b/tutorials/migration_sdf.md index 90d591b21c..241fd70367 100644 --- a/tutorials/migration_sdf.md +++ b/tutorials/migration_sdf.md @@ -215,7 +215,7 @@ On Ignition, that would be: ``` + name="gz::sim::systems::DiffDrive"> ... diff --git a/tutorials/migration_world_api.md b/tutorials/migration_world_api.md index 6b0c5d73ef..80e2002251 100644 --- a/tutorials/migration_world_api.md +++ b/tutorials/migration_world_api.md @@ -9,7 +9,7 @@ view of the architecture differences before using this guide. This tutorial is meant to serve as a reference guide for developers migrating functions from the -[gazebo::physics::World](http://osrf-distributions.s3.amazonaws.com/gazebo/api/11.0.0/classgazebo_1_1physics_1_1World.html) +[sim::physics::World](http://osrf-distributions.s3.amazonaws.com/gazebo/api/11.0.0/classgazebo_1_1physics_1_1World.html) class. If you're trying to use some API which doesn't have an equivalent on Ignition @@ -18,7 +18,7 @@ yet, feel free to ## World API -Gazebo-classic's `gazebo::physics::World` provides lots of functionality, which +Gazebo-classic's `sim::physics::World` provides lots of functionality, which can be divided in these categories: * **Properties**: Setting / getting properties @@ -52,25 +52,25 @@ components (properties) into entities such as worlds. Classic | Ignition -- | -- -Atmosphere | `ignition::gazebo::World::Atmosphere` +Atmosphere | `gz::sim::World::Atmosphere` AtmosphereEnabled | TODO DisableAllModels | TODO EnableAllModels | TODO GetSDFDom | TODO -Gravity | `ignition::gazebo::World::Gravity` +Gravity | `gz::sim::World::Gravity` IsLoaded | Not applicable -IsPaused | Use `ignition::gazebo::UpdateInfo` -Iterations | Use `ignition::gazebo::UpdateInfo` -MagneticField | `ignition::gazebo::World::MagneticField` -Name | `ignition::gazebo::World::Name` -PauseTime | Use `ignition::gazebo::UpdateInfo` +IsPaused | Use `gz::sim::UpdateInfo` +Iterations | Use `gz::sim::UpdateInfo` +MagneticField | `gz::sim::World::MagneticField` +Name | `gz::sim::World::Name` +PauseTime | Use `gz::sim::UpdateInfo` Physics | TODO PhysicsEnabled | TODO PresetMgr | TODO -PublishLightPose | Use `ignition::gazebo::systems::PosePublisher` -PublishModelPose | Use `ignition::gazebo::systems::PosePublisher` +PublishLightPose | Use `gz::sim::systems::PosePublisher` +PublishModelPose | Use `gz::sim::systems::PosePublisher` PublishModelScale | TODO -RealTime | Use `ignition::gazebo::UpdateInfo` +RealTime | Use `gz::sim::UpdateInfo` Running | Not applicable SDF | TODO SetAtmosphereEnabled | TODO @@ -82,9 +82,9 @@ SetPhysicsEnabled | TODO SetSimTime | Use world control service SetState | TODO SetWindEnabled | TODO -SimTime | Use `ignition::gazebo::UpdateInfo` +SimTime | Use `gz::sim::UpdateInfo` SphericalCoords | TODO -StartTime | Use `ignition::gazebo::UpdateInfo` +StartTime | Use `gz::sim::UpdateInfo` URI | TODO UpdateStateSDF | TODO Wind | TODO @@ -101,15 +101,15 @@ they deal with entity IDs. Classic | Ignition -- | -- -BaseByName | Use type-specific `ignition::gazebo::World::*ByName` -EntityByName | Use type-specific `ignition::gazebo::World::*ByName` -LightByName | `ignition::gazebo::World::LightByName` -LightCount | `ignition::gazebo::World::LightCount` -Lights | `ignition::gazebo::World::Lights` -ModelByIndex | `ignition::gazebo::World::ModelByName` -ModelByName | `ignition::gazebo::World::ModelByName` -ModelCount | `ignition::gazebo::World::ModelCount` -Models | `ignition::gazebo::World::Models` +BaseByName | Use type-specific `gz::sim::World::*ByName` +EntityByName | Use type-specific `gz::sim::World::*ByName` +LightByName | `gz::sim::World::LightByName` +LightCount | `gz::sim::World::LightCount` +Lights | `gz::sim::World::Lights` +ModelByIndex | `gz::sim::World::ModelByName` +ModelByName | `gz::sim::World::ModelByName` +ModelCount | `gz::sim::World::ModelCount` +Models | `gz::sim::World::Models` PrintEntityTree | Use scene graph service ## Write family @@ -122,7 +122,7 @@ Classic | Ignition Clear | TODO ClearModels | TODO InsertModelFile | TODO -InsertModelSDF | `ignition::gazebo::SdfEntityCreator::CreateEntities` +InsertModelSDF | `gz::sim::SdfEntityCreator::CreateEntities` InsertModelString | TODO RemoveModel | TODO RemovePlugin | TODO @@ -137,8 +137,8 @@ Classic | Ignition -- | -- Fini | N/A Init | N/A -Load | `ignition::gazebo::SdfEntityCreator::CreateEntities` -LoadLight | `ignition::gazebo::SdfEntityCreator::CreateEntities` +Load | `gz::sim::SdfEntityCreator::CreateEntities` +LoadLight | `gz::sim::SdfEntityCreator::CreateEntities` LoadPlugin | TODO Reset | TODO ResetEntities | TODO @@ -161,7 +161,7 @@ Classic | Ignition -- | -- EntityBelowPoint | Requires a system ModelBelowPoint | Requires a system -SceneMsg | Use `ignition::gazebo::systems::SceneBoradcaster` +SceneMsg | Use `gz::sim::systems::SceneBoradcaster` WorldPoseMutex | N/A StripWorldName | N/A UniqueModelName | TODO diff --git a/tutorials/physics.md b/tutorials/physics.md index adc2d1c283..ed0b5377a4 100644 --- a/tutorials/physics.md +++ b/tutorials/physics.md @@ -2,15 +2,15 @@ Ignition Gazebo supports choosing what physics engine to use at runtime. This is made possible by -[Ignition Physics](https://gazebosim.org/libs/physics)' abstraction +[Gazebo Physics](https://gazebosim.org/libs/physics)' abstraction layer. Ignition Gazebo uses the [DART](https://dartsim.github.io/) physics engine by default. Downstream developers may also integrate other physics engines by creating new -Ignition Physics engine plugins. See -[Ignition Physics](https://gazebosim.org/api/physics/2.0/tutorials.html)'s +Gazebo Physics engine plugins. See +[Gazebo Physics](https://gazebosim.org/api/physics/2.0/tutorials.html)'s tutorials to learn how to integrate a new engine. ## How Gazebo finds engines @@ -56,7 +56,7 @@ For the example above, you can load it like this: ```{.xml} + name="gz::sim::systems::Physics"> CustomEngine @@ -73,15 +73,15 @@ Alternatively, you can choose a plugin from the command line using the ### From C++ API All features available through the command line are also available through -[ignition::gazebo::ServerConfig](https://gazebosim.org/api/gazebo/2.0/classignition_1_1gazebo_1_1ServerConfig.html). +[gz::sim::ServerConfig](https://gazebosim.org/api/gazebo/2.0/classignition_1_1gazebo_1_1ServerConfig.html). When instantiating a server programmatically, a physics engine can be passed to the constructor, for example: ``` -ignition::gazebo::ServerConfig serverConfig; +gz::sim::ServerConfig serverConfig; serverConfig.SetPhysicsEngine("CustomEngine"); -ignition::gazebo::Server server(serverConfig); +gz::sim::Server server(serverConfig); ``` ## Troubleshooting diff --git a/tutorials/rendering_plugins.md b/tutorials/rendering_plugins.md index 2a9cc22873..c14b360c96 100644 --- a/tutorials/rendering_plugins.md +++ b/tutorials/rendering_plugins.md @@ -16,20 +16,20 @@ During simulation, there are up to two 3D scenes being rendered by Ignition Gazebo, one on the server process and one on the client process. The server-side scene will only be created when using the -`ignition::gazebo::systems::Sensors` system plugin on the server. This is the +`gz::sim::systems::Sensors` system plugin on the server. This is the scene that shows what the sensors see. The client-side scene will only be created when using the -`ignition::gazebo::Scene3D` GUI system plugin on the client. This is the +`gz::sim::Scene3D` GUI system plugin on the client. This is the scene that shows what the user sees. For the user to see what the sensors see, they need to use other GUI plugins -that display sensor data, such as `ignition::gui::plugins::ImageDisplay` for -camera images or `ignition::gazebo::VisualizeLidar` for lidar point clouds. +that display sensor data, such as `gz::gui::plugins::ImageDisplay` for +camera images or `gz::sim::VisualizeLidar` for lidar point clouds. Ignition Gazebo keeps these scenes in sync by sending periodic state messages from the server to the client that contain entity and component data with -the `ignition::gazebo::systems::SceneBroadcaster` plugin. Any +the `gz::sim::systems::SceneBroadcaster` plugin. Any changes done to these scenes using Ignition Rendering APIs directly, as described in this tutorial, will only affect one of the scenes and will not be synchronized. The examples below will show how to change the ambient light for @@ -41,18 +41,18 @@ Depending on the scene that you want to affect, you'll need to write a different plugin. To interact with the server-side scene, you'll need to write an -`ignition::gazebo::System`. +`gz::sim::System`. See [Create System Plugins](createsystemplugins.html). To interact with the client-side scene, you'll need to write an -[ignition::gui::Plugin](https://gazebosim.org/api/gui/4.1/classignition_1_1gui_1_1Plugin.html), -or a more specialized `ignition::gazebo::GuiSystem` +[gz::gui::Plugin](https://gazebosim.org/api/gui/4.1/classignition_1_1gui_1_1Plugin.html), +or a more specialized `gz::sim::GuiSystem` if you need to access entities and components. See the [GUI system plugin example](https://github.com/gazebosim/gz-sim/tree/main/examples/plugin/gui_system_plugin). ## Getting the scene -When writing either plugin type, the `ignition::rendering::Scene` pointer can +When writing either plugin type, the `gz::rendering::Scene` pointer can be conveniently found using the rendering engine's singleton. Both example plugins use the exact same logic to get the scene: @@ -72,14 +72,14 @@ different for each plugin type. ### Render events on the GUI The GUI plugin will need to listen to -[ignition::gui::events::Render](https://gazebosim.org/api/gui/4.1/classignition_1_1gui_1_1events_1_1Render.html) +[gz::gui::events::Render](https://gazebosim.org/api/gui/4.1/classignition_1_1gui_1_1events_1_1Render.html) events. Here's how to do it: 1. Include the GUI events header: \snippet examples/plugin/rendering_plugins/RenderingGuiPlugin.cc includeGuiEvents -2. The 3D scene sends render events periodically to the `ignition::gui::MainWindow`, +2. The 3D scene sends render events periodically to the `gz::gui::MainWindow`, not directly to every plugin. Therefore, your plugin will need to install a filter so that it receives all events coming from the `MainWindow`. In your plugin's `LoadConfig` call, install the filter as follows: @@ -100,8 +100,8 @@ events. Here's how to do it: ### Render events on the server -The server plugin will need to listen to `ignition::gazebo::events::PreRender` or -`ignition::gazebo::events::PostRender` events. +The server plugin will need to listen to `gz::sim::events::PreRender` or +`gz::sim::events::PostRender` events. Here's how to do it: diff --git a/tutorials/resources.md b/tutorials/resources.md index b7491e5472..d21759d0fa 100644 --- a/tutorials/resources.md +++ b/tutorials/resources.md @@ -40,7 +40,7 @@ Ignition will look for system plugins on the following paths, in order: 1. All paths on the `IGN_GAZEBO_SYSTEM_PLUGIN_PATH` environment variable 2. `$HOME/.ignition/gazebo/plugins` -3. [Systems that are installed with Ignition Gazebo](https://gazebosim.org/api/gazebo/3.7/namespaceignition_1_1gazebo_1_1systems.html) +3. [Systems that are installed with Ignition Gazebo](https://gazebosim.org/api/gazebo/3.7/namespace gz_1_1gazebo_1_1systems.html) ### Ignition GUI plugins @@ -60,9 +60,9 @@ Ignition will look for GUI plugins on the following paths, in order: 1. All paths set on the `IGN_GUI_PLUGIN_PATH` environment variable 2. [GUI plugins that are installed with Ignition Gazebo](https://github.com/gazebosim/gz-sim/tree/ign-gazebo3/src/gui/plugins) -3. Other paths added by calling `ignition::gui::App()->AddPluginPath` +3. Other paths added by calling `gz::gui::App()->AddPluginPath` 4. `~/.ignition/gui/plugins` -5. [Plugins which are installed with Ignition GUI](https://gazebosim.org/api/gui/3.0/namespaceignition_1_1gui_1_1plugins.html) +5. [Plugins which are installed with Gazebo GUI](https://gazebosim.org/api/gui/3.0/namespace gz_1_1gui_1_1plugins.html) ### Physics engines @@ -109,7 +109,7 @@ Top-level entities such as models, lights and actors may be loaded through: * The `/world//create` service: * SDF file as string (`` / `` / `` root) * Path / URL to SDF file - * (TODO) `ignition::msgs::Model`, `ignition::msgs::Light` + * (TODO) `gz::msgs::Model`, `gz::msgs::Light` * Within a system, using [SdfEntityCreator](https://gazebosim.org/api/gazebo/3.0/classignition_1_1gazebo_1_1SdfEntityCreator.html) or directly creating components and entities. diff --git a/tutorials/server_config.md b/tutorials/server_config.md index 9766d94843..8dd19cbdf8 100644 --- a/tutorials/server_config.md +++ b/tutorials/server_config.md @@ -90,7 +90,7 @@ favorite editor and save this file as `fuel_preview.sdf`: + name="gz::sim::systems::SceneBroadcaster"> @@ -239,12 +239,12 @@ system: + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Sensors"> ogre diff --git a/tutorials/terminology.md b/tutorials/terminology.md index 806ad26f8a..7175e8dc4f 100644 --- a/tutorials/terminology.md +++ b/tutorials/terminology.md @@ -10,14 +10,14 @@ to developers touching the source code. * **Entity**: Every "object" in the world, such as models, links, collisions, visuals, lights, joints, etc. - An entity [is just a numeric ID](namespaceignition_1_1gazebo.html#ad83694d867b0e3a9446b535b5dfd208d), + An entity [is just a numeric ID](namespace gz_1_1gazebo.html#ad83694d867b0e3a9446b535b5dfd208d), and may have several components attached to it. Entity IDs are assigned at runtime. * **Component**: Adds a certain functionality or characteristic (e.g., pose, name, material, etc.) to an entity. Ignition Gazebo comes with various - [components](namespaceignition_1_1gazebo_1_1components.html) + [components](namespace gz_1_1gazebo_1_1components.html) ready to be used, such as `Pose` and `Inertial`, and downstream developers can also create their own by inheriting from the [BaseComponent](classignition_1_1gazebo_1_1components_1_1BaseComponent.html) diff --git a/tutorials/test_fixture.md b/tutorials/test_fixture.md index 15d4af5586..1e9fe0d39a 100644 --- a/tutorials/test_fixture.md +++ b/tutorials/test_fixture.md @@ -18,7 +18,7 @@ helpful pointers on how to setup tests. ## Test Fixture -The example above uses the `ignition::gazebo::TestFixture` class, which provides +The example above uses the `gz::sim::TestFixture` class, which provides a convenient API to start a simulation and step through it while checking that entities in simulation are acting as expected. See that class' documentation for more information. diff --git a/tutorials/triggered_publisher.md b/tutorials/triggered_publisher.md index 11557b2136..fbcf6e422c 100644 --- a/tutorials/triggered_publisher.md +++ b/tutorials/triggered_publisher.md @@ -26,7 +26,7 @@ the change to the `DiffDrive` system is shown below: + name="gz::sim::systems::DiffDrive"> front_left_wheel_joint rear_left_wheel_joint front_right_wheel_joint @@ -45,7 +45,7 @@ a "start" message from the user: ```xml + name="gz::sim::systems::TriggeredPublisher"> linear: {x: 3} @@ -118,14 +118,14 @@ indicating where the sensor is on the ground. + name="gz::sim::systems::TouchPlugin"> vehicle_blue trigger true + name="gz::sim::systems::DetachableJoint"> body box1 box_body @@ -142,7 +142,7 @@ indicating where the sensor is on the ground. ... + name="gz::sim::systems::Contact"> ... @@ -164,7 +164,7 @@ message is `true` ```xml + name="gz::sim::systems::TriggeredPublisher"> data: true @@ -197,7 +197,7 @@ the link "box_body" in `box1` ... + name="gz::sim::systems::Altimeter"> ... @@ -220,7 +220,7 @@ static model `trigger` by adding the following to `trigger` ... + name="gz::sim::systems::DetachableJoint"> body box2 box_body @@ -244,7 +244,7 @@ numbers is not advised, we will set a tolerance of 0.2. ```xml + name="gz::sim::systems::TriggeredPublisher"> -7.5 diff --git a/tutorials/video_recorder.md b/tutorials/video_recorder.md index 91128d28fb..26856c7610 100644 --- a/tutorials/video_recorder.md +++ b/tutorials/video_recorder.md @@ -93,12 +93,12 @@ settings). Defaults to `false`. Note: the server publishes states at 60Hz and the video recorder records at 25 FPS so it also makes sense to update the Scene Broadcaster system to only publish states at 25Hz. You can do this by going to the world SDF file, locate the -`ignition::gazebo::systems::SceneBroadcaster` system, and set the +`gz::sim::systems::SceneBroadcaster` system, and set the `` parameter: ```xml + name='gz::sim::systems::SceneBroadcaster'> 25 ``` From 1a180713667f706e9fd9cb03e6f0b2c065260c68 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Mon, 1 May 2023 06:39:43 -0700 Subject: [PATCH 02/31] Add tutorial on migrating the Sensor class from gazebo classic (#1930) Signed-off-by: Ian Chen --- tutorials.md.in | 1 + tutorials/migration_sensor_api.md | 133 ++++++++++++++++++++++++++++++ 2 files changed, 134 insertions(+) create mode 100644 tutorials/migration_sensor_api.md diff --git a/tutorials.md.in b/tutorials.md.in index c454fc1ccc..8925641b75 100644 --- a/tutorials.md.in +++ b/tutorials.md.in @@ -53,6 +53,7 @@ Ignition @IGN_DESIGNATION_CAP@ library and how to use the library effectively. * \subpage migrationjointapi "Joint API": Guide on what Joint C++ functions to call in Gazebo when migrating from Gazebo classic * \subpage migrationactorapi "Actor API": Guide on what Actor C++ functions to call in Gazebo when migrating from Gazebo classic * \subpage migrationlinkapi "Link API": Guide on what Link C++ functions to call in Gazebo when migrating from Gazebo classic +* \subpage migrationsensorapi "Sensor API": Guide on what Sensor C++ functions to call in Gazebo when migrating from Gazebo classic * \subpage ardupilot "Case Study": Migrating the ArduPilot ModelPlugin from Gazebo classic to Gazebo. ## License diff --git a/tutorials/migration_sensor_api.md b/tutorials/migration_sensor_api.md new file mode 100644 index 0000000000..0616b2b012 --- /dev/null +++ b/tutorials/migration_sensor_api.md @@ -0,0 +1,133 @@ +\page migrationsensorapi + +# Migration from Gazebo-classic: Sensor API + +When migrating plugins from Gazebo-classic to Gazebo, developers will +notice that the C++ APIs for both simulators are quite different. Be sure to +check the [plugin migration tutorial](migrationplugins.html) to get a high-level +view of the architecture differences before using this guide. + +This tutorial is meant to serve as a reference guide for developers migrating +functions from the +[gazebo::sensors::Sensor](http://osrf-distributions.s3.amazonaws.com/gazebo/api/11.0.0/classgazebo_1_1sensors_1_1Sensor.html) +class. + +If you're trying to use some API which doesn't have an equivalent on Gazebo +yet, feel free to +[ticket an issue](https://github.com/gazebosim/gz-sim/issues/). + +## Sensor API + +Gazebo-classic's `gazebo::sensors::Sensor` provides lots of functionality, which +can be divided in these categories: + +* **Properties**: Setting / getting properties + * Example: [Sensor::Name](http://osrf-distributions.s3.amazonaws.com/gazebo/api/11.0.0/classgazebo_1_1sensors_1_1Sensor.html#a41087c5f2f732f7a2f336b45b952f199) +* **Read family**: Getting parent + * Example: [Sensor::ParentName](http://osrf-distributions.s3.amazonaws.com/gazebo/api/11.0.0/classgazebo_1_1sensors_1_1Sensor.html#ac39481d8faba2202d0212ef018595de3) +* **Write family**: Changing parent + * Example: [Sensor::SetParent](http://osrf-distributions.s3.amazonaws.com/gazebo/api/11.0.0/classgazebo_1_1sensors_1_1Sensor.html#a8d07a3535e558a172e212f73b942d39d) +* **Lifecycle**: Functions to control the sensor's lifecycle + * Example: [Sensor::Init](http://osrf-distributions.s3.amazonaws.com/gazebo/api/11.0.0/classgazebo_1_1sensors_1_1Sensor.html#a3e0b39e1326de703012f81ac2be7feba) + +You'll find the Gazebo APIs below on the following headers: + +* [ignition/gazebo/Sensor.hh](https://gazebosim.org/api/gazebo/6/Sensor_8hh.html) +* [ignition/gazebo/Util.hh](https://gazebosim.org/api/gazebo/6/Util_8hh.html) +* [ignition/gazebo/SdfEntityCreator.hh](https://gazebosim.org/api/gazebo/6/SdfEntityCreator_8hh.html) +* [ignition/gazebo/EntityComponentManager.hh](https://gazebosim.org/api/gazebo/6/classignition_1_1gazebo_1_1EntityComponentManager.html) + +It's worth remembering that most of this functionality can be performed using +the +[EntityComponentManager](https://gazebosim.org/api/gazebo/6/classignition_1_1gazebo_1_1EntityComponentManager.html) +directly. + +As an example the `Sensor::Pose()` is a convienient function for querying the `Pose` component from the `EntityComponentManager`, i.e. + +``` + math::Pose3d pose = _ecm.Component(sensorEntityId)->Data(); +``` + +The functions presented in the sections below exist for convenience and +readability. The items marked as `TODO` means that the equivalent API is not +implemented yet in Gazebo. + +### Properties + +Most of Gazebo-classic's Sensor API is related to setting and getting +properties. These functions are great candidates to have equivalents on Gazebo +Gazebo, because the Entity-Component-System architecture is perfect for setting +components (properties) into entities such as sensors. + +--- + +Classic | Gazebo +-- | -- +Category | TODO +FillMsg | TODO +Id | `ignition::gazebo::Sensor::Entity` +IsActive | TODO +LastMeasurementTime | TODO +LastUpdateTime | TODO +Name | `ignition::gazebo::Sensor::Name` +NextRequiredTimestamp | TODO +Noise | TODO +Pose | `ignition::gazebo::Sensor::Pose` +ResetLastUpdateTime | TODO +ScopedName | `ignition::gazebo::scopedName` +SetActive | TODO +SetPose | TODO +SetUpdateRate | TODO +Topic | `ignition::gazebo::Sensor::Topic` +Type | `ignition::gazebo::entityType` +UpdateRate | TODO +Visualize | TODO +WorldName | `ignition::gazebo::worldEntity` + +--- + +## Read family + +These APIs deal with reading information related to parent relationship. + +The main difference in these APIs across Gazebo generations is that +on classic, they deal with shared pointers to entities, while on Gazebo, +they deal with entity IDs. + +--- + +Classic | Gazebo +-- | -- +ParentId | `ignition::gazebo::Sensor::Parent` +ParentName | `ignition::gazebo::Sensor::Parent` + +--- + +## Write family + +These functions deal with modifying the entity tree, attaching children to new +parents. + +--- + +Classic | Gazebo +-- | -- +SetParent | TODO +--- + +## Lifecycle + +These functions aren't related to the state of a sensor, but perform some +processing related to the sensor's lifecycle, like initializing, updating or +terminating it. + +--- + +Classic | Gazebo +-- | -- +ConnectUpdated | TODO +Fini | N/A +Init | N/A +Load | `ignition::gazebo::SdfEntityCreator::CreateEntities` +Update | Entities are updated by systems +--- From f3fecc77e42816bacb2502bf48ff5de83c8aa5ed Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Tue, 2 May 2023 05:07:44 -0700 Subject: [PATCH 03/31] Add missing cmake exports from core library (#1978) Not all of the needed include paths are exported with the gz-sim target, so including the gz/sim.hh header doesn't work easily. This test fails to build and illustrates the problem. Signed-off-by: Steve Peters --- src/CMakeLists.txt | 2 ++ test/integration/CMakeLists.txt | 1 + test/integration/include_sim_hh.cc | 27 +++++++++++++++++++++++++++ 3 files changed, 30 insertions(+) create mode 100644 test/integration/include_sim_hh.cc diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 59a1e99180..6c52f7d832 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -106,6 +106,8 @@ target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME} ignition-common${IGN_COMMON_VER}::profiler ignition-fuel_tools${IGN_FUEL_TOOLS_VER}::ignition-fuel_tools${IGN_FUEL_TOOLS_VER} ignition-gui${IGN_GUI_VER}::ignition-gui${IGN_GUI_VER} + ignition-physics${IGN_PHYSICS_VER}::core + ignition-rendering${IGN_RENDERING_VER}::core ignition-transport${IGN_TRANSPORT_VER}::ignition-transport${IGN_TRANSPORT_VER} sdformat${SDF_VER}::sdformat${SDF_VER} protobuf::libprotobuf diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index a42a778995..f8335cfe0c 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -20,6 +20,7 @@ set(tests events.cc examples_build.cc imu_system.cc + include_sim_hh.cc joint_controller_system.cc joint_position_controller_system.cc joint_state_publisher_system.cc diff --git a/test/integration/include_sim_hh.cc b/test/integration/include_sim_hh.cc new file mode 100644 index 0000000000..2c32b2be8c --- /dev/null +++ b/test/integration/include_sim_hh.cc @@ -0,0 +1,27 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include + +#include + +///////////////////////////////////////////////// +// Simple test to make sure it compiles +TEST(Compilation, sim_hh) +{ + gz::sim::System system; +} From 875de1bfa76634e058c0b183c2de0b79215696c3 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Tue, 2 May 2023 13:00:18 -0700 Subject: [PATCH 04/31] Add redirection header gz/sim.hh (#1983) Needed since the auto-generated header is gz/gazebo.hh Signed-off-by: Steve Peters --- include/gz/CMakeLists.txt | 3 +++ include/gz/sim.hh | 29 +++++++++++++++++++++++++++++ 2 files changed, 32 insertions(+) create mode 100644 include/gz/sim.hh diff --git a/include/gz/CMakeLists.txt b/include/gz/CMakeLists.txt index e4f01467e8..99bfa64c8f 100644 --- a/include/gz/CMakeLists.txt +++ b/include/gz/CMakeLists.txt @@ -1 +1,4 @@ add_subdirectory(sim) +# Manually install the redirection header sim.hh +# Do not merge this forward to gz-sim7 +install(FILES sim.hh DESTINATION ${IGN_INCLUDE_INSTALL_DIR_FULL}/gz) diff --git a/include/gz/sim.hh b/include/gz/sim.hh new file mode 100644 index 0000000000..79b6e2f239 --- /dev/null +++ b/include/gz/sim.hh @@ -0,0 +1,29 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#ifndef GZ_SIM_HH_ +#define GZ_SIM_HH_ + +// Since gz-cmake derives the auto-generated header name from the cmake +// project name, for ignition-gazebo*, the auto-generated header name +// is . +// This header file provides a redirection from to +// for the ignition-gazebo* projects and should not be merged forward to +// gz-sim*. +#include + +#endif From a2a2c856e9cc80ef604d2ce49b0dbea9d4dae570 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Tue, 2 May 2023 16:25:12 -0700 Subject: [PATCH 05/31] Use ignition::gazebo:: in class instantiation (#1967) Fixes macOS build. Signed-off-by: Steve Peters --- src/EntityComponentManager.cc | 2 +- src/Link.cc | 2 +- src/Model.cc | 2 +- src/SdfEntityCreator.cc | 2 +- src/ServerConfig.cc | 4 ++-- src/SystemLoader.cc | 2 +- src/TestFixture.cc | 2 +- src/World.cc | 2 +- src/rendering/MarkerManager.cc | 2 +- src/rendering/RenderUtil.cc | 2 +- src/rendering/SceneManager.cc | 2 +- src/systems/ackermann_steering/AckermannSteering.cc | 2 +- src/systems/air_pressure/AirPressure.cc | 2 +- src/systems/altimeter/Altimeter.cc | 2 +- src/systems/apply_joint_force/ApplyJointForce.cc | 2 +- src/systems/apply_link_wrench/ApplyLinkWrench.cc | 2 +- src/systems/battery_plugin/LinearBatteryPlugin.cc | 2 +- src/systems/buoyancy/Buoyancy.cc | 2 +- src/systems/camera_video_recorder/CameraVideoRecorder.cc | 2 +- src/systems/collada_world_exporter/ColladaWorldExporter.cc | 2 +- src/systems/contact/Contact.cc | 2 +- src/systems/diff_drive/DiffDrive.cc | 2 +- src/systems/imu/Imu.cc | 2 +- src/systems/joint_controller/JointController.cc | 2 +- .../joint_position_controller/JointPositionController.cc | 2 +- src/systems/kinetic_energy_monitor/KineticEnergyMonitor.cc | 2 +- src/systems/lift_drag/LiftDrag.cc | 2 +- src/systems/log/LogPlayback.cc | 2 +- src/systems/log/LogRecord.cc | 2 +- src/systems/log_video_recorder/LogVideoRecorder.cc | 2 +- .../logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc | 2 +- src/systems/logical_camera/LogicalCamera.cc | 2 +- src/systems/magnetometer/Magnetometer.cc | 2 +- src/systems/multicopter_motor_model/MulticopterMotorModel.cc | 2 +- src/systems/physics/Physics.cc | 2 +- src/systems/pose_publisher/PosePublisher.cc | 2 +- src/systems/scene_broadcaster/SceneBroadcaster.cc | 2 +- src/systems/sensors/Sensors.cc | 2 +- src/systems/thermal/Thermal.cc | 2 +- src/systems/touch_plugin/TouchPlugin.cc | 2 +- src/systems/track_controller/TrackController.cc | 2 +- src/systems/tracked_vehicle/TrackedVehicle.cc | 2 +- src/systems/user_commands/UserCommands.cc | 2 +- src/systems/velocity_control/VelocityControl.cc | 2 +- src/systems/wheel_slip/WheelSlip.cc | 2 +- src/systems/wind_effects/WindEffects.cc | 2 +- 46 files changed, 47 insertions(+), 47 deletions(-) diff --git a/src/EntityComponentManager.cc b/src/EntityComponentManager.cc index 67c76857ec..916ac90781 100644 --- a/src/EntityComponentManager.cc +++ b/src/EntityComponentManager.cc @@ -32,7 +32,7 @@ using namespace gz; using namespace gz::sim; -class gz::sim::EntityComponentManagerPrivate +class ignition::gazebo::EntityComponentManagerPrivate { /// \brief Implementation of the CreateEntity function, which takes a specific /// entity as input. diff --git a/src/Link.cc b/src/Link.cc index 904d769d98..491e40210e 100644 --- a/src/Link.cc +++ b/src/Link.cc @@ -36,7 +36,7 @@ #include "gz/sim/Link.hh" -class gz::sim::LinkPrivate +class ignition::gazebo::LinkPrivate { /// \brief Id of link entity. public: Entity id{kNullEntity}; diff --git a/src/Model.cc b/src/Model.cc index 5f63074151..d4d0d6653e 100644 --- a/src/Model.cc +++ b/src/Model.cc @@ -28,7 +28,7 @@ #include "gz/sim/components/WindMode.hh" #include "gz/sim/Model.hh" -class gz::sim::ModelPrivate +class ignition::gazebo::ModelPrivate { /// \brief Id of model entity. public: Entity id{kNullEntity}; diff --git a/src/SdfEntityCreator.cc b/src/SdfEntityCreator.cc index e40978a5b5..8b5f9698f3 100644 --- a/src/SdfEntityCreator.cc +++ b/src/SdfEntityCreator.cc @@ -70,7 +70,7 @@ #include "gz/sim/components/WindMode.hh" #include "gz/sim/components/World.hh" -class gz::sim::SdfEntityCreatorPrivate +class ignition::gazebo::SdfEntityCreatorPrivate { /// \brief Pointer to entity component manager. We don't assume ownership. public: EntityComponentManager *ecm{nullptr}; diff --git a/src/ServerConfig.cc b/src/ServerConfig.cc index f61447e839..5535ea62d6 100644 --- a/src/ServerConfig.cc +++ b/src/ServerConfig.cc @@ -31,7 +31,7 @@ using namespace gz; using namespace gz::sim; /// \brief Private data for PluginInfoConfig. -class gz::sim::ServerConfig::PluginInfoPrivate +class ignition::gazebo::ServerConfig::PluginInfoPrivate { /// \brief Default constructor. public: PluginInfoPrivate() = default; @@ -192,7 +192,7 @@ void ServerConfig::PluginInfo::SetSdf(const sdf::ElementPtr &_sdf) } /// \brief Private data for ServerConfig. -class gz::sim::ServerConfigPrivate +class ignition::gazebo::ServerConfigPrivate { /// \brief Default constructor. public: ServerConfigPrivate() diff --git a/src/SystemLoader.cc b/src/SystemLoader.cc index 72d8ac701b..f63dcb427a 100644 --- a/src/SystemLoader.cc +++ b/src/SystemLoader.cc @@ -35,7 +35,7 @@ using namespace gz::sim; -class gz::sim::SystemLoaderPrivate +class ignition::gazebo::SystemLoaderPrivate { ////////////////////////////////////////////////// public: explicit SystemLoaderPrivate() = default; diff --git a/src/TestFixture.cc b/src/TestFixture.cc index dafd7b94d2..7e05455ed2 100644 --- a/src/TestFixture.cc +++ b/src/TestFixture.cc @@ -106,7 +106,7 @@ void HelperSystem::PostUpdate(const UpdateInfo &_info, } ////////////////////////////////////////////////// -class gz::sim::TestFixturePrivate +class ignition::gazebo::TestFixturePrivate { /// \brief Initialize fixture /// \param[in] _config Server config diff --git a/src/World.cc b/src/World.cc index 5f776f0551..002e5729a9 100644 --- a/src/World.cc +++ b/src/World.cc @@ -28,7 +28,7 @@ #include "gz/sim/components/World.hh" #include "gz/sim/World.hh" -class gz::sim::WorldPrivate +class ignition::gazebo::WorldPrivate { /// \brief Id of world entity. public: Entity id{kNullEntity}; diff --git a/src/rendering/MarkerManager.cc b/src/rendering/MarkerManager.cc index 1c057e3720..3e06e7c935 100644 --- a/src/rendering/MarkerManager.cc +++ b/src/rendering/MarkerManager.cc @@ -37,7 +37,7 @@ using namespace gz; using namespace gz::sim; /// Private data for the MarkerManager class -class gz::sim::MarkerManagerPrivate +class ignition::gazebo::MarkerManagerPrivate { /// \brief Processes a marker message. /// \param[in] _msg The message data. diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index f35c6bedfa..d29dbd56b2 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -75,7 +75,7 @@ using namespace gz; using namespace gz::sim; // Private data class. -class gz::sim::RenderUtilPrivate +class ignition::gazebo::RenderUtilPrivate { /// True if the rendering component is initialized public: bool initialized = false; diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index 67c93485c4..2a1f7e509c 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -50,7 +50,7 @@ using namespace gz::sim; using namespace std::chrono_literals; /// \brief Private data class. -class gz::sim::SceneManagerPrivate +class ignition::gazebo::SceneManagerPrivate { /// \brief Keep track of world ID, which is equivalent to the scene's /// root visual. diff --git a/src/systems/ackermann_steering/AckermannSteering.cc b/src/systems/ackermann_steering/AckermannSteering.cc index dbc8225e66..5d61fca244 100644 --- a/src/systems/ackermann_steering/AckermannSteering.cc +++ b/src/systems/ackermann_steering/AckermannSteering.cc @@ -54,7 +54,7 @@ struct Commands Commands() : lin(0.0), ang(0.0) {} }; -class gz::sim::systems::AckermannSteeringPrivate +class ignition::gazebo::systems::AckermannSteeringPrivate { /// \brief Callback for velocity subscription /// \param[in] _msg Velocity message diff --git a/src/systems/air_pressure/AirPressure.cc b/src/systems/air_pressure/AirPressure.cc index 6e47bcd7bf..a28b44f7d9 100644 --- a/src/systems/air_pressure/AirPressure.cc +++ b/src/systems/air_pressure/AirPressure.cc @@ -48,7 +48,7 @@ using namespace gz::sim; using namespace systems; /// \brief Private AirPressure data class. -class gz::sim::systems::AirPressurePrivate +class ignition::gazebo::systems::AirPressurePrivate { /// \brief A map of air pressure entity to its sensor public: std::unordered_map collisionEntities; }; -class gz::sim::systems::ContactPrivate +class ignition::gazebo::systems::ContactPrivate { /// \brief Create sensors that correspond to entities in the simulation /// \param[in] _ecm Mutable reference to ECM. diff --git a/src/systems/diff_drive/DiffDrive.cc b/src/systems/diff_drive/DiffDrive.cc index ae0878d663..e2fc82492b 100644 --- a/src/systems/diff_drive/DiffDrive.cc +++ b/src/systems/diff_drive/DiffDrive.cc @@ -53,7 +53,7 @@ struct Commands Commands() : lin(0.0), ang(0.0) {} }; -class gz::sim::systems::DiffDrivePrivate +class ignition::gazebo::systems::DiffDrivePrivate { /// \brief Callback for velocity subscription /// \param[in] _msg Velocity message diff --git a/src/systems/imu/Imu.cc b/src/systems/imu/Imu.cc index d596bb79bf..ce384d69ab 100644 --- a/src/systems/imu/Imu.cc +++ b/src/systems/imu/Imu.cc @@ -48,7 +48,7 @@ using namespace gz::sim; using namespace systems; /// \brief Private Imu data class. -class gz::sim::systems::ImuPrivate +class ignition::gazebo::systems::ImuPrivate { /// \brief A map of IMU entity to its IMU sensor. public: std::unordered_map Date: Fri, 12 May 2023 13:46:39 -0700 Subject: [PATCH 06/31] Use gui 6.8 Signed-off-by: Nate Koenig --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 93a00ee84d..8d04ff2326 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -100,7 +100,7 @@ set(IGN_FUEL_TOOLS_VER ${ignition-fuel_tools7_VERSION_MAJOR}) #-------------------------------------- # Find ignition-gui -ign_find_package(ignition-gui6 REQUIRED VERSION 6.5) +ign_find_package(ignition-gui6 REQUIRED VERSION 6.8) set(IGN_GUI_VER ${ignition-gui6_VERSION_MAJOR}) ign_find_package (Qt5 COMPONENTS From bd5353f622d91bb784a6703ecbf9c3395abf2ea4 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 17 May 2023 20:45:18 -0700 Subject: [PATCH 07/31] Fix visibility Signed-off-by: Nate Koenig --- include/gz/sim/gui/GuiSystem.hh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/gz/sim/gui/GuiSystem.hh b/include/gz/sim/gui/GuiSystem.hh index c519a9835a..2940d107fb 100644 --- a/include/gz/sim/gui/GuiSystem.hh +++ b/include/gz/sim/gui/GuiSystem.hh @@ -41,7 +41,7 @@ namespace gazebo /// GUI systems are different from `gz::sim::System`s because they /// don't run in the same process as the physics. Instead, they run in a /// separate process that is stepped by updates coming through the network - class IGNITION_GAZEBO_VISIBLE GuiSystem : public gz::gui::Plugin + class IGNITION_GAZEBO_GUI_VISIBLE GuiSystem : public gz::gui::Plugin { Q_OBJECT From a0234e946dbde868eab735868ae2aea189de8193 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 24 May 2023 05:57:47 -0700 Subject: [PATCH 08/31] Fixed headers and most comments Signed-off-by: Nate Koenig --- include/gz/sim/Actor.hh | 10 +- include/gz/sim/Joint.hh | 16 +-- include/gz/sim/Light.hh | 18 +-- include/gz/sim/Primitives.hh | 4 +- include/gz/sim/Sensor.hh | 10 +- include/gz/sim/comms/Broker.hh | 6 +- include/gz/sim/comms/ICommsModel.hh | 8 +- include/gz/sim/comms/MsgManager.hh | 10 +- include/gz/sim/components/BatteryPowerLoad.hh | 6 +- .../gz/sim/components/BoundingBoxCamera.hh | 8 +- include/gz/sim/components/CMakeLists.txt | 2 +- include/gz/sim/components/CanonicalLink.hh | 1 + include/gz/sim/components/CustomSensor.hh | 8 +- include/gz/sim/components/Factory.hh | 2 +- include/gz/sim/components/ForceTorque.hh | 10 +- include/gz/sim/components/HaltMotion.hh | 6 +- .../sim/components/JointTransmittedWrench.hh | 10 +- include/gz/sim/components/LightCmd.hh | 12 +- include/gz/sim/components/LightType.hh | 8 +- include/gz/sim/components/NavSat.hh | 10 +- include/gz/sim/components/ParticleEmitter.hh | 10 +- include/gz/sim/components/Recreate.hh | 6 +- .../components/RenderEngineServerHeadless.hh | 8 +- .../gz/sim/components/SegmentationCamera.hh | 8 +- include/gz/sim/components/SemanticLabel.hh | 8 +- .../gz/sim/components/SphericalCoordinates.hh | 12 +- include/gz/sim/components/SystemPluginInfo.hh | 10 +- include/gz/sim/components/TemperatureRange.hh | 8 +- include/gz/sim/components/Visibility.hh | 6 +- include/gz/sim/components/VisualCmd.hh | 12 +- include/gz/sim/components/WheelSlipCmd.hh | 12 +- include/gz/sim/config.hh.in | 2 +- include/gz/sim/detail/BaseView.hh | 6 +- include/gz/sim/gui/GuiEvents.hh | 4 +- src/Actor.cc | 12 +- src/Actor_TEST.cc | 10 +- src/BaseView.cc | 6 +- src/ComponentFactory.cc | 2 +- src/EntityComponentManager.cc | 2 +- src/Joint.cc | 46 +++---- src/Joint_TEST.cc | 12 +- src/Light.cc | 18 +-- src/Light_TEST.cc | 12 +- src/ModelCommandAPI_TEST.cc | 2 +- src/Primitives.cc | 6 +- src/Primitives_TEST.cc | 2 +- src/SdfEntityCreator_TEST.cc | 2 +- src/SdfGenerator_TEST.cc | 2 +- src/Sensor.cc | 12 +- src/Sensor_TEST.cc | 10 +- src/SimulationRunner.cc | 2 +- src/SystemInternal.hh | 6 +- src/SystemManager.cc | 6 +- src/SystemManager.hh | 14 +-- src/SystemManager_TEST.cc | 12 +- src/World.cc | 18 +-- src/WorldControl.hh | 2 +- src/comms/Broker.cc | 16 +-- src/comms/Broker_TEST.cc | 10 +- src/comms/ICommsModel.cc | 12 +- src/comms/MsgManager.cc | 10 +- src/comms/MsgManager_TEST.cc | 4 +- src/gui/GuiEvents.cc | 2 +- src/gui/GuiEvents_TEST.cc | 4 +- src/gui/Gui_clean_exit_TEST.cc | 10 +- src/gui/plugins/align_tool/AlignTool.cc | 6 +- .../banana_for_scale/BananaForScale.cc | 16 +-- .../banana_for_scale/BananaForScale.hh | 2 +- .../component_inspector/ComponentInspector.cc | 2 +- .../component_inspector/ComponentInspector.hh | 2 +- .../component_inspector/SystemPluginInfo.cc | 6 +- .../component_inspector/SystemPluginInfo.hh | 2 +- .../component_inspector_editor/AirPressure.cc | 6 +- .../component_inspector_editor/Altimeter.cc | 4 +- .../ComponentInspectorEditor.cc | 112 +++++++++--------- .../ComponentInspectorEditor.hh | 10 +- .../plugins/component_inspector_editor/Imu.cc | 6 +- .../component_inspector_editor/JointType.cc | 10 +- .../component_inspector_editor/Lidar.cc | 6 +- .../Magnetometer.cc | 4 +- .../component_inspector_editor/ModelEditor.cc | 26 ++-- .../component_inspector_editor/ModelEditor.hh | 2 +- .../component_inspector_editor/Pose3d.cc | 12 +- .../component_inspector_editor/Pose3d.hh | 2 +- .../component_inspector_editor/Types.hh | 2 +- src/gui/plugins/copy_paste/CopyPaste.cc | 18 +-- src/gui/plugins/copy_paste/CopyPaste.hh | 4 +- .../EntityContextMenuPlugin.cc | 18 +-- .../EntityContextMenuPlugin.hh | 6 +- src/gui/plugins/lights/Lights.cc | 22 ++-- src/gui/plugins/lights/Lights.hh | 2 +- src/gui/plugins/plotting/Plotting.cc | 42 +++---- src/gui/plugins/plotting/Plotting.hh | 16 +-- .../resource_spawner/ResourceSpawner.cc | 2 +- src/gui/plugins/scene3d/Scene3D.cc | 2 +- .../plugins/scene_manager/GzSceneManager.cc | 30 ++--- .../plugins/scene_manager/GzSceneManager.hh | 2 +- .../plugins/select_entities/SelectEntities.cc | 28 ++--- .../plugins/select_entities/SelectEntities.hh | 2 +- src/gui/plugins/spawn/Spawn.cc | 46 +++---- src/gui/plugins/spawn/Spawn.hh | 4 +- .../transform_control/TransformControl.cc | 10 +- .../plugins/video_recorder/VideoRecorder.cc | 14 +-- .../VisualizationCapabilities.cc | 104 ++++++++-------- .../VisualizationCapabilities.hh | 2 +- .../visualize_contacts/VisualizeContacts.cc | 36 +++--- .../visualize_contacts/VisualizeContacts.hh | 4 +- .../plugins/visualize_lidar/VisualizeLidar.cc | 54 ++++----- .../plugins/visualize_lidar/VisualizeLidar.hh | 6 +- src/network/PeerTracker_TEST.cc | 4 +- src/rendering/MarkerManager.cc | 2 +- src/systems/buoyancy/Buoyancy.cc | 2 +- src/systems/buoyancy_engine/BuoyancyEngine.cc | 16 +-- src/systems/buoyancy_engine/BuoyancyEngine.hh | 2 +- src/systems/comms_endpoint/CommsEndpoint.cc | 14 +-- src/systems/comms_endpoint/CommsEndpoint.hh | 4 +- .../detachable_joint/DetachableJoint.cc | 11 +- src/systems/follow_actor/FollowActor.cc | 14 +-- src/systems/follow_actor/FollowActor.hh | 4 +- src/systems/force_torque/ForceTorque.cc | 42 +++---- src/systems/force_torque/ForceTorque.hh | 4 +- src/systems/hydrodynamics/Hydrodynamics.cc | 22 ++-- src/systems/hydrodynamics/Hydrodynamics.hh | 2 +- .../JointTrajectoryController.cc | 38 +++--- .../JointTrajectoryController.hh | 2 +- src/systems/label/Label.cc | 14 +-- src/systems/label/Label.hh | 4 +- src/systems/log/LogPlayback.cc | 1 - .../LogicalAudioSensorPlugin.cc | 2 +- src/systems/mecanum_drive/MecanumDrive.cc | 28 ++--- src/systems/mecanum_drive/MecanumDrive.hh | 2 +- .../model_photo_shoot/ModelPhotoShoot.cc | 34 +++--- .../model_photo_shoot/ModelPhotoShoot.hh | 2 +- .../MulticopterMotorModel.cc | 2 +- src/systems/navsat/NavSat.cc | 28 ++--- src/systems/navsat/NavSat.hh | 6 +- .../odometry_publisher/OdometryPublisher.cc | 28 ++--- .../odometry_publisher/OdometryPublisher.hh | 2 +- .../OpticalTactilePlugin.cc | 30 ++--- .../OpticalTactilePlugin.hh | 2 +- .../optical_tactile_plugin/Visualization.cc | 6 +- .../optical_tactile_plugin/Visualization.hh | 8 +- .../particle_emitter/ParticleEmitter.cc | 32 ++--- .../particle_emitter/ParticleEmitter.hh | 2 +- .../particle_emitter2/ParticleEmitter2.cc | 22 ++-- .../particle_emitter2/ParticleEmitter2.hh | 2 +- src/systems/perfect_comms/PerfectComms.cc | 10 +- src/systems/perfect_comms/PerfectComms.hh | 6 +- .../physics/CanonicalLinkModelTracker.hh | 10 +- src/systems/rf_comms/RFComms.cc | 20 ++-- src/systems/rf_comms/RFComms.hh | 6 +- src/systems/shader_param/ShaderParam.cc | 24 ++-- src/systems/shader_param/ShaderParam.hh | 2 +- src/systems/thermal/ThermalSensor.cc | 14 +-- src/systems/thermal/ThermalSensor.hh | 6 +- src/systems/thruster/Thruster.cc | 42 +++---- src/systems/thruster/Thruster.hh | 2 +- .../trajectory_follower/TrajectoryFollower.cc | 30 ++--- .../trajectory_follower/TrajectoryFollower.hh | 2 +- test/integration/ModelPhotoShootTest.hh | 34 +++--- test/integration/actor.cc | 20 ++-- test/integration/actor_trajectory.cc | 20 ++-- test/integration/buoyancy_engine.cc | 26 ++-- .../camera_sensor_background_from_scene.cc | 12 +- test/integration/deprecated_TEST.cc | 2 +- test/integration/distortion_camera.cc | 16 +-- test/integration/entity_system.cc | 24 ++-- test/integration/follow_actor_system.cc | 22 ++-- test/integration/force_torque_system.cc | 24 ++-- test/integration/fuel_cached_server.cc | 6 +- test/integration/halt_motion.cc | 26 ++-- test/integration/hydrodynamics.cc | 32 ++--- test/integration/hydrodynamics_flags.cc | 32 ++--- test/integration/joint.cc | 54 ++++----- .../joint_trajectory_controller_system.cc | 26 ++-- test/integration/light.cc | 34 +++--- .../logical_audio_sensor_plugin.cc | 2 +- .../model_photo_shoot_default_joints.cc | 2 +- .../model_photo_shoot_random_joints.cc | 2 +- test/integration/multicopter.cc | 2 +- test/integration/multiple_servers.cc | 6 +- test/integration/navsat_system.cc | 32 ++--- test/integration/nested_model_physics.cc | 26 ++-- test/integration/odometry_publisher.cc | 32 ++--- test/integration/optical_tactile_plugin.cc | 18 +-- test/integration/particle_emitter.cc | 26 ++-- test/integration/particle_emitter2.cc | 24 ++-- test/integration/perfect_comms.cc | 10 +- test/integration/play_pause.cc | 2 +- test/integration/recreate_entities.cc | 32 ++--- test/integration/rf_comms.cc | 12 +- test/integration/sensor.cc | 24 ++-- test/integration/sensors_system_battery.cc | 18 +-- test/integration/shader_param_system.cc | 14 +-- test/integration/spherical_coordinates.cc | 30 ++--- test/integration/thermal_sensor_system.cc | 28 ++--- test/integration/thruster.cc | 40 +++---- test/integration/triggered_camera.cc | 20 ++-- test/integration/world_control_state.cc | 14 +-- test/performance/sdf_runner.cc | 2 +- test/plugins/TestVisualSystem.cc | 2 +- test/plugins/TestVisualSystem.hh | 10 +- 202 files changed, 1366 insertions(+), 1361 deletions(-) diff --git a/include/gz/sim/Actor.hh b/include/gz/sim/Actor.hh index 50460891a0..e19f154a0a 100644 --- a/include/gz/sim/Actor.hh +++ b/include/gz/sim/Actor.hh @@ -21,14 +21,14 @@ #include #include -#include +#include #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" +#include "gz/sim/config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Types.hh" namespace ignition { diff --git a/include/gz/sim/Joint.hh b/include/gz/sim/Joint.hh index e8b8ab31f3..e58ed60264 100644 --- a/include/gz/sim/Joint.hh +++ b/include/gz/sim/Joint.hh @@ -25,18 +25,18 @@ #include #include -#include -#include -#include +#include +#include +#include #include #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Types.hh" +#include "gz/sim/config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Types.hh" namespace ignition { diff --git a/include/gz/sim/Light.hh b/include/gz/sim/Light.hh index f3680991dd..130809bac3 100644 --- a/include/gz/sim/Light.hh +++ b/include/gz/sim/Light.hh @@ -24,15 +24,15 @@ #include -#include -#include -#include -#include - -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" +#include +#include +#include +#include + +#include "gz/sim/config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Types.hh" namespace ignition { diff --git a/include/gz/sim/Primitives.hh b/include/gz/sim/Primitives.hh index eff9a97b83..cb68727af3 100644 --- a/include/gz/sim/Primitives.hh +++ b/include/gz/sim/Primitives.hh @@ -18,8 +18,8 @@ #ifndef IGNITION_GAZEBO_PRIMITIVES_HH_ #define IGNITION_GAZEBO_PRIMITIVES_HH_ -#include -#include +#include +#include #include diff --git a/include/gz/sim/Sensor.hh b/include/gz/sim/Sensor.hh index af677f252b..ee08c8a814 100644 --- a/include/gz/sim/Sensor.hh +++ b/include/gz/sim/Sensor.hh @@ -23,14 +23,14 @@ #include -#include +#include #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" +#include "gz/sim/config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/Types.hh" namespace ignition { diff --git a/include/gz/sim/comms/Broker.hh b/include/gz/sim/comms/Broker.hh index bf06cdf383..f25646d575 100644 --- a/include/gz/sim/comms/Broker.hh +++ b/include/gz/sim/comms/Broker.hh @@ -20,10 +20,10 @@ #include -#include +#include #include -#include "ignition/gazebo/comms/MsgManager.hh" -#include "ignition/gazebo/config.hh" +#include "gz/sim/comms/MsgManager.hh" +#include "gz/sim/config.hh" namespace ignition { diff --git a/include/gz/sim/comms/ICommsModel.hh b/include/gz/sim/comms/ICommsModel.hh index 367cbe975b..e91ee63335 100644 --- a/include/gz/sim/comms/ICommsModel.hh +++ b/include/gz/sim/comms/ICommsModel.hh @@ -20,11 +20,11 @@ #include -#include +#include #include -#include "ignition/gazebo/comms/MsgManager.hh" -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/System.hh" +#include "gz/sim/comms/MsgManager.hh" +#include "gz/sim/config.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/include/gz/sim/comms/MsgManager.hh b/include/gz/sim/comms/MsgManager.hh index aa5bde7f4d..68ebfbd54b 100644 --- a/include/gz/sim/comms/MsgManager.hh +++ b/include/gz/sim/comms/MsgManager.hh @@ -23,11 +23,11 @@ #include #include -#include -#include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/System.hh" +#include +#include +#include "gz/sim/config.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/include/gz/sim/components/BatteryPowerLoad.hh b/include/gz/sim/components/BatteryPowerLoad.hh index 6cfb191678..47764ca4b2 100644 --- a/include/gz/sim/components/BatteryPowerLoad.hh +++ b/include/gz/sim/components/BatteryPowerLoad.hh @@ -17,9 +17,9 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_BATTERYPOWERLOAD_HH_ #define IGNITION_GAZEBO_COMPONENTS_BATTERYPOWERLOAD_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/BoundingBoxCamera.hh b/include/gz/sim/components/BoundingBoxCamera.hh index 2451fd8f24..39d56f1d84 100644 --- a/include/gz/sim/components/BoundingBoxCamera.hh +++ b/include/gz/sim/components/BoundingBoxCamera.hh @@ -19,10 +19,10 @@ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/CMakeLists.txt b/include/gz/sim/components/CMakeLists.txt index 83f18ce69d..100786be0e 100644 --- a/include/gz/sim/components/CMakeLists.txt +++ b/include/gz/sim/components/CMakeLists.txt @@ -13,5 +13,5 @@ configure_file( install( FILES ${CMAKE_CURRENT_BINARY_DIR}/components.hh - DESTINATION ${IGN_INCLUDE_INSTALL_DIR_FULL}/ignition/${IGN_DESIGNATION} + DESTINATION ${IGN_INCLUDE_INSTALL_DIR_FULL}/gz/sim ) diff --git a/include/gz/sim/components/CanonicalLink.hh b/include/gz/sim/components/CanonicalLink.hh index 8577db427b..f9d43e01ca 100644 --- a/include/gz/sim/components/CanonicalLink.hh +++ b/include/gz/sim/components/CanonicalLink.hh @@ -20,6 +20,7 @@ #include #include #include +#include namespace ignition { diff --git a/include/gz/sim/components/CustomSensor.hh b/include/gz/sim/components/CustomSensor.hh index 9871249241..63b79d63d1 100644 --- a/include/gz/sim/components/CustomSensor.hh +++ b/include/gz/sim/components/CustomSensor.hh @@ -18,10 +18,10 @@ #define IGNITION_GAZEBO_COMPONENTS_CUSTOMSENSOR_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/Factory.hh b/include/gz/sim/components/Factory.hh index 10a2c88909..7883333888 100644 --- a/include/gz/sim/components/Factory.hh +++ b/include/gz/sim/components/Factory.hh @@ -284,7 +284,7 @@ namespace components void Register(const std::string &_type, ComponentDescriptorBase *_compDesc, RegistrationObjectId _regObjId) { - auto typeHash = ignition::common::hash64(_type); + auto typeHash = gz::common::hash64(_type); // Initialize static member variable - we need to set these // static members for every shared lib that uses the component, but we diff --git a/include/gz/sim/components/ForceTorque.hh b/include/gz/sim/components/ForceTorque.hh index 12da278077..98c42c1f67 100644 --- a/include/gz/sim/components/ForceTorque.hh +++ b/include/gz/sim/components/ForceTorque.hh @@ -19,12 +19,12 @@ #include -#include -#include +#include +#include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/HaltMotion.hh b/include/gz/sim/components/HaltMotion.hh index 2b44fa5bb8..ece6c659df 100644 --- a/include/gz/sim/components/HaltMotion.hh +++ b/include/gz/sim/components/HaltMotion.hh @@ -17,9 +17,9 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_HALT_MOTION_HH_ #define IGNITION_GAZEBO_COMPONENTS_HALT_MOTION_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/JointTransmittedWrench.hh b/include/gz/sim/components/JointTransmittedWrench.hh index a723fdc285..e082f1ab1a 100644 --- a/include/gz/sim/components/JointTransmittedWrench.hh +++ b/include/gz/sim/components/JointTransmittedWrench.hh @@ -17,12 +17,12 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ #define IGNITION_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/LightCmd.hh b/include/gz/sim/components/LightCmd.hh index fdba5858fc..b4e36b8ddd 100644 --- a/include/gz/sim/components/LightCmd.hh +++ b/include/gz/sim/components/LightCmd.hh @@ -19,13 +19,13 @@ #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include +#include namespace ignition { diff --git a/include/gz/sim/components/LightType.hh b/include/gz/sim/components/LightType.hh index 249eb8602f..ffc3ed62c7 100644 --- a/include/gz/sim/components/LightType.hh +++ b/include/gz/sim/components/LightType.hh @@ -20,10 +20,10 @@ #include #include #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/NavSat.hh b/include/gz/sim/components/NavSat.hh index ae3358b9b4..35c864563a 100644 --- a/include/gz/sim/components/NavSat.hh +++ b/include/gz/sim/components/NavSat.hh @@ -19,12 +19,12 @@ #include -#include -#include +#include +#include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/ParticleEmitter.hh b/include/gz/sim/components/ParticleEmitter.hh index 86fc36bd88..7d70532c22 100644 --- a/include/gz/sim/components/ParticleEmitter.hh +++ b/include/gz/sim/components/ParticleEmitter.hh @@ -17,11 +17,11 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ #define IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/Recreate.hh b/include/gz/sim/components/Recreate.hh index bb053fe5f9..d15ea5fdf4 100644 --- a/include/gz/sim/components/Recreate.hh +++ b/include/gz/sim/components/Recreate.hh @@ -17,9 +17,9 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_RECREATE_HH_ #define IGNITION_GAZEBO_COMPONENTS_RECREATE_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/RenderEngineServerHeadless.hh b/include/gz/sim/components/RenderEngineServerHeadless.hh index 9746e4b0aa..0f9ea36ebc 100644 --- a/include/gz/sim/components/RenderEngineServerHeadless.hh +++ b/include/gz/sim/components/RenderEngineServerHeadless.hh @@ -18,10 +18,10 @@ #define IGNITION_GAZEBO_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/SegmentationCamera.hh b/include/gz/sim/components/SegmentationCamera.hh index c476fc8ba8..b84658a6ef 100644 --- a/include/gz/sim/components/SegmentationCamera.hh +++ b/include/gz/sim/components/SegmentationCamera.hh @@ -19,10 +19,10 @@ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/SemanticLabel.hh b/include/gz/sim/components/SemanticLabel.hh index 3139b75310..9282751be8 100644 --- a/include/gz/sim/components/SemanticLabel.hh +++ b/include/gz/sim/components/SemanticLabel.hh @@ -17,10 +17,10 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_LABEL_HH_ #define IGNITION_GAZEBO_COMPONENTS_LABEL_HH_ -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/components/Component.hh" -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/config.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/components/Component.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/config.hh" namespace ignition { diff --git a/include/gz/sim/components/SphericalCoordinates.hh b/include/gz/sim/components/SphericalCoordinates.hh index 93ebd43fa8..1f98bf7331 100644 --- a/include/gz/sim/components/SphericalCoordinates.hh +++ b/include/gz/sim/components/SphericalCoordinates.hh @@ -17,12 +17,12 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ #define IGNITION_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/SystemPluginInfo.hh b/include/gz/sim/components/SystemPluginInfo.hh index 365886c1e4..4990b2a2ee 100644 --- a/include/gz/sim/components/SystemPluginInfo.hh +++ b/include/gz/sim/components/SystemPluginInfo.hh @@ -17,11 +17,11 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_SYSTEMINFO_HH_ #define IGNITION_GAZEBO_COMPONENTS_SYSTEMINFO_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/TemperatureRange.hh b/include/gz/sim/components/TemperatureRange.hh index 99e4a26151..668fa2a7ef 100644 --- a/include/gz/sim/components/TemperatureRange.hh +++ b/include/gz/sim/components/TemperatureRange.hh @@ -20,11 +20,11 @@ #include #include -#include +#include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/Visibility.hh b/include/gz/sim/components/Visibility.hh index 7a53ddbb3e..3465db7eaa 100644 --- a/include/gz/sim/components/Visibility.hh +++ b/include/gz/sim/components/Visibility.hh @@ -18,9 +18,9 @@ #define IGNITION_GAZEBO_COMPONENTS_VISIBILITY_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/sim/components/VisualCmd.hh b/include/gz/sim/components/VisualCmd.hh index 794057aabb..71a424ec9b 100644 --- a/include/gz/sim/components/VisualCmd.hh +++ b/include/gz/sim/components/VisualCmd.hh @@ -17,13 +17,13 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_VISUALCMD_HH_ #define IGNITION_GAZEBO_COMPONENTS_VISUALCMD_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include +#include #include diff --git a/include/gz/sim/components/WheelSlipCmd.hh b/include/gz/sim/components/WheelSlipCmd.hh index 4daf7ee249..ec6ae1b3bb 100644 --- a/include/gz/sim/components/WheelSlipCmd.hh +++ b/include/gz/sim/components/WheelSlipCmd.hh @@ -17,13 +17,13 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ #define IGNITION_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include +#include namespace ignition { diff --git a/include/gz/sim/config.hh.in b/include/gz/sim/config.hh.in index 509d058cb0..72249e5b0c 100644 --- a/include/gz/sim/config.hh.in +++ b/include/gz/sim/config.hh.in @@ -11,7 +11,7 @@ #define IGNITION_GAZEBO_VERSION_NAMESPACE v${PROJECT_VERSION_MAJOR} -#define IGNITION_GAZEBO_VERSION_HEADER "Ignition Gazebo, version ${PROJECT_VERSION_FULL}\nCopyright (C) 2018 Open Source Robotics Foundation.\nReleased under the Apache 2.0 License.\n\n" +#define IGNITION_GAZEBO_VERSION_HEADER "Gazebo Sim, version ${PROJECT_VERSION_FULL}\nCopyright (C) 2018 Open Source Robotics Foundation.\nReleased under the Apache 2.0 License.\n\n" #define IGNITION_GAZEBO_GUI_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${IGN_DATA_INSTALL_DIR}/gui" #define IGNITION_GAZEBO_SYSTEM_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${IGN_DATA_INSTALL_DIR}/systems" diff --git a/include/gz/sim/detail/BaseView.hh b/include/gz/sim/detail/BaseView.hh index 9c1761d604..6452524bd8 100644 --- a/include/gz/sim/detail/BaseView.hh +++ b/include/gz/sim/detail/BaseView.hh @@ -22,9 +22,9 @@ #include #include -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/Types.hh" -#include "ignition/gazebo/config.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/Types.hh" +#include "gz/sim/config.hh" namespace ignition { diff --git a/include/gz/sim/gui/GuiEvents.hh b/include/gz/sim/gui/GuiEvents.hh index ff8a1e4b41..0c9be56991 100644 --- a/include/gz/sim/gui/GuiEvents.hh +++ b/include/gz/sim/gui/GuiEvents.hh @@ -192,7 +192,7 @@ namespace events /// \param[in] _type Entity type /// \param[in] _parent Parent entity. public: explicit ModelEditorAddEntity(QString _entity, QString _type, - ignition::gazebo::Entity _parent); + gz::sim::Entity _parent); /// \brief Get the entity to add public: QString Entity() const; @@ -202,7 +202,7 @@ namespace events /// \brief Get the parent entity to add the entity to - public: ignition::gazebo::Entity ParentEntity() const; + public: gz::sim::Entity ParentEntity() const; /// \brief Get the data map. /// \return the QMap of string, string holding custom data. diff --git a/src/Actor.cc b/src/Actor.cc index c84c1db01e..e76a387212 100644 --- a/src/Actor.cc +++ b/src/Actor.cc @@ -15,13 +15,13 @@ * */ -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Pose.hh" +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Pose.hh" -#include "ignition/gazebo/Actor.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Actor.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/Actor_TEST.cc b/src/Actor_TEST.cc index 94b761e077..0c8103a4f6 100644 --- a/src/Actor_TEST.cc +++ b/src/Actor_TEST.cc @@ -19,11 +19,11 @@ #include -#include "ignition/gazebo/Actor.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" +#include "gz/sim/Actor.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" ///////////////////////////////////////////////// TEST(ActorTest, Constructor) diff --git a/src/BaseView.cc b/src/BaseView.cc index 276b2ac175..d366d946c7 100644 --- a/src/BaseView.cc +++ b/src/BaseView.cc @@ -14,10 +14,10 @@ * limitations under the License. * */ -#include "ignition/gazebo/detail/BaseView.hh" +#include "gz/sim/detail/BaseView.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/Types.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/Types.hh" using namespace ignition; using namespace gazebo; diff --git a/src/ComponentFactory.cc b/src/ComponentFactory.cc index 52f5e55569..607e03dd1d 100644 --- a/src/ComponentFactory.cc +++ b/src/ComponentFactory.cc @@ -15,7 +15,7 @@ * */ -#include "ignition/gazebo/components/Factory.hh" +#include "gz/sim/components/Factory.hh" using Factory = ignition::gazebo::components::Factory; diff --git a/src/EntityComponentManager.cc b/src/EntityComponentManager.cc index 376e7dd6be..d768971aa4 100644 --- a/src/EntityComponentManager.cc +++ b/src/EntityComponentManager.cc @@ -15,7 +15,7 @@ * */ -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/EntityComponentManager.hh" #include #include diff --git a/src/Joint.cc b/src/Joint.cc index 511289ff8a..e579a208ca 100644 --- a/src/Joint.cc +++ b/src/Joint.cc @@ -15,29 +15,29 @@ * */ -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/JointEffortLimitsCmd.hh" -#include "ignition/gazebo/components/JointForceCmd.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/JointPositionLimitsCmd.hh" -#include "ignition/gazebo/components/JointPositionReset.hh" -#include "ignition/gazebo/components/JointTransmittedWrench.hh" -#include "ignition/gazebo/components/JointType.hh" -#include "ignition/gazebo/components/JointVelocity.hh" -#include "ignition/gazebo/components/JointVelocityCmd.hh" -#include "ignition/gazebo/components/JointVelocityLimitsCmd.hh" -#include "ignition/gazebo/components/JointVelocityReset.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/ParentLinkName.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/ThreadPitch.hh" - -#include "ignition/gazebo/Joint.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/JointEffortLimitsCmd.hh" +#include "gz/sim/components/JointForceCmd.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/JointPositionLimitsCmd.hh" +#include "gz/sim/components/JointPositionReset.hh" +#include "gz/sim/components/JointTransmittedWrench.hh" +#include "gz/sim/components/JointType.hh" +#include "gz/sim/components/JointVelocity.hh" +#include "gz/sim/components/JointVelocityCmd.hh" +#include "gz/sim/components/JointVelocityLimitsCmd.hh" +#include "gz/sim/components/JointVelocityReset.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/ParentLinkName.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/ThreadPitch.hh" + +#include "gz/sim/Joint.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/Joint_TEST.cc b/src/Joint_TEST.cc index 1dc8e0e56a..8bdf8fea9f 100644 --- a/src/Joint_TEST.cc +++ b/src/Joint_TEST.cc @@ -19,12 +19,12 @@ #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Joint.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Sensor.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Joint.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Sensor.hh" ///////////////////////////////////////////////// TEST(JointTest, Constructor) diff --git a/src/Light.cc b/src/Light.cc index a3337bf110..fab8a01acb 100644 --- a/src/Light.cc +++ b/src/Light.cc @@ -15,19 +15,19 @@ * */ -#include +#include #include -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/LightType.hh" -#include "ignition/gazebo/components/LightCmd.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Pose.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/LightType.hh" +#include "gz/sim/components/LightCmd.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Pose.hh" -#include "ignition/gazebo/Light.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Light.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/Light_TEST.cc b/src/Light_TEST.cc index c435f3acd8..e4ca49eb70 100644 --- a/src/Light_TEST.cc +++ b/src/Light_TEST.cc @@ -19,12 +19,12 @@ #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Light.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Sensor.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Light.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Sensor.hh" ///////////////////////////////////////////////// TEST(LightTest, Constructor) diff --git a/src/ModelCommandAPI_TEST.cc b/src/ModelCommandAPI_TEST.cc index bfcb8cf333..ade1bf9b5c 100644 --- a/src/ModelCommandAPI_TEST.cc +++ b/src/ModelCommandAPI_TEST.cc @@ -20,7 +20,7 @@ #include #include -#include +#include #include "gz/sim/Server.hh" #include "gz/sim/test_config.hh" // NOLINT(build/include) diff --git a/src/Primitives.cc b/src/Primitives.cc index 9e34eac618..2b9cd89282 100644 --- a/src/Primitives.cc +++ b/src/Primitives.cc @@ -15,9 +15,9 @@ * */ -#include -#include -#include "ignition/gazebo/Primitives.hh" +#include +#include +#include "gz/sim/Primitives.hh" using namespace ignition; using namespace gazebo; diff --git a/src/Primitives_TEST.cc b/src/Primitives_TEST.cc index b6635e6144..112e948097 100644 --- a/src/Primitives_TEST.cc +++ b/src/Primitives_TEST.cc @@ -17,7 +17,7 @@ #include -#include +#include #include using PrimitiveShape = ignition::gazebo::PrimitiveShape; diff --git a/src/SdfEntityCreator_TEST.cc b/src/SdfEntityCreator_TEST.cc index 2fbd0d553e..884330e124 100644 --- a/src/SdfEntityCreator_TEST.cc +++ b/src/SdfEntityCreator_TEST.cc @@ -48,7 +48,7 @@ #include "gz/sim/components/Physics.hh" #include "gz/sim/components/Pose.hh" #include "gz/sim/components/Transparency.hh" -#include "ignition/gazebo/components/Visibility.hh" +#include "gz/sim/components/Visibility.hh" #include "gz/sim/components/Visual.hh" #include "gz/sim/components/World.hh" #include "gz/sim/SdfEntityCreator.hh" diff --git a/src/SdfGenerator_TEST.cc b/src/SdfGenerator_TEST.cc index f41ff646b4..9eda70e7c0 100644 --- a/src/SdfGenerator_TEST.cc +++ b/src/SdfGenerator_TEST.cc @@ -21,7 +21,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/Sensor.cc b/src/Sensor.cc index fbba159b08..8842c463a9 100644 --- a/src/Sensor.cc +++ b/src/Sensor.cc @@ -15,13 +15,13 @@ * */ -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Sensor.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Sensor.hh" -#include "ignition/gazebo/Sensor.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Sensor.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/Sensor_TEST.cc b/src/Sensor_TEST.cc index f518809b23..96234a97d9 100644 --- a/src/Sensor_TEST.cc +++ b/src/Sensor_TEST.cc @@ -19,11 +19,11 @@ #include -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Sensor.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Sensor.hh" ///////////////////////////////////////////////// TEST(SensorTest, Constructor) diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc index c62148dc7d..f2d8dfb4ca 100644 --- a/src/SimulationRunner.cc +++ b/src/SimulationRunner.cc @@ -27,7 +27,7 @@ #include "gz/sim/components/Sensor.hh" #include "gz/sim/components/Visual.hh" #include "gz/sim/components/World.hh" -#include "ignition/gazebo/components/ParentEntity.hh" +#include "gz/sim/components/ParentEntity.hh" #include "gz/sim/components/Physics.hh" #include "gz/sim/components/PhysicsCmd.hh" #include "gz/sim/components/Recreate.hh" diff --git a/src/SystemInternal.hh b/src/SystemInternal.hh index 0f0e6ff4d7..8eb1dae337 100644 --- a/src/SystemInternal.hh +++ b/src/SystemInternal.hh @@ -22,9 +22,9 @@ #include #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/System.hh" -#include "ignition/gazebo/SystemPluginPtr.hh" +#include "gz/sim/config.hh" +#include "gz/sim/System.hh" +#include "gz/sim/SystemPluginPtr.hh" namespace ignition { diff --git a/src/SystemManager.cc b/src/SystemManager.cc index 1397fa9354..8332301ecb 100644 --- a/src/SystemManager.cc +++ b/src/SystemManager.cc @@ -18,10 +18,10 @@ #include #include -#include +#include -#include "ignition/gazebo/components/SystemPluginInfo.hh" -#include "ignition/gazebo/Conversions.hh" +#include "gz/sim/components/SystemPluginInfo.hh" +#include "gz/sim/Conversions.hh" #include "SystemManager.hh" using namespace ignition; diff --git a/src/SystemManager.hh b/src/SystemManager.hh index f6883da4de..75d997d469 100644 --- a/src/SystemManager.hh +++ b/src/SystemManager.hh @@ -17,20 +17,20 @@ #ifndef IGNITION_GAZEBO_SYSTEMMANAGER_HH_ #define IGNITION_GAZEBO_SYSTEMMANAGER_HH_ -#include +#include #include #include #include #include -#include +#include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/Types.hh" +#include "gz/sim/config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Export.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/Types.hh" #include "SystemInternal.hh" diff --git a/src/SystemManager_TEST.cc b/src/SystemManager_TEST.cc index 63bec9b571..02a2957334 100644 --- a/src/SystemManager_TEST.cc +++ b/src/SystemManager_TEST.cc @@ -17,12 +17,12 @@ #include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/System.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/Types.hh" -#include "ignition/gazebo/components/SystemPluginInfo.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/System.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/Types.hh" +#include "gz/sim/components/SystemPluginInfo.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "SystemManager.hh" diff --git a/src/World.cc b/src/World.cc index 7c6aa87516..d1462b79b9 100644 --- a/src/World.cc +++ b/src/World.cc @@ -18,17 +18,17 @@ #include #include -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/Atmosphere.hh" -#include "ignition/gazebo/components/Gravity.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/MagneticField.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/Atmosphere.hh" +#include "gz/sim/components/Gravity.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/MagneticField.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" #include "gz/sim/components/ParentEntity.hh" -#include "ignition/gazebo/components/SphericalCoordinates.hh" +#include "gz/sim/components/SphericalCoordinates.hh" #include "gz/sim/components/World.hh" -#include "ignition/gazebo/World.hh" +#include "gz/sim/World.hh" class ignition::gazebo::WorldPrivate { diff --git a/src/WorldControl.hh b/src/WorldControl.hh index 9016e8c8f4..9e57ac458f 100644 --- a/src/WorldControl.hh +++ b/src/WorldControl.hh @@ -20,7 +20,7 @@ #include #include -#include "ignition/gazebo/config.hh" +#include "gz/sim/config.hh" namespace ignition { diff --git a/src/comms/Broker.cc b/src/comms/Broker.cc index 8c33c5fa21..3a78971b88 100644 --- a/src/comms/Broker.cc +++ b/src/comms/Broker.cc @@ -15,19 +15,19 @@ * */ -#include -#include -#include +#include +#include +#include #include #include #include -#include -#include "ignition/gazebo/comms/Broker.hh" -#include "ignition/gazebo/comms/MsgManager.hh" -#include "ignition/gazebo/Conversions.hh" -#include "ignition/gazebo/Util.hh" +#include +#include "gz/sim/comms/Broker.hh" +#include "gz/sim/comms/MsgManager.hh" +#include "gz/sim/Conversions.hh" +#include "gz/sim/Util.hh" /// \brief Private Broker data class. class ignition::gazebo::comms::Broker::Implementation diff --git a/src/comms/Broker_TEST.cc b/src/comms/Broker_TEST.cc index 66e263fa9b..0f84d14254 100644 --- a/src/comms/Broker_TEST.cc +++ b/src/comms/Broker_TEST.cc @@ -16,12 +16,12 @@ */ #include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/comms/Broker.hh" -#include "ignition/gazebo/comms/MsgManager.hh" +#include "gz/sim/comms/Broker.hh" +#include "gz/sim/comms/MsgManager.hh" #include "helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/src/comms/ICommsModel.cc b/src/comms/ICommsModel.cc index 7b0074821c..01a74ee965 100644 --- a/src/comms/ICommsModel.cc +++ b/src/comms/ICommsModel.cc @@ -20,13 +20,13 @@ #include #include -#include +#include #include -#include "ignition/gazebo/comms/Broker.hh" -#include "ignition/gazebo/comms/ICommsModel.hh" -#include "ignition/gazebo/comms/MsgManager.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/EventManager.hh" +#include "gz/sim/comms/Broker.hh" +#include "gz/sim/comms/ICommsModel.hh" +#include "gz/sim/comms/MsgManager.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/EventManager.hh" using namespace ignition; using namespace gazebo; diff --git a/src/comms/MsgManager.cc b/src/comms/MsgManager.cc index 4219588099..37575c897e 100644 --- a/src/comms/MsgManager.cc +++ b/src/comms/MsgManager.cc @@ -15,15 +15,15 @@ * */ -#include +#include #include #include -#include -#include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/comms/MsgManager.hh" +#include +#include +#include "gz/sim/config.hh" +#include "gz/sim/comms/MsgManager.hh" /// \brief Private MsgManager data class. class ignition::gazebo::comms::MsgManager::Implementation diff --git a/src/comms/MsgManager_TEST.cc b/src/comms/MsgManager_TEST.cc index b0e0989405..5986e6ff2c 100644 --- a/src/comms/MsgManager_TEST.cc +++ b/src/comms/MsgManager_TEST.cc @@ -16,11 +16,11 @@ */ #include -#include +#include #include -#include "ignition/gazebo/comms/MsgManager.hh" +#include "gz/sim/comms/MsgManager.hh" #include "helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/src/gui/GuiEvents.cc b/src/gui/GuiEvents.cc index b9ce7e8812..99237233f2 100644 --- a/src/gui/GuiEvents.cc +++ b/src/gui/GuiEvents.cc @@ -15,7 +15,7 @@ * */ -#include "ignition/gazebo/gui/GuiEvents.hh" +#include "gz/sim/gui/GuiEvents.hh" class ignition::gazebo::gui::events::GuiNewRemovedEntities::Implementation { diff --git a/src/gui/GuiEvents_TEST.cc b/src/gui/GuiEvents_TEST.cc index cb0bebc999..c0b5e13378 100644 --- a/src/gui/GuiEvents_TEST.cc +++ b/src/gui/GuiEvents_TEST.cc @@ -17,8 +17,8 @@ #include -#include "ignition/gazebo/test_config.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" +#include "gz/sim/test_config.hh" +#include "gz/sim/gui/GuiEvents.hh" using namespace ignition; using namespace gazebo; diff --git a/src/gui/Gui_clean_exit_TEST.cc b/src/gui/Gui_clean_exit_TEST.cc index 4e548ec80e..8dc8c30e52 100644 --- a/src/gui/Gui_clean_exit_TEST.cc +++ b/src/gui/Gui_clean_exit_TEST.cc @@ -20,13 +20,13 @@ #include #include #include -#include -#include +#include +#include #include "helpers/EnvTestFixture.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/gui/Gui.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/Server.hh" +#include "gz/sim/gui/Gui.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) using namespace ignition; diff --git a/src/gui/plugins/align_tool/AlignTool.cc b/src/gui/plugins/align_tool/AlignTool.cc index 765ab5b51b..5fdbcf4f62 100644 --- a/src/gui/plugins/align_tool/AlignTool.cc +++ b/src/gui/plugins/align_tool/AlignTool.cc @@ -16,7 +16,7 @@ */ #include -#include +#include #include #include @@ -27,7 +27,7 @@ #include #include -#include +#include #include #include #include @@ -37,7 +37,7 @@ #include #include #include -#include +#include #include #include "gz/sim/EntityComponentManager.hh" diff --git a/src/gui/plugins/banana_for_scale/BananaForScale.cc b/src/gui/plugins/banana_for_scale/BananaForScale.cc index 469a442950..a134466d00 100644 --- a/src/gui/plugins/banana_for_scale/BananaForScale.cc +++ b/src/gui/plugins/banana_for_scale/BananaForScale.cc @@ -21,16 +21,16 @@ #include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include -#include +#include +#include -#include "ignition/gazebo/gui/GuiEvents.hh" +#include "gz/sim/gui/GuiEvents.hh" namespace ignition::gazebo { diff --git a/src/gui/plugins/banana_for_scale/BananaForScale.hh b/src/gui/plugins/banana_for_scale/BananaForScale.hh index 7016e22392..36e71d28f5 100644 --- a/src/gui/plugins/banana_for_scale/BananaForScale.hh +++ b/src/gui/plugins/banana_for_scale/BananaForScale.hh @@ -20,7 +20,7 @@ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 6c366f1f84..c95a915ea4 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -234,7 +234,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const msgs::Light &_data) ////////////////////////////////////////////////// template<> -void gazebo::setData(QStandardItem *_item, +void ignition::gazebo::setData(QStandardItem *_item, const math::Vector3d &_data) { if (nullptr == _item) diff --git a/src/gui/plugins/component_inspector/ComponentInspector.hh b/src/gui/plugins/component_inspector/ComponentInspector.hh index 807b777a15..2060068510 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.hh +++ b/src/gui/plugins/component_inspector/ComponentInspector.hh @@ -34,7 +34,7 @@ #include "Types.hh" -#include +#include Q_DECLARE_METATYPE(ignition::gazebo::ComponentTypeId) diff --git a/src/gui/plugins/component_inspector/SystemPluginInfo.cc b/src/gui/plugins/component_inspector/SystemPluginInfo.cc index e8ecf8a932..6fbf8c7950 100644 --- a/src/gui/plugins/component_inspector/SystemPluginInfo.cc +++ b/src/gui/plugins/component_inspector/SystemPluginInfo.cc @@ -14,10 +14,10 @@ * limitations under the License. * */ -#include +#include -#include -#include +#include +#include #include "SystemPluginInfo.hh" #include "ComponentInspector.hh" diff --git a/src/gui/plugins/component_inspector/SystemPluginInfo.hh b/src/gui/plugins/component_inspector/SystemPluginInfo.hh index 43c2698c9c..80569ef76c 100644 --- a/src/gui/plugins/component_inspector/SystemPluginInfo.hh +++ b/src/gui/plugins/component_inspector/SystemPluginInfo.hh @@ -17,7 +17,7 @@ #ifndef IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_SYSTEMINFO_HH_ #define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_SYSTEMINFO_HH_ -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/EntityComponentManager.hh" #include #include diff --git a/src/gui/plugins/component_inspector_editor/AirPressure.cc b/src/gui/plugins/component_inspector_editor/AirPressure.cc index 5f8baf3d0a..65d3b10cf8 100644 --- a/src/gui/plugins/component_inspector_editor/AirPressure.cc +++ b/src/gui/plugins/component_inspector_editor/AirPressure.cc @@ -16,9 +16,9 @@ */ #include -#include -#include -#include +#include +#include +#include #include "AirPressure.hh" #include "ComponentInspectorEditor.hh" diff --git a/src/gui/plugins/component_inspector_editor/Altimeter.cc b/src/gui/plugins/component_inspector_editor/Altimeter.cc index 480a6c5eaa..672b617fa3 100644 --- a/src/gui/plugins/component_inspector_editor/Altimeter.cc +++ b/src/gui/plugins/component_inspector_editor/Altimeter.cc @@ -16,8 +16,8 @@ */ #include -#include -#include +#include +#include #include "Altimeter.hh" #include "ComponentInspectorEditor.hh" diff --git a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc index 8c14082c2a..6aacd3b4dc 100644 --- a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc +++ b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc @@ -22,62 +22,62 @@ #include #include -#include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/AngularAcceleration.hh" -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/BatterySoC.hh" -#include "ignition/gazebo/components/CastShadows.hh" -#include "ignition/gazebo/components/CenterOfVolume.hh" -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Gravity.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/LaserRetro.hh" -#include "ignition/gazebo/components/Level.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/LightCmd.hh" -#include "ignition/gazebo/components/LightType.hh" -#include "ignition/gazebo/components/LinearAcceleration.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/LinearVelocitySeed.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/MagneticField.hh" -#include "ignition/gazebo/components/Material.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/ParentLinkName.hh" -#include "ignition/gazebo/components/Performer.hh" -#include "ignition/gazebo/components/PerformerAffinity.hh" -#include "ignition/gazebo/components/Physics.hh" -#include "ignition/gazebo/components/PhysicsEnginePlugin.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Recreate.hh" -#include "ignition/gazebo/components/RenderEngineGuiPlugin.hh" -#include "ignition/gazebo/components/RenderEngineServerPlugin.hh" -#include "ignition/gazebo/components/SelfCollide.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/SourceFilePath.hh" -#include "ignition/gazebo/components/SphericalCoordinates.hh" -#include "ignition/gazebo/components/Static.hh" -#include "ignition/gazebo/components/ThreadPitch.hh" -#include "ignition/gazebo/components/Transparency.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/Volume.hh" -#include "ignition/gazebo/components/WindMode.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" -#include "ignition/gazebo/Util.hh" +#include +#include +#include +#include +#include +#include +#include + +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/AngularAcceleration.hh" +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/BatterySoC.hh" +#include "gz/sim/components/CastShadows.hh" +#include "gz/sim/components/CenterOfVolume.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Gravity.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/LaserRetro.hh" +#include "gz/sim/components/Level.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/LightCmd.hh" +#include "gz/sim/components/LightType.hh" +#include "gz/sim/components/LinearAcceleration.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/LinearVelocitySeed.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/MagneticField.hh" +#include "gz/sim/components/Material.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/ParentLinkName.hh" +#include "gz/sim/components/Performer.hh" +#include "gz/sim/components/PerformerAffinity.hh" +#include "gz/sim/components/Physics.hh" +#include "gz/sim/components/PhysicsEnginePlugin.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Recreate.hh" +#include "gz/sim/components/RenderEngineGuiPlugin.hh" +#include "gz/sim/components/RenderEngineServerPlugin.hh" +#include "gz/sim/components/SelfCollide.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/SourceFilePath.hh" +#include "gz/sim/components/SphericalCoordinates.hh" +#include "gz/sim/components/Static.hh" +#include "gz/sim/components/ThreadPitch.hh" +#include "gz/sim/components/Transparency.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/Volume.hh" +#include "gz/sim/components/WindMode.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/gui/GuiEvents.hh" +#include "gz/sim/Util.hh" #include "AirPressure.hh" #include "Altimeter.hh" diff --git a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.hh b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.hh index f4e2ac3b8d..a68c48f47e 100644 --- a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.hh +++ b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.hh @@ -26,13 +26,13 @@ #include #include -#include +#include -#include -#include -#include +#include +#include +#include -#include +#include #include "Types.hh" Q_DECLARE_METATYPE(ignition::gazebo::ComponentTypeId) diff --git a/src/gui/plugins/component_inspector_editor/Imu.cc b/src/gui/plugins/component_inspector_editor/Imu.cc index 4dbd6a099a..5a2b4beb04 100644 --- a/src/gui/plugins/component_inspector_editor/Imu.cc +++ b/src/gui/plugins/component_inspector_editor/Imu.cc @@ -16,9 +16,9 @@ */ #include -#include -#include -#include +#include +#include +#include #include "ComponentInspectorEditor.hh" #include "Imu.hh" diff --git a/src/gui/plugins/component_inspector_editor/JointType.cc b/src/gui/plugins/component_inspector_editor/JointType.cc index b8f70106fe..25191b0303 100644 --- a/src/gui/plugins/component_inspector_editor/JointType.cc +++ b/src/gui/plugins/component_inspector_editor/JointType.cc @@ -16,11 +16,11 @@ */ #include -#include -#include "ignition/gazebo/components/JointType.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Recreate.hh" -#include +#include +#include "gz/sim/components/JointType.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Recreate.hh" +#include #include "JointType.hh" #include "ComponentInspectorEditor.hh" diff --git a/src/gui/plugins/component_inspector_editor/Lidar.cc b/src/gui/plugins/component_inspector_editor/Lidar.cc index 36ae02162f..00cde19708 100644 --- a/src/gui/plugins/component_inspector_editor/Lidar.cc +++ b/src/gui/plugins/component_inspector_editor/Lidar.cc @@ -16,9 +16,9 @@ */ #include -#include -#include -#include +#include +#include +#include #include "ComponentInspectorEditor.hh" #include "Lidar.hh" diff --git a/src/gui/plugins/component_inspector_editor/Magnetometer.cc b/src/gui/plugins/component_inspector_editor/Magnetometer.cc index 3ba125ae70..0c2fa64ef3 100644 --- a/src/gui/plugins/component_inspector_editor/Magnetometer.cc +++ b/src/gui/plugins/component_inspector_editor/Magnetometer.cc @@ -16,8 +16,8 @@ */ #include -#include -#include +#include +#include #include "ComponentInspectorEditor.hh" #include "Magnetometer.hh" diff --git a/src/gui/plugins/component_inspector_editor/ModelEditor.cc b/src/gui/plugins/component_inspector_editor/ModelEditor.cc index 91699dd528..2f88fcd717 100644 --- a/src/gui/plugins/component_inspector_editor/ModelEditor.cc +++ b/src/gui/plugins/component_inspector_editor/ModelEditor.cc @@ -23,11 +23,11 @@ #include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include @@ -39,15 +39,15 @@ #include #include -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Recreate.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/SdfEntityCreator.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Recreate.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/SdfEntityCreator.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/gui/GuiEvents.hh" +#include "gz/sim/Util.hh" #include "ModelEditor.hh" diff --git a/src/gui/plugins/component_inspector_editor/ModelEditor.hh b/src/gui/plugins/component_inspector_editor/ModelEditor.hh index bfc09df897..8234dfb5ac 100644 --- a/src/gui/plugins/component_inspector_editor/ModelEditor.hh +++ b/src/gui/plugins/component_inspector_editor/ModelEditor.hh @@ -22,7 +22,7 @@ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/component_inspector_editor/Pose3d.cc b/src/gui/plugins/component_inspector_editor/Pose3d.cc index 42a349d8f8..e8a8d3d701 100644 --- a/src/gui/plugins/component_inspector_editor/Pose3d.cc +++ b/src/gui/plugins/component_inspector_editor/Pose3d.cc @@ -14,13 +14,13 @@ * limitations under the License. * */ -#include +#include -#include -#include -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Recreate.hh" -#include +#include +#include +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Recreate.hh" +#include #include "ComponentInspectorEditor.hh" #include "Pose3d.hh" diff --git a/src/gui/plugins/component_inspector_editor/Pose3d.hh b/src/gui/plugins/component_inspector_editor/Pose3d.hh index 5407edbc02..2a4f27973a 100644 --- a/src/gui/plugins/component_inspector_editor/Pose3d.hh +++ b/src/gui/plugins/component_inspector_editor/Pose3d.hh @@ -18,7 +18,7 @@ #define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_POSE3D_HH_ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/component_inspector_editor/Types.hh b/src/gui/plugins/component_inspector_editor/Types.hh index b8eb0ff422..78e8463d1b 100644 --- a/src/gui/plugins/component_inspector_editor/Types.hh +++ b/src/gui/plugins/component_inspector_editor/Types.hh @@ -23,7 +23,7 @@ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/copy_paste/CopyPaste.cc b/src/gui/plugins/copy_paste/CopyPaste.cc index 7b633c3176..52bb86b9ce 100644 --- a/src/gui/plugins/copy_paste/CopyPaste.cc +++ b/src/gui/plugins/copy_paste/CopyPaste.cc @@ -19,15 +19,15 @@ #include #include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" +#include +#include +#include +#include +#include +#include + +#include "gz/sim/components/Name.hh" +#include "gz/sim/gui/GuiEvents.hh" #include "CopyPaste.hh" diff --git a/src/gui/plugins/copy_paste/CopyPaste.hh b/src/gui/plugins/copy_paste/CopyPaste.hh index 9b54d85b94..0ac3dc3301 100644 --- a/src/gui/plugins/copy_paste/CopyPaste.hh +++ b/src/gui/plugins/copy_paste/CopyPaste.hh @@ -20,9 +20,9 @@ #include -#include +#include -#include "ignition/gazebo/gui/GuiSystem.hh" +#include "gz/sim/gui/GuiSystem.hh" namespace ignition { diff --git a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc index ebba5b6c54..ff916ff00b 100644 --- a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc +++ b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc @@ -22,18 +22,18 @@ #include -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include -#include +#include -#include -#include -#include +#include +#include +#include namespace ignition::gazebo { diff --git a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh index 4ed5858f3a..e7fd8b0966 100644 --- a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh +++ b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh @@ -20,11 +20,11 @@ #include -#include +#include -#include +#include -#include +#include namespace ignition { diff --git a/src/gui/plugins/lights/Lights.cc b/src/gui/plugins/lights/Lights.cc index 81ff6554ef..395c4607d9 100644 --- a/src/gui/plugins/lights/Lights.cc +++ b/src/gui/plugins/lights/Lights.cc @@ -17,23 +17,23 @@ #include "Lights.hh" -#include -#include +#include +#include #include #include #include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Primitives.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Primitives.hh" namespace ignition::gazebo { diff --git a/src/gui/plugins/lights/Lights.hh b/src/gui/plugins/lights/Lights.hh index 9caecfbbef..49fd8dd063 100644 --- a/src/gui/plugins/lights/Lights.hh +++ b/src/gui/plugins/lights/Lights.hh @@ -20,7 +20,7 @@ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/plotting/Plotting.cc b/src/gui/plugins/plotting/Plotting.cc index a6f5228ae5..902e0e5962 100644 --- a/src/gui/plugins/plotting/Plotting.cc +++ b/src/gui/plugins/plotting/Plotting.cc @@ -17,27 +17,27 @@ #include "Plotting.hh" -#include - -#include "ignition/gazebo/components/AngularAcceleration.hh" -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/CastShadows.hh" -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Gravity.hh" -#include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/LinearAcceleration.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/LinearVelocitySeed.hh" -#include "ignition/gazebo/components/MagneticField.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Physics.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/PoseCmd.hh" -#include "ignition/gazebo/components/SphericalCoordinates.hh" -#include "ignition/gazebo/components/Static.hh" -#include "ignition/gazebo/components/WindMode.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/EntityComponentManager.hh" +#include + +#include "gz/sim/components/AngularAcceleration.hh" +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/CastShadows.hh" +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Gravity.hh" +#include "gz/sim/components/Light.hh" +#include "gz/sim/components/LinearAcceleration.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/LinearVelocitySeed.hh" +#include "gz/sim/components/MagneticField.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Physics.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/PoseCmd.hh" +#include "gz/sim/components/SphericalCoordinates.hh" +#include "gz/sim/components/Static.hh" +#include "gz/sim/components/WindMode.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/EntityComponentManager.hh" namespace ignition::gazebo { diff --git a/src/gui/plugins/plotting/Plotting.hh b/src/gui/plugins/plotting/Plotting.hh index 9e85c62264..578bb7ff6c 100644 --- a/src/gui/plugins/plotting/Plotting.hh +++ b/src/gui/plugins/plotting/Plotting.hh @@ -17,14 +17,14 @@ #ifndef IGNITION_GUI_PLUGINS_PLOTTING_HH_ #define IGNITION_GUI_PLUGINS_PLOTTING_HH_ -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include #include "sdf/Physics.hh" diff --git a/src/gui/plugins/resource_spawner/ResourceSpawner.cc b/src/gui/plugins/resource_spawner/ResourceSpawner.cc index 935f2c7201..205edac008 100644 --- a/src/gui/plugins/resource_spawner/ResourceSpawner.cc +++ b/src/gui/plugins/resource_spawner/ResourceSpawner.cc @@ -33,7 +33,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index c73fcbd927..20a4212356 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -49,7 +49,7 @@ #include #include -#include +#include #include #include #include diff --git a/src/gui/plugins/scene_manager/GzSceneManager.cc b/src/gui/plugins/scene_manager/GzSceneManager.cc index 9d0c6b1338..62bdf3c70d 100644 --- a/src/gui/plugins/scene_manager/GzSceneManager.cc +++ b/src/gui/plugins/scene_manager/GzSceneManager.cc @@ -26,21 +26,21 @@ #include -#include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/SystemPluginInfo.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" -#include "ignition/gazebo/rendering/RenderUtil.hh" +#include +#include +#include +#include +#include +#include +#include + +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/SystemPluginInfo.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/gui/GuiEvents.hh" +#include "gz/sim/rendering/RenderUtil.hh" namespace ignition { diff --git a/src/gui/plugins/scene_manager/GzSceneManager.hh b/src/gui/plugins/scene_manager/GzSceneManager.hh index 34208e0b33..c84f33322e 100644 --- a/src/gui/plugins/scene_manager/GzSceneManager.hh +++ b/src/gui/plugins/scene_manager/GzSceneManager.hh @@ -20,7 +20,7 @@ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/select_entities/SelectEntities.cc b/src/gui/plugins/select_entities/SelectEntities.cc index 921dd03242..fb5ab946f6 100644 --- a/src/gui/plugins/select_entities/SelectEntities.cc +++ b/src/gui/plugins/select_entities/SelectEntities.cc @@ -23,20 +23,20 @@ #include -#include -#include -#include -#include -#include -#include -#include -#include -#include "ignition/rendering/Camera.hh" - -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/rendering/RenderUtil.hh" +#include +#include +#include +#include +#include +#include +#include +#include +#include "gz/rendering/Camera.hh" + +#include "gz/sim/Entity.hh" +#include "gz/sim/gui/GuiEvents.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/rendering/RenderUtil.hh" #include "SelectEntities.hh" diff --git a/src/gui/plugins/select_entities/SelectEntities.hh b/src/gui/plugins/select_entities/SelectEntities.hh index cdbd3a172c..6643ab539e 100644 --- a/src/gui/plugins/select_entities/SelectEntities.hh +++ b/src/gui/plugins/select_entities/SelectEntities.hh @@ -20,7 +20,7 @@ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/spawn/Spawn.cc b/src/gui/plugins/spawn/Spawn.cc index be60287e52..cc33737aa4 100644 --- a/src/gui/plugins/spawn/Spawn.cc +++ b/src/gui/plugins/spawn/Spawn.cc @@ -17,8 +17,8 @@ #include "Spawn.hh" -#include -#include +#include +#include #include #include @@ -27,35 +27,35 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include -#include -#include -#include -#include +#include +#include +#include +#include -#include -#include +#include +#include -#include +#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include -#include -#include +#include +#include #include -#include "ignition/gazebo/rendering/RenderUtil.hh" -#include "ignition/gazebo/rendering/SceneManager.hh" +#include "gz/sim/rendering/RenderUtil.hh" +#include "gz/sim/rendering/SceneManager.hh" namespace ignition::gazebo { diff --git a/src/gui/plugins/spawn/Spawn.hh b/src/gui/plugins/spawn/Spawn.hh index f87ec4c160..43e5844919 100644 --- a/src/gui/plugins/spawn/Spawn.hh +++ b/src/gui/plugins/spawn/Spawn.hh @@ -20,8 +20,8 @@ #include -#include -#include +#include +#include namespace ignition { diff --git a/src/gui/plugins/transform_control/TransformControl.cc b/src/gui/plugins/transform_control/TransformControl.cc index bfe09786aa..5f51340eac 100644 --- a/src/gui/plugins/transform_control/TransformControl.cc +++ b/src/gui/plugins/transform_control/TransformControl.cc @@ -27,11 +27,11 @@ #include #include -#include -#include +#include +#include #include -#include -#include +#include +#include #include #include #include @@ -40,7 +40,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/gui/plugins/video_recorder/VideoRecorder.cc b/src/gui/plugins/video_recorder/VideoRecorder.cc index 64a6a66a27..061e008b84 100644 --- a/src/gui/plugins/video_recorder/VideoRecorder.cc +++ b/src/gui/plugins/video_recorder/VideoRecorder.cc @@ -25,15 +25,15 @@ #include #include -#include -#include +#include +#include #include -#include -#include +#include +#include #include -#include -#include -#include +#include +#include +#include #include #include diff --git a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc index e995949bab..34305ecc5a 100644 --- a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc +++ b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc @@ -17,8 +17,8 @@ #include "VisualizationCapabilities.hh" -#include -#include +#include +#include #include #include @@ -32,33 +32,33 @@ #include #include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -#include - -#include "ignition/rendering/AxisVisual.hh" -#include "ignition/rendering/Capsule.hh" -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include + +#include "gz/rendering/AxisVisual.hh" +#include "gz/rendering/Capsule.hh" +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include #include #include @@ -69,29 +69,29 @@ #include #include -#include "ignition/gazebo/components/CastShadows.hh" -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/Geometry.hh" -#include "ignition/gazebo/components/Inertial.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/JointType.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/ParentLinkName.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Scene.hh" -#include "ignition/gazebo/components/Transparency.hh" -#include "ignition/gazebo/components/Visibility.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/components/World.hh" - -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/rendering/RenderUtil.hh" -#include "ignition/gazebo/rendering/SceneManager.hh" +#include "gz/sim/components/CastShadows.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/Geometry.hh" +#include "gz/sim/components/Inertial.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/JointType.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/ParentLinkName.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Scene.hh" +#include "gz/sim/components/Transparency.hh" +#include "gz/sim/components/Visibility.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/components/World.hh" + +#include "gz/sim/Util.hh" +#include "gz/sim/rendering/RenderUtil.hh" +#include "gz/sim/rendering/SceneManager.hh" namespace ignition::gazebo { diff --git a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.hh b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.hh index 99a400f7eb..9d9d646448 100644 --- a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.hh +++ b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.hh @@ -20,7 +20,7 @@ #include -#include +#include namespace ignition { diff --git a/src/gui/plugins/visualize_contacts/VisualizeContacts.cc b/src/gui/plugins/visualize_contacts/VisualizeContacts.cc index 4420d90d05..58b4339c4a 100644 --- a/src/gui/plugins/visualize_contacts/VisualizeContacts.cc +++ b/src/gui/plugins/visualize_contacts/VisualizeContacts.cc @@ -15,8 +15,8 @@ * */ -#include -#include +#include +#include #include #include @@ -24,27 +24,27 @@ #include #include -#include +#include -#include +#include -#include -#include +#include +#include -#include +#include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/ContactSensor.hh" -#include "ignition/gazebo/components/ContactSensorData.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/gui/GuiEvents.hh" -#include "ignition/gazebo/rendering/RenderUtil.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/ContactSensor.hh" +#include "gz/sim/components/ContactSensorData.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/gui/GuiEvents.hh" +#include "gz/sim/rendering/RenderUtil.hh" #include "VisualizeContacts.hh" diff --git a/src/gui/plugins/visualize_contacts/VisualizeContacts.hh b/src/gui/plugins/visualize_contacts/VisualizeContacts.hh index f1c6211084..333d8edf60 100644 --- a/src/gui/plugins/visualize_contacts/VisualizeContacts.hh +++ b/src/gui/plugins/visualize_contacts/VisualizeContacts.hh @@ -20,9 +20,9 @@ #include -#include +#include -#include "ignition/gui/qt.h" +#include "gz/gui/qt.h" namespace ignition { diff --git a/src/gui/plugins/visualize_lidar/VisualizeLidar.cc b/src/gui/plugins/visualize_lidar/VisualizeLidar.cc index 1a39fcffdf..1a1a0ea6a7 100644 --- a/src/gui/plugins/visualize_lidar/VisualizeLidar.cc +++ b/src/gui/plugins/visualize_lidar/VisualizeLidar.cc @@ -24,41 +24,41 @@ #include #include -#include -#include +#include +#include -#include +#include -#include -#include +#include +#include -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/rendering/RenderUtil.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/rendering/RenderUtil.hh" -#include "ignition/rendering/RenderTypes.hh" -#include "ignition/rendering/RenderingIface.hh" -#include "ignition/rendering/RenderEngine.hh" -#include "ignition/rendering/Scene.hh" -#include "ignition/rendering/LidarVisual.hh" +#include "gz/rendering/RenderTypes.hh" +#include "gz/rendering/RenderingIface.hh" +#include "gz/rendering/RenderEngine.hh" +#include "gz/rendering/Scene.hh" +#include "gz/rendering/LidarVisual.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Util.hh" -#include "ignition/msgs/laserscan.pb.h" +#include "gz/msgs/laserscan.pb.h" namespace ignition { diff --git a/src/gui/plugins/visualize_lidar/VisualizeLidar.hh b/src/gui/plugins/visualize_lidar/VisualizeLidar.hh index 7eebe69977..fe0bcdbad8 100644 --- a/src/gui/plugins/visualize_lidar/VisualizeLidar.hh +++ b/src/gui/plugins/visualize_lidar/VisualizeLidar.hh @@ -20,9 +20,9 @@ #include -#include "ignition/msgs/laserscan.pb.h" -#include "ignition/gazebo/gui/GuiSystem.hh" -#include "ignition/gui/qt.h" +#include "gz/msgs/laserscan.pb.h" +#include "gz/sim/gui/GuiSystem.hh" +#include "gz/gui/qt.h" namespace ignition { diff --git a/src/network/PeerTracker_TEST.cc b/src/network/PeerTracker_TEST.cc index da26ebb84a..fdc1d0d5d9 100644 --- a/src/network/PeerTracker_TEST.cc +++ b/src/network/PeerTracker_TEST.cc @@ -18,8 +18,8 @@ #include #include -#include -#include +#include +#include #include #include "PeerTracker.hh" diff --git a/src/rendering/MarkerManager.cc b/src/rendering/MarkerManager.cc index 9307cc492c..e66e356348 100644 --- a/src/rendering/MarkerManager.cc +++ b/src/rendering/MarkerManager.cc @@ -21,7 +21,7 @@ #include #include -#include +#include #include #include "gz/sim/Events.hh" diff --git a/src/systems/buoyancy/Buoyancy.cc b/src/systems/buoyancy/Buoyancy.cc index b3e9c0abe1..5347737ebb 100644 --- a/src/systems/buoyancy/Buoyancy.cc +++ b/src/systems/buoyancy/Buoyancy.cc @@ -42,7 +42,7 @@ #include "gz/sim/components/Gravity.hh" #include "gz/sim/components/Inertial.hh" #include "gz/sim/components/Link.hh" -#include "ignition/gazebo/components/ParentEntity.hh" +#include "gz/sim/components/ParentEntity.hh" #include "gz/sim/components/Pose.hh" #include "gz/sim/components/Volume.hh" #include "gz/sim/components/World.hh" diff --git a/src/systems/buoyancy_engine/BuoyancyEngine.cc b/src/systems/buoyancy_engine/BuoyancyEngine.cc index d128de4581..d200e22cdd 100644 --- a/src/systems/buoyancy_engine/BuoyancyEngine.cc +++ b/src/systems/buoyancy_engine/BuoyancyEngine.cc @@ -21,14 +21,14 @@ #include #include -#include -#include -#include -#include - -#include -#include -#include +#include +#include +#include +#include + +#include +#include +#include #include "BuoyancyEngine.hh" diff --git a/src/systems/buoyancy_engine/BuoyancyEngine.hh b/src/systems/buoyancy_engine/BuoyancyEngine.hh index 1e6f6747b5..faa0536c37 100644 --- a/src/systems/buoyancy_engine/BuoyancyEngine.hh +++ b/src/systems/buoyancy_engine/BuoyancyEngine.hh @@ -17,7 +17,7 @@ #ifndef IGNITION_GAZEBO_SYSTEMS_BUOYANCYENGINE_HH_ #define IGNITION_GAZEBO_SYSTEMS_BUOYANCYENGINE_HH_ -#include +#include #include diff --git a/src/systems/comms_endpoint/CommsEndpoint.cc b/src/systems/comms_endpoint/CommsEndpoint.cc index 98c4522bac..4202be96e2 100644 --- a/src/systems/comms_endpoint/CommsEndpoint.cc +++ b/src/systems/comms_endpoint/CommsEndpoint.cc @@ -15,19 +15,19 @@ * */ -#include -#include +#include +#include #include #include #include -#include -#include -#include +#include +#include +#include #include -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" #include "CommsEndpoint.hh" using namespace ignition; diff --git a/src/systems/comms_endpoint/CommsEndpoint.hh b/src/systems/comms_endpoint/CommsEndpoint.hh index a21e9b3089..d41841b45c 100644 --- a/src/systems/comms_endpoint/CommsEndpoint.hh +++ b/src/systems/comms_endpoint/CommsEndpoint.hh @@ -19,9 +19,9 @@ #include -#include +#include #include -#include "ignition/gazebo/System.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/detachable_joint/DetachableJoint.cc b/src/systems/detachable_joint/DetachableJoint.cc index c161247b28..15885a14f0 100644 --- a/src/systems/detachable_joint/DetachableJoint.cc +++ b/src/systems/detachable_joint/DetachableJoint.cc @@ -96,9 +96,14 @@ void DetachableJoint::Configure(const Entity &_entity, } // Setup detach topic - std::string defaultTopic{"/model/" + this->model.Name(_ecm) + - "/detachable_joint/detach"}; - this->topic = _sdf->Get("topic", defaultTopic).first; + std::vector topics; + if (_sdf->HasElement("topic")) + { + topics.push_back(_sdf->Get("topic")); + } + topics.push_back("/model/" + this->model.Name(_ecm) + + "/detachable_joint/detach"); + this->topic = validTopic(topics); this->suppressChildWarning = _sdf->Get("suppress_child_warning", this->suppressChildWarning) diff --git a/src/systems/follow_actor/FollowActor.cc b/src/systems/follow_actor/FollowActor.cc index f55c65c8ce..aad9a9e58e 100644 --- a/src/systems/follow_actor/FollowActor.cc +++ b/src/systems/follow_actor/FollowActor.cc @@ -17,15 +17,15 @@ #include -#include +#include -#include +#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include "FollowActor.hh" diff --git a/src/systems/follow_actor/FollowActor.hh b/src/systems/follow_actor/FollowActor.hh index 6c6023d836..019f22d57f 100644 --- a/src/systems/follow_actor/FollowActor.hh +++ b/src/systems/follow_actor/FollowActor.hh @@ -18,8 +18,8 @@ #define IGNITION_GAZEBO_SYSTEMS_FOLLOWACTOR_HH_ #include -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/force_torque/ForceTorque.cc b/src/systems/force_torque/ForceTorque.cc index 7ebd91c3d2..21b15f4243 100644 --- a/src/systems/force_torque/ForceTorque.cc +++ b/src/systems/force_torque/ForceTorque.cc @@ -21,30 +21,30 @@ #include #include -#include +#include #include -#include - -#include - -#include -#include - -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/ForceTorque.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointTransmittedWrench.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/ParentLinkName.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Util.hh" +#include + +#include + +#include +#include + +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/ForceTorque.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointTransmittedWrench.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/ParentLinkName.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/force_torque/ForceTorque.hh b/src/systems/force_torque/ForceTorque.hh index 5df5652fb0..ed4d40e387 100644 --- a/src/systems/force_torque/ForceTorque.hh +++ b/src/systems/force_torque/ForceTorque.hh @@ -18,8 +18,8 @@ #define IGNITION_GAZEBO_SYSTEMS_FORCE_TORQUE_HH_ #include -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/hydrodynamics/Hydrodynamics.cc b/src/systems/hydrodynamics/Hydrodynamics.cc index 4891165dda..a6e67c3b26 100644 --- a/src/systems/hydrodynamics/Hydrodynamics.cc +++ b/src/systems/hydrodynamics/Hydrodynamics.cc @@ -18,20 +18,20 @@ #include -#include +#include -#include "ignition/msgs/vector3d.pb.h" +#include "gz/msgs/vector3d.pb.h" -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/System.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/System.hh" +#include "gz/sim/Util.hh" -#include "ignition/transport/Node.hh" +#include "gz/transport/Node.hh" #include "Hydrodynamics.hh" diff --git a/src/systems/hydrodynamics/Hydrodynamics.hh b/src/systems/hydrodynamics/Hydrodynamics.hh index 0dd8cf3b9e..53187133ad 100644 --- a/src/systems/hydrodynamics/Hydrodynamics.hh +++ b/src/systems/hydrodynamics/Hydrodynamics.hh @@ -17,7 +17,7 @@ #ifndef IGNITION_GAZEBO_SYSTEMS_HYDRODYNAMICS_HH_ #define IGNITION_GAZEBO_SYSTEMS_HYDRODYNAMICS_HH_ -#include +#include #include namespace ignition diff --git a/src/systems/joint_traj_control/JointTrajectoryController.cc b/src/systems/joint_traj_control/JointTrajectoryController.cc index d7cb345e60..c72ef9e457 100644 --- a/src/systems/joint_traj_control/JointTrajectoryController.cc +++ b/src/systems/joint_traj_control/JointTrajectoryController.cc @@ -15,25 +15,25 @@ * */ -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -#include -#include -#include -#include -#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include #include #include diff --git a/src/systems/joint_traj_control/JointTrajectoryController.hh b/src/systems/joint_traj_control/JointTrajectoryController.hh index fb60279d1d..0caa15181a 100644 --- a/src/systems/joint_traj_control/JointTrajectoryController.hh +++ b/src/systems/joint_traj_control/JointTrajectoryController.hh @@ -18,7 +18,7 @@ #ifndef IGNITION_GAZEBO_SYSTEMS_JOINT_TRAJECTORY_CONTROLLER_HH_ #define IGNITION_GAZEBO_SYSTEMS_JOINT_TRAJECTORY_CONTROLLER_HH_ -#include +#include #include namespace ignition diff --git a/src/systems/label/Label.cc b/src/systems/label/Label.cc index 09986de104..1f76d0bd0a 100644 --- a/src/systems/label/Label.cc +++ b/src/systems/label/Label.cc @@ -19,14 +19,14 @@ #include #include -#include +#include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/SemanticLabel.hh" -#include "ignition/gazebo/components/Visual.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/SemanticLabel.hh" +#include "gz/sim/components/Visual.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/label/Label.hh b/src/systems/label/Label.hh index a0d6fffde6..4f09d886de 100644 --- a/src/systems/label/Label.hh +++ b/src/systems/label/Label.hh @@ -19,8 +19,8 @@ #include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/System.hh" +#include "gz/sim/config.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/log/LogPlayback.cc b/src/systems/log/LogPlayback.cc index e1e99dec25..49719c6f9f 100644 --- a/src/systems/log/LogPlayback.cc +++ b/src/systems/log/LogPlayback.cc @@ -17,7 +17,6 @@ #include "LogPlayback.hh" -#include #include #include diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc index e0c7dd86ab..9b8325c629 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc @@ -31,7 +31,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/systems/mecanum_drive/MecanumDrive.cc b/src/systems/mecanum_drive/MecanumDrive.cc index 59dd701675..3b1ff40312 100644 --- a/src/systems/mecanum_drive/MecanumDrive.cc +++ b/src/systems/mecanum_drive/MecanumDrive.cc @@ -17,7 +17,7 @@ #include "MecanumDrive.hh" -#include +#include #include #include @@ -25,19 +25,19 @@ #include #include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/CanonicalLink.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/JointVelocityCmd.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include +#include +#include +#include +#include +#include + +#include "gz/sim/components/CanonicalLink.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/JointVelocityCmd.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/mecanum_drive/MecanumDrive.hh b/src/systems/mecanum_drive/MecanumDrive.hh index e9db61c2c9..38b7e342fe 100644 --- a/src/systems/mecanum_drive/MecanumDrive.hh +++ b/src/systems/mecanum_drive/MecanumDrive.hh @@ -19,7 +19,7 @@ #include -#include +#include namespace ignition { diff --git a/src/systems/model_photo_shoot/ModelPhotoShoot.cc b/src/systems/model_photo_shoot/ModelPhotoShoot.cc index 31f6373e1c..75d18c84cb 100644 --- a/src/systems/model_photo_shoot/ModelPhotoShoot.cc +++ b/src/systems/model_photo_shoot/ModelPhotoShoot.cc @@ -20,23 +20,23 @@ #include #include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/JointType.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/JointPositionReset.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/rendering/Events.hh" -#include "ignition/gazebo/Util.hh" +#include +#include +#include +#include +#include +#include + +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/JointType.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/JointPositionReset.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/rendering/Events.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/model_photo_shoot/ModelPhotoShoot.hh b/src/systems/model_photo_shoot/ModelPhotoShoot.hh index b059f2486e..9a14609c6a 100644 --- a/src/systems/model_photo_shoot/ModelPhotoShoot.hh +++ b/src/systems/model_photo_shoot/ModelPhotoShoot.hh @@ -21,7 +21,7 @@ #include -#include "ignition/gazebo/System.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/multicopter_motor_model/MulticopterMotorModel.cc b/src/systems/multicopter_motor_model/MulticopterMotorModel.cc index 914918770a..e438b715f5 100644 --- a/src/systems/multicopter_motor_model/MulticopterMotorModel.cc +++ b/src/systems/multicopter_motor_model/MulticopterMotorModel.cc @@ -35,7 +35,7 @@ #include #include #include -#include +#include #include diff --git a/src/systems/navsat/NavSat.cc b/src/systems/navsat/NavSat.cc index 2eea382d9e..2d56ef302a 100644 --- a/src/systems/navsat/NavSat.cc +++ b/src/systems/navsat/NavSat.cc @@ -17,7 +17,7 @@ #include "NavSat.hh" -#include +#include #include #include @@ -27,22 +27,22 @@ #include -#include -#include +#include +#include -#include -#include +#include +#include -#include -#include +#include +#include -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/NavSat.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/NavSat.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/navsat/NavSat.hh b/src/systems/navsat/NavSat.hh index e4ce4f34d6..71c10b75e1 100644 --- a/src/systems/navsat/NavSat.hh +++ b/src/systems/navsat/NavSat.hh @@ -17,10 +17,10 @@ #ifndef IGNITION_GAZEBO_SYSTEMS_NAVSAT_HH_ #define IGNITION_GAZEBO_SYSTEMS_NAVSAT_HH_ -#include +#include -#include -#include +#include +#include namespace ignition { diff --git a/src/systems/odometry_publisher/OdometryPublisher.cc b/src/systems/odometry_publisher/OdometryPublisher.cc index 8b6270c0fd..1b8b2c8e58 100644 --- a/src/systems/odometry_publisher/OdometryPublisher.cc +++ b/src/systems/odometry_publisher/OdometryPublisher.cc @@ -17,8 +17,8 @@ #include "OdometryPublisher.hh" -#include -#include +#include +#include #include #include @@ -26,18 +26,18 @@ #include #include -#include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include +#include +#include +#include +#include +#include +#include + +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/odometry_publisher/OdometryPublisher.hh b/src/systems/odometry_publisher/OdometryPublisher.hh index c087ad51a0..0e8eb4b814 100644 --- a/src/systems/odometry_publisher/OdometryPublisher.hh +++ b/src/systems/odometry_publisher/OdometryPublisher.hh @@ -19,7 +19,7 @@ #include -#include +#include namespace ignition { diff --git a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc index 6007d95259..a6e2fec324 100644 --- a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc +++ b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc @@ -21,26 +21,26 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include -#include "ignition/gazebo/components/ContactSensor.hh" -#include "ignition/gazebo/components/ContactSensorData.hh" -#include "ignition/gazebo/components/Collision.hh" -#include "ignition/gazebo/components/DepthCamera.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Geometry.hh" +#include "gz/sim/components/ContactSensor.hh" +#include "gz/sim/components/ContactSensorData.hh" +#include "gz/sim/components/Collision.hh" +#include "gz/sim/components/DepthCamera.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Geometry.hh" #include "sdf/Box.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" #include "OpticalTactilePlugin.hh" diff --git a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh index 30853d164a..bb89595861 100644 --- a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh +++ b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh @@ -19,7 +19,7 @@ #define IGNITION_GAZEBO_SYSTEMS_OPTICAL_TACTILE_PLUGIN_HH_ #include -#include +#include #include "Visualization.hh" namespace ignition diff --git a/src/systems/optical_tactile_plugin/Visualization.cc b/src/systems/optical_tactile_plugin/Visualization.cc index d330e6a9d4..16c55a814f 100644 --- a/src/systems/optical_tactile_plugin/Visualization.cc +++ b/src/systems/optical_tactile_plugin/Visualization.cc @@ -15,9 +15,9 @@ * */ -#include -#include -#include +#include +#include +#include #include "Visualization.hh" diff --git a/src/systems/optical_tactile_plugin/Visualization.hh b/src/systems/optical_tactile_plugin/Visualization.hh index 96c8b46cc0..b2bee311e8 100644 --- a/src/systems/optical_tactile_plugin/Visualization.hh +++ b/src/systems/optical_tactile_plugin/Visualization.hh @@ -21,11 +21,11 @@ #include #include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/components/ContactSensorData.hh" +#include "gz/sim/components/ContactSensorData.hh" namespace ignition { diff --git a/src/systems/particle_emitter/ParticleEmitter.cc b/src/systems/particle_emitter/ParticleEmitter.cc index db1aa6b924..fae477f3f0 100644 --- a/src/systems/particle_emitter/ParticleEmitter.cc +++ b/src/systems/particle_emitter/ParticleEmitter.cc @@ -15,27 +15,27 @@ * */ -#include +#include #include #include #include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include #include #include "ParticleEmitter.hh" diff --git a/src/systems/particle_emitter/ParticleEmitter.hh b/src/systems/particle_emitter/ParticleEmitter.hh index 6a3da57d23..8fc1f91def 100644 --- a/src/systems/particle_emitter/ParticleEmitter.hh +++ b/src/systems/particle_emitter/ParticleEmitter.hh @@ -19,7 +19,7 @@ #include -#include +#include namespace ignition { diff --git a/src/systems/particle_emitter2/ParticleEmitter2.cc b/src/systems/particle_emitter2/ParticleEmitter2.cc index 6e0c290992..d79d45cb1c 100644 --- a/src/systems/particle_emitter2/ParticleEmitter2.cc +++ b/src/systems/particle_emitter2/ParticleEmitter2.cc @@ -15,24 +15,24 @@ * */ -#include -#include +#include +#include #include #include #include #include -#include -#include -#include -#include +#include +#include +#include +#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include "ParticleEmitter2.hh" using namespace std::chrono_literals; diff --git a/src/systems/particle_emitter2/ParticleEmitter2.hh b/src/systems/particle_emitter2/ParticleEmitter2.hh index a52d39f65f..e9e489a8ff 100644 --- a/src/systems/particle_emitter2/ParticleEmitter2.hh +++ b/src/systems/particle_emitter2/ParticleEmitter2.hh @@ -19,7 +19,7 @@ #include -#include +#include namespace ignition { diff --git a/src/systems/perfect_comms/PerfectComms.cc b/src/systems/perfect_comms/PerfectComms.cc index 08f24cc033..75b7eefe81 100644 --- a/src/systems/perfect_comms/PerfectComms.cc +++ b/src/systems/perfect_comms/PerfectComms.cc @@ -17,11 +17,11 @@ #include -#include -#include -#include "ignition/gazebo/comms/Broker.hh" -#include "ignition/gazebo/comms/MsgManager.hh" -#include "ignition/gazebo/Util.hh" +#include +#include +#include "gz/sim/comms/Broker.hh" +#include "gz/sim/comms/MsgManager.hh" +#include "gz/sim/Util.hh" #include "PerfectComms.hh" using namespace ignition; diff --git a/src/systems/perfect_comms/PerfectComms.hh b/src/systems/perfect_comms/PerfectComms.hh index 9ac93f07a7..14e200b518 100644 --- a/src/systems/perfect_comms/PerfectComms.hh +++ b/src/systems/perfect_comms/PerfectComms.hh @@ -19,10 +19,10 @@ #include -#include +#include #include -#include "ignition/gazebo/comms/ICommsModel.hh" -#include "ignition/gazebo/System.hh" +#include "gz/sim/comms/ICommsModel.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/physics/CanonicalLinkModelTracker.hh b/src/systems/physics/CanonicalLinkModelTracker.hh index 4f6f01443e..44e6f99e02 100644 --- a/src/systems/physics/CanonicalLinkModelTracker.hh +++ b/src/systems/physics/CanonicalLinkModelTracker.hh @@ -20,11 +20,11 @@ #include #include -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/components/CanonicalLink.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/config.hh" +#include "gz/sim/Entity.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/components/CanonicalLink.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/config.hh" namespace ignition::gazebo { diff --git a/src/systems/rf_comms/RFComms.cc b/src/systems/rf_comms/RFComms.cc index 2ec1444cd0..978c36a74f 100644 --- a/src/systems/rf_comms/RFComms.cc +++ b/src/systems/rf_comms/RFComms.cc @@ -15,7 +15,7 @@ * */ -#include +#include #include #include @@ -26,15 +26,15 @@ #include #include -#include -#include -#include -#include -#include "ignition/gazebo/comms/MsgManager.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include +#include +#include +#include +#include "gz/sim/comms/MsgManager.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" #include "RFComms.hh" using namespace ignition; diff --git a/src/systems/rf_comms/RFComms.hh b/src/systems/rf_comms/RFComms.hh index c36696b62a..14e482b4aa 100644 --- a/src/systems/rf_comms/RFComms.hh +++ b/src/systems/rf_comms/RFComms.hh @@ -19,10 +19,10 @@ #include -#include +#include #include -#include "ignition/gazebo/comms/ICommsModel.hh" -#include "ignition/gazebo/System.hh" +#include "gz/sim/comms/ICommsModel.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/shader_param/ShaderParam.cc b/src/systems/shader_param/ShaderParam.cc index a97eeb4dbe..01cb24de8c 100644 --- a/src/systems/shader_param/ShaderParam.cc +++ b/src/systems/shader_param/ShaderParam.cc @@ -24,21 +24,21 @@ #include #include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include #include -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/SourceFilePath.hh" -#include "ignition/gazebo/rendering/Events.hh" -#include "ignition/gazebo/rendering/RenderUtil.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/SourceFilePath.hh" +#include "gz/sim/rendering/Events.hh" +#include "gz/sim/rendering/RenderUtil.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/shader_param/ShaderParam.hh b/src/systems/shader_param/ShaderParam.hh index 7b6135dd79..98c3fb2e6e 100644 --- a/src/systems/shader_param/ShaderParam.hh +++ b/src/systems/shader_param/ShaderParam.hh @@ -20,7 +20,7 @@ #include -#include "ignition/gazebo/System.hh" +#include "gz/sim/System.hh" namespace ignition { diff --git a/src/systems/thermal/ThermalSensor.cc b/src/systems/thermal/ThermalSensor.cc index 72e5f60a45..030b9c7bcf 100644 --- a/src/systems/thermal/ThermalSensor.cc +++ b/src/systems/thermal/ThermalSensor.cc @@ -20,14 +20,14 @@ #include #include -#include -#include +#include +#include -#include "ignition/gazebo/components/ThermalCamera.hh" -#include "ignition/gazebo/components/Temperature.hh" -#include "ignition/gazebo/components/TemperatureRange.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/ThermalCamera.hh" +#include "gz/sim/components/Temperature.hh" +#include "gz/sim/components/TemperatureRange.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Util.hh" using namespace ignition; using namespace gazebo; diff --git a/src/systems/thermal/ThermalSensor.hh b/src/systems/thermal/ThermalSensor.hh index c0a27306d3..dae7094bb3 100644 --- a/src/systems/thermal/ThermalSensor.hh +++ b/src/systems/thermal/ThermalSensor.hh @@ -18,9 +18,9 @@ #define IGNITION_GAZEBO_SYSTEMS_THERMALSENSOR_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/src/systems/thruster/Thruster.cc b/src/systems/thruster/Thruster.cc index e3a58424c5..fc75ec0a21 100644 --- a/src/systems/thruster/Thruster.cc +++ b/src/systems/thruster/Thruster.cc @@ -19,27 +19,27 @@ #include #include -#include - -#include - -#include - -#include - -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/BatterySoC.hh" -#include "ignition/gazebo/components/BatteryPowerLoad.hh" -#include "ignition/gazebo/components/ChildLinkName.hh" -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/JointVelocityCmd.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include + +#include + +#include + +#include + +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/BatterySoC.hh" +#include "gz/sim/components/BatteryPowerLoad.hh" +#include "gz/sim/components/ChildLinkName.hh" +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/JointVelocityCmd.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" #include "Thruster.hh" diff --git a/src/systems/thruster/Thruster.hh b/src/systems/thruster/Thruster.hh index e40627d465..f97de16a32 100644 --- a/src/systems/thruster/Thruster.hh +++ b/src/systems/thruster/Thruster.hh @@ -17,7 +17,7 @@ #ifndef IGNITION_GAZEBO_SYSTEMS_THRUSTER_HH_ #define IGNITION_GAZEBO_SYSTEMS_THRUSTER_HH_ -#include +#include #include diff --git a/src/systems/trajectory_follower/TrajectoryFollower.cc b/src/systems/trajectory_follower/TrajectoryFollower.cc index 8366c6065d..403d4d0345 100644 --- a/src/systems/trajectory_follower/TrajectoryFollower.cc +++ b/src/systems/trajectory_follower/TrajectoryFollower.cc @@ -15,28 +15,28 @@ * */ -#include +#include #include #include #include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/AngularVelocityCmd.hh" -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Util.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/AngularVelocityCmd.hh" +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Util.hh" #include "TrajectoryFollower.hh" diff --git a/src/systems/trajectory_follower/TrajectoryFollower.hh b/src/systems/trajectory_follower/TrajectoryFollower.hh index 57fbfcaae9..9d8adf77a0 100644 --- a/src/systems/trajectory_follower/TrajectoryFollower.hh +++ b/src/systems/trajectory_follower/TrajectoryFollower.hh @@ -17,7 +17,7 @@ #ifndef IGNITION_GAZEBO_SYSTEMS_TRAJECTORYFOLLOWER_HH_ #define IGNITION_GAZEBO_SYSTEMS_TRAJECTORYFOLLOWER_HH_ -#include +#include #include namespace ignition diff --git a/test/integration/ModelPhotoShootTest.hh b/test/integration/ModelPhotoShootTest.hh index 9e3066951a..895c7edad6 100644 --- a/test/integration/ModelPhotoShootTest.hh +++ b/test/integration/ModelPhotoShootTest.hh @@ -27,24 +27,24 @@ #include #include -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/JointType.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" -#include "ignition/gazebo/TestFixture.hh" -#include "ignition/gazebo/rendering/Events.hh" -#include "ignition/gazebo/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/JointType.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" +#include "gz/sim/TestFixture.hh" +#include "gz/sim/rendering/Events.hh" +#include "gz/sim/Model.hh" -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include "helpers/UniqueTestDirectoryEnv.hh" diff --git a/test/integration/actor.cc b/test/integration/actor.cc index 7e874e57f8..6c0c23f324 100644 --- a/test/integration/actor.cc +++ b/test/integration/actor.cc @@ -17,16 +17,16 @@ #include -#include -#include -#include - -#include -#include -#include -#include -#include -#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/actor_trajectory.cc b/test/integration/actor_trajectory.cc index 66b25c6516..44de67fdbd 100644 --- a/test/integration/actor_trajectory.cc +++ b/test/integration/actor_trajectory.cc @@ -21,19 +21,19 @@ #include #include -#include +#include -#include -#include +#include +#include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/EventManager.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/Types.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/EventManager.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/Types.hh" +#include "gz/sim/test_config.hh" -#include "ignition/gazebo/rendering/Events.hh" +#include "gz/sim/rendering/Events.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/buoyancy_engine.cc b/test/integration/buoyancy_engine.cc index 334113eb78..7e8b94ada1 100644 --- a/test/integration/buoyancy_engine.cc +++ b/test/integration/buoyancy_engine.cc @@ -17,19 +17,19 @@ #include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Model.hh" - -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include + +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Model.hh" + +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/camera_sensor_background_from_scene.cc b/test/integration/camera_sensor_background_from_scene.cc index bc9e0259fa..cf7ffe59b1 100644 --- a/test/integration/camera_sensor_background_from_scene.cc +++ b/test/integration/camera_sensor_background_from_scene.cc @@ -19,13 +19,13 @@ #include -#include -#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/deprecated_TEST.cc b/test/integration/deprecated_TEST.cc index a47d16ea3a..06fbb6f904 100644 --- a/test/integration/deprecated_TEST.cc +++ b/test/integration/deprecated_TEST.cc @@ -16,7 +16,7 @@ */ #include -#include +#include ///////////////////////////////////////////////// // Make sure the ignition namespace still works diff --git a/test/integration/distortion_camera.cc b/test/integration/distortion_camera.cc index 279e6d28e7..c2d4ca8c29 100644 --- a/test/integration/distortion_camera.cc +++ b/test/integration/distortion_camera.cc @@ -20,18 +20,18 @@ #ifdef _MSC_VER #pragma warning(push, 0) #endif -#include +#include #ifdef _MSC_VER #pragma warning(pop) #endif -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" -#include -#include -#include -#include -#include +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" +#include +#include +#include +#include +#include #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/entity_system.cc b/test/integration/entity_system.cc index 338cf4e685..ed9f496ed0 100644 --- a/test/integration/entity_system.cc +++ b/test/integration/entity_system.cc @@ -16,18 +16,18 @@ */ #include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include + +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/follow_actor_system.cc b/test/integration/follow_actor_system.cc index a919b970d9..215d0d9388 100644 --- a/test/integration/follow_actor_system.cc +++ b/test/integration/follow_actor_system.cc @@ -16,17 +16,17 @@ */ #include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Actor.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include + +#include "gz/sim/components/Actor.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/force_torque_system.cc b/test/integration/force_torque_system.cc index 60c57a8b01..a251dfca5a 100644 --- a/test/integration/force_torque_system.cc +++ b/test/integration/force_torque_system.cc @@ -17,18 +17,18 @@ #include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/components/ForceTorque.hh" - -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include + +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/components/ForceTorque.hh" + +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "helpers/Relay.hh" #include "helpers/EnvTestFixture.hh" diff --git a/test/integration/fuel_cached_server.cc b/test/integration/fuel_cached_server.cc index 25f0e93377..a356a29ee2 100644 --- a/test/integration/fuel_cached_server.cc +++ b/test/integration/fuel_cached_server.cc @@ -16,10 +16,10 @@ */ #include -#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/ServerConfig.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/ServerConfig.hh" #include "../test/helpers/EnvTestFixture.hh" diff --git a/test/integration/halt_motion.cc b/test/integration/halt_motion.cc index fe8e0d8a92..e2238dd3da 100644 --- a/test/integration/halt_motion.cc +++ b/test/integration/halt_motion.cc @@ -16,19 +16,19 @@ */ #include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/HaltMotion.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include + +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/HaltMotion.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/hydrodynamics.cc b/test/integration/hydrodynamics.cc index 937cae1d95..ece8fe029f 100644 --- a/test/integration/hydrodynamics.cc +++ b/test/integration/hydrodynamics.cc @@ -17,22 +17,22 @@ #include -#include - -#include -#include -#include -#include - -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/TestFixture.hh" -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/World.hh" - -#include "ignition/gazebo/test_config.hh" +#include + +#include +#include +#include +#include + +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/TestFixture.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/World.hh" + +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/test/integration/hydrodynamics_flags.cc b/test/integration/hydrodynamics_flags.cc index a437d402ab..b64b7eb453 100644 --- a/test/integration/hydrodynamics_flags.cc +++ b/test/integration/hydrodynamics_flags.cc @@ -17,22 +17,22 @@ #include -#include - -#include -#include -#include -#include - -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/TestFixture.hh" -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/World.hh" - -#include "ignition/gazebo/test_config.hh" +#include + +#include +#include +#include +#include + +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/TestFixture.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/World.hh" + +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/test/integration/joint.cc b/test/integration/joint.cc index 7247079878..70b03ac134 100644 --- a/test/integration/joint.cc +++ b/test/integration/joint.cc @@ -17,33 +17,33 @@ #include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/joint_trajectory_controller_system.cc b/test/integration/joint_trajectory_controller_system.cc index 160af92aac..5d3e61e04c 100644 --- a/test/integration/joint_trajectory_controller_system.cc +++ b/test/integration/joint_trajectory_controller_system.cc @@ -17,24 +17,24 @@ #include -#include -#include +#include +#include #include -#include -#include -#include -#include +#include +#include +#include +#include -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/JointPosition.hh" -#include "ignition/gazebo/components/JointVelocity.hh" -#include "ignition/gazebo/components/Name.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/JointPosition.hh" +#include "gz/sim/components/JointVelocity.hh" +#include "gz/sim/components/Name.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/light.cc b/test/integration/light.cc index abc20be990..6cd8c1ff37 100644 --- a/test/integration/light.cc +++ b/test/integration/light.cc @@ -17,27 +17,27 @@ #include -#include +#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/logical_audio_sensor_plugin.cc b/test/integration/logical_audio_sensor_plugin.cc index e4450358c8..4d6201a609 100644 --- a/test/integration/logical_audio_sensor_plugin.cc +++ b/test/integration/logical_audio_sensor_plugin.cc @@ -26,7 +26,7 @@ #include #include #include -#include +#include #include #include diff --git a/test/integration/model_photo_shoot_default_joints.cc b/test/integration/model_photo_shoot_default_joints.cc index 620bf42e8a..6c18c24797 100644 --- a/test/integration/model_photo_shoot_default_joints.cc +++ b/test/integration/model_photo_shoot_default_joints.cc @@ -17,7 +17,7 @@ #include "ModelPhotoShootTest.hh" -#include +#include // Test the Model Photo Shoot plugin on the example world. TEST_F(ModelPhotoShootTest, diff --git a/test/integration/model_photo_shoot_random_joints.cc b/test/integration/model_photo_shoot_random_joints.cc index 21cabd9681..782e84a9f9 100644 --- a/test/integration/model_photo_shoot_random_joints.cc +++ b/test/integration/model_photo_shoot_random_joints.cc @@ -17,7 +17,7 @@ #include "ModelPhotoShootTest.hh" -#include +#include // Test the Model Photo Shoot plugin on the example world. TEST_F(ModelPhotoShootTest, diff --git a/test/integration/multicopter.cc b/test/integration/multicopter.cc index ba8ab1b53e..0ae09e1bf3 100644 --- a/test/integration/multicopter.cc +++ b/test/integration/multicopter.cc @@ -20,7 +20,7 @@ #include -#include +#include #include #include diff --git a/test/integration/multiple_servers.cc b/test/integration/multiple_servers.cc index 519ee43313..b80cde5a36 100644 --- a/test/integration/multiple_servers.cc +++ b/test/integration/multiple_servers.cc @@ -17,10 +17,10 @@ #include -#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/ServerConfig.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/ServerConfig.hh" #include "../test/helpers/EnvTestFixture.hh" diff --git a/test/integration/navsat_system.cc b/test/integration/navsat_system.cc index 38ae04c867..921d81b182 100644 --- a/test/integration/navsat_system.cc +++ b/test/integration/navsat_system.cc @@ -17,24 +17,24 @@ #include -#include +#include #include -#include -#include -#include -#include - -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/NavSat.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Sensor.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/TestFixture.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include + +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/NavSat.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Sensor.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/TestFixture.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/nested_model_physics.cc b/test/integration/nested_model_physics.cc index f3eeb33e02..51380e03d4 100644 --- a/test/integration/nested_model_physics.cc +++ b/test/integration/nested_model_physics.cc @@ -16,19 +16,19 @@ */ #include -#include -#include -#include - -#include "ignition/math/Pose3.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Model.hh" - -#include "ignition/gazebo/test_config.hh" +#include +#include +#include + +#include "gz/math/Pose3.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Model.hh" + +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/odometry_publisher.cc b/test/integration/odometry_publisher.cc index 52e2eb0891..9006eec1a7 100644 --- a/test/integration/odometry_publisher.cc +++ b/test/integration/odometry_publisher.cc @@ -16,22 +16,22 @@ */ #include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/AngularVelocity.hh" -#include "ignition/gazebo/components/AngularVelocityCmd.hh" -#include "ignition/gazebo/components/LinearVelocity.hh" -#include "ignition/gazebo/components/LinearVelocityCmd.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include + +#include "gz/sim/components/AngularVelocity.hh" +#include "gz/sim/components/AngularVelocityCmd.hh" +#include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/LinearVelocityCmd.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/optical_tactile_plugin.cc b/test/integration/optical_tactile_plugin.cc index 76fb2e4571..d580ed3ce4 100644 --- a/test/integration/optical_tactile_plugin.cc +++ b/test/integration/optical_tactile_plugin.cc @@ -17,19 +17,19 @@ #include -#include +#include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/particle_emitter.cc b/test/integration/particle_emitter.cc index 40bb5308d1..329a64cebd 100644 --- a/test/integration/particle_emitter.cc +++ b/test/integration/particle_emitter.cc @@ -19,19 +19,19 @@ #include -#include - -#include -#include -#include - -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParticleEmitter.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/test_config.hh" +#include + +#include +#include +#include + +#include "gz/sim/Entity.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParticleEmitter.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/test_config.hh" #include "helpers/EnvTestFixture.hh" #include "helpers/Relay.hh" diff --git a/test/integration/particle_emitter2.cc b/test/integration/particle_emitter2.cc index 4d71f3349a..7d3bff2590 100644 --- a/test/integration/particle_emitter2.cc +++ b/test/integration/particle_emitter2.cc @@ -19,18 +19,18 @@ #include -#include -#include -#include -#include - -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParticleEmitter.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include + +#include "gz/sim/Entity.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParticleEmitter.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/test_config.hh" #include "helpers/EnvTestFixture.hh" #include "helpers/Relay.hh" diff --git a/test/integration/perfect_comms.cc b/test/integration/perfect_comms.cc index 56c77957c8..9d846e260d 100644 --- a/test/integration/perfect_comms.cc +++ b/test/integration/perfect_comms.cc @@ -21,11 +21,11 @@ #include #include -#include -#include -#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include +#include +#include +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/test/integration/play_pause.cc b/test/integration/play_pause.cc index 1ce1a37197..844bcfb9e1 100644 --- a/test/integration/play_pause.cc +++ b/test/integration/play_pause.cc @@ -19,7 +19,7 @@ #include #include -#include "ignition/msgs.hh" +#include "gz/msgs.hh" #include "gz/transport.hh" #include "gz/sim/Server.hh" #include "gz/sim/test_config.hh" // NOLINT(build/include) diff --git a/test/integration/recreate_entities.cc b/test/integration/recreate_entities.cc index 97ab6eb9f2..9c493b1723 100644 --- a/test/integration/recreate_entities.cc +++ b/test/integration/recreate_entities.cc @@ -20,24 +20,24 @@ #include #include -#include -#include -#include +#include +#include +#include #include -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/Link.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/ParentLinkName.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/Recreate.hh" -#include "ignition/gazebo/components/World.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/components/Factory.hh" +#include "gz/sim/components/Joint.hh" +#include "gz/sim/components/Link.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/ParentLinkName.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/Recreate.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/Relay.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/rf_comms.cc b/test/integration/rf_comms.cc index aa64733de1..9d70109395 100644 --- a/test/integration/rf_comms.cc +++ b/test/integration/rf_comms.cc @@ -21,12 +21,12 @@ #include #include -#include -#include -#include -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include +#include +#include +#include "gz/sim/Model.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/test/integration/sensor.cc b/test/integration/sensor.cc index 7536e00d27..e0bea88580 100644 --- a/test/integration/sensor.cc +++ b/test/integration/sensor.cc @@ -17,18 +17,18 @@ #include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/sensors_system_battery.cc b/test/integration/sensors_system_battery.cc index b7b65c0e11..19631fff7e 100644 --- a/test/integration/sensors_system_battery.cc +++ b/test/integration/sensors_system_battery.cc @@ -21,17 +21,17 @@ #include -#include -#include +#include +#include -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/Types.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/EntityComponentManager.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/Types.hh" +#include "gz/sim/test_config.hh" -#include "ignition/gazebo/components/BatterySoC.hh" -#include "ignition/gazebo/components/Name.hh" +#include "gz/sim/components/BatterySoC.hh" +#include "gz/sim/components/Name.hh" #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/shader_param_system.cc b/test/integration/shader_param_system.cc index 906133e937..8952203ac6 100644 --- a/test/integration/shader_param_system.cc +++ b/test/integration/shader_param_system.cc @@ -17,15 +17,15 @@ #include -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/spherical_coordinates.cc b/test/integration/spherical_coordinates.cc index 6f50f269bd..466019b889 100644 --- a/test/integration/spherical_coordinates.cc +++ b/test/integration/spherical_coordinates.cc @@ -16,21 +16,21 @@ */ #include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/TestFixture.hh" -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/World.hh" -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/components/SphericalCoordinates.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include + +#include "gz/sim/TestFixture.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/World.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/ParentEntity.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/components/SphericalCoordinates.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/thermal_sensor_system.cc b/test/integration/thermal_sensor_system.cc index 8013bee829..1fb4d7ac0f 100644 --- a/test/integration/thermal_sensor_system.cc +++ b/test/integration/thermal_sensor_system.cc @@ -20,20 +20,20 @@ #include #include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/Temperature.hh" -#include "ignition/gazebo/components/TemperatureRange.hh" -#include "ignition/gazebo/components/ThermalCamera.hh" -#include "ignition/gazebo/components/Visual.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" +#include +#include +#include +#include +#include + +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Temperature.hh" +#include "gz/sim/components/TemperatureRange.hh" +#include "gz/sim/components/ThermalCamera.hh" +#include "gz/sim/components/Visual.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/integration/thruster.cc b/test/integration/thruster.cc index b6b0e589f1..023978f424 100644 --- a/test/integration/thruster.cc +++ b/test/integration/thruster.cc @@ -17,26 +17,26 @@ #include -#include - -#include -#include -#include -#include -#include - -#include "ignition/gazebo/Link.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/TestFixture.hh" -#include "ignition/gazebo/Util.hh" -#include "ignition/gazebo/World.hh" - -#include "ignition/gazebo/components/JointAxis.hh" -#include "ignition/gazebo/components/Pose.hh" - -#include "ignition/gazebo/test_config.hh" +#include + +#include +#include +#include +#include +#include + +#include "gz/sim/Link.hh" +#include "gz/sim/Model.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/TestFixture.hh" +#include "gz/sim/Util.hh" +#include "gz/sim/World.hh" + +#include "gz/sim/components/JointAxis.hh" +#include "gz/sim/components/Pose.hh" + +#include "gz/sim/test_config.hh" #include "../helpers/EnvTestFixture.hh" using namespace ignition; diff --git a/test/integration/triggered_camera.cc b/test/integration/triggered_camera.cc index 6f36f37c6b..45b2fb0f74 100644 --- a/test/integration/triggered_camera.cc +++ b/test/integration/triggered_camera.cc @@ -20,20 +20,20 @@ #ifdef _MSC_VER #pragma warning(push, 0) #endif -#include +#include #ifdef _MSC_VER #pragma warning(pop) #endif -#include "ignition/gazebo/rendering/Events.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/test_config.hh" -#include -#include -#include -#include -#include +#include "gz/sim/rendering/Events.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "gz/sim/test_config.hh" +#include +#include +#include +#include +#include #include "plugins/MockSystem.hh" #include "../helpers/EnvTestFixture.hh" diff --git a/test/integration/world_control_state.cc b/test/integration/world_control_state.cc index 92bebfb68c..c3e7399f48 100644 --- a/test/integration/world_control_state.cc +++ b/test/integration/world_control_state.cc @@ -17,15 +17,15 @@ #include -#include -#include -#include +#include +#include +#include -#include "ignition/gazebo/components/Model.hh" -#include "ignition/gazebo/components/Name.hh" +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "gz/sim/Server.hh" +#include "gz/sim/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" diff --git a/test/performance/sdf_runner.cc b/test/performance/sdf_runner.cc index 9cbbab1300..11725b95f1 100644 --- a/test/performance/sdf_runner.cc +++ b/test/performance/sdf_runner.cc @@ -17,7 +17,7 @@ #include -#include +#include #include #include diff --git a/test/plugins/TestVisualSystem.cc b/test/plugins/TestVisualSystem.cc index 9cc3741117..129c739e6f 100644 --- a/test/plugins/TestVisualSystem.cc +++ b/test/plugins/TestVisualSystem.cc @@ -16,7 +16,7 @@ */ #include "TestVisualSystem.hh" -#include +#include IGNITION_ADD_PLUGIN(ignition::gazebo::TestVisualSystem, ignition::gazebo::System, diff --git a/test/plugins/TestVisualSystem.hh b/test/plugins/TestVisualSystem.hh index e8cdf4a45f..dd751292d9 100644 --- a/test/plugins/TestVisualSystem.hh +++ b/test/plugins/TestVisualSystem.hh @@ -17,11 +17,11 @@ #ifndef IGNITION_GAZEBO_TEST_TESTVISUALSYSTEM_HH_ #define IGNITION_GAZEBO_TEST_TESTVISUALSYSTEM_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { From aee9f0d99abb9c0631bdea8f6e1b641da386fb99 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 24 May 2023 20:05:42 +0000 Subject: [PATCH 09/31] Fixed header redirects Signed-off-by: Nate Koenig --- include/ignition/gazebo/Actor.hh | 146 +-------- include/ignition/gazebo/Joint.hh | 269 +---------------- include/ignition/gazebo/Light.hh | 276 +----------------- include/ignition/gazebo/Primitives.hh | 68 +---- include/ignition/gazebo/Sensor.hh | 100 +------ include/ignition/gazebo/comms/Broker.hh | 141 +-------- include/ignition/gazebo/comms/ICommsModel.hh | 122 +------- include/ignition/gazebo/comms/MsgManager.hh | 146 +-------- .../gazebo/components/BatteryPowerLoad.hh | 39 +-- .../gazebo/components/BoundingBoxCamera.hh | 32 +- .../gazebo/components/CustomSensor.hh | 32 +- .../ignition/gazebo/components/ForceTorque.hh | 34 +-- .../ignition/gazebo/components/HaltMotion.hh | 25 +- .../components/JointTransmittedWrench.hh | 41 +-- .../ignition/gazebo/components/LightCmd.hh | 33 +-- .../ignition/gazebo/components/LightType.hh | 33 +-- include/ignition/gazebo/components/NavSat.hh | 33 +-- .../gazebo/components/ParticleEmitter.hh | 39 +-- .../ignition/gazebo/components/Recreate.hh | 35 +-- .../components/RenderEngineServerHeadless.hh | 32 +- .../gazebo/components/SegmentationCamera.hh | 32 +- .../gazebo/components/SemanticLabel.hh | 30 +- .../gazebo/components/SphericalCoordinates.hh | 40 +-- .../gazebo/components/SystemPluginInfo.hh | 34 +-- .../gazebo/components/TemperatureRange.hh | 86 +----- .../ignition/gazebo/components/Visibility.hh | 35 +-- .../ignition/gazebo/components/VisualCmd.hh | 33 +-- .../gazebo/components/WheelSlipCmd.hh | 31 +- 28 files changed, 74 insertions(+), 1923 deletions(-) diff --git a/include/ignition/gazebo/Actor.hh b/include/ignition/gazebo/Actor.hh index 50460891a0..a8bd091180 100644 --- a/include/ignition/gazebo/Actor.hh +++ b/include/ignition/gazebo/Actor.hh @@ -14,148 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_ACTOR_HH_ -#define IGNITION_GAZEBO_ACTOR_HH_ -#include -#include -#include - -#include - -#include - -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // - /// \class Actor Actor.hh ignition/gazebo/Actor.hh - /// \brief This class provides wrappers around entities and components - /// which are more convenient and straight-forward to use than dealing - /// with the `EntityComponentManager` directly. - /// All the functions provided here are meant to be used with a actor - /// entity. - /// - /// For example, given an actor's entity, find the value of its - /// name component, one could use the entity-component manager (`ecm`) - /// directly as follows: - /// - /// std::string name = ecm.Component(entity)->Data(); - /// - /// Using this class however, the same information can be obtained with - /// a simpler function call: - /// - /// Actor actor(entity); - /// std::string name = actor.Name(ecm); - /// - class IGNITION_GAZEBO_VISIBLE Actor - { - /// \brief Constructor - /// \param[in] _entity Actor entity - public: explicit Actor(gazebo::Entity _entity = kNullEntity); - - /// \brief Get the entity which this Actor is related to. - /// \return Actor entity. - public: gazebo::Entity Entity() const; - - /// \brief Reset Entity to a new one - /// \param[in] _newEntity New actor entity. - public: void ResetEntity(gazebo::Entity _newEntity); - - /// \brief Check whether this actor correctly refers to an entity that - /// has a components::Actor. - /// \param[in] _ecm Entity-component manager. - /// \return True if it's a valid actor in the manager. - public: bool Valid(const EntityComponentManager &_ecm) const; - - /// \brief Get the actor's unscoped name. - /// \param[in] _ecm Entity-component manager. - /// \return Actor's name or nullopt if the entity does not have a - /// components::Name component - public: std::optional Name( - const EntityComponentManager &_ecm) const; - - /// \brief Get the pose of the actor. - /// If the actor has a trajectory, this will only return the origin - /// pose of the trajectory and not the actual world pose of the actor. - /// \param[in] _ecm Entity-component manager. - /// \return Pose of the actor or nullopt if the entity does not - /// have a components::Pose component. - /// \sa WorldPose - public: std::optional Pose( - const EntityComponentManager &_ecm) const; - - /// \brief Get the trajectory pose of the actor. There are two - /// ways that the actor can follow a trajectory: 1) SDF script, - /// 2) manually setting trajectory pose. This function retrieves 2) the - /// manual trajectory pose set by the user. The Trajectory pose is - /// given relative to the trajectory pose origin returned by Pose(). - /// \param[in] _ecm Entity Component manager. - /// \return Trajectory pose of the actor w.r.t. to trajectory origin. - /// \sa Pose - public: std::optional TrajectoryPose( - const EntityComponentManager &_ecm) const; - - /// \brief Set the trajectory pose of the actor. There are two - /// ways that the actor can follow a trajectory: 1) SDF script, - /// 2) manually setting trajectory pose. This function enables option 2). - /// Manually setting the trajectory pose will override the scripted - /// trajectory specified in SDF. - /// \param[in] _ecm Entity Component manager. - /// \param[in] _name Trajectory pose w.r.t. to the trajectory origin - /// \sa Pose - public: void SetTrajectoryPose(EntityComponentManager &_ecm, - const math::Pose3d &_pose); - - /// \brief Get the world pose of the actor. - /// This returns the current world pose of the actor computed by gazebo. - /// The world pose is the combination of the actor's pose and its - /// trajectory pose. The currently trajectory pose is either manually set - /// via SetTrajectoryPose or interpolated from waypoints in the SDF script - /// based on the current time. - /// \param[in] _ecm Entity-component manager. - /// \return World pose of the actor or nullopt if the entity does not - /// have a components::WorldPose component. - /// \sa Pose - public: std::optional WorldPose( - const EntityComponentManager &_ecm) const; - - /// \brief Set the name of animation to use for this actor. - /// \param[in] _ecm Entity Component manager. - /// \param[in] _name Animation name - public: void SetAnimationName(EntityComponentManager &_ecm, - const std::string &_name); - - /// \brief Set the time of animation for this actor. - /// \param[in] _ecm Entity Component manager. - /// \param[in] _time Animation time - public: void SetAnimationTime(EntityComponentManager &_ecm, - const std::chrono::steady_clock::duration &_time); - - /// \brief Get the name of animation used by the actor - /// \param[in] _ecm Entity-component manager. - /// \return Animation name - public: std::optional AnimationName( - const EntityComponentManager &_ecm) const; - - /// \brief Get the time of animation for this actor - /// \param[in] _ecm Entity-component manager. - /// \return Animation time - public: std::optional AnimationTime( - const EntityComponentManager &_ecm) const; - - /// \brief Private data pointer. - IGN_UTILS_IMPL_PTR(dataPtr) - }; - } - } -} -#endif +#include +#include diff --git a/include/ignition/gazebo/Joint.hh b/include/ignition/gazebo/Joint.hh index e8b8ab31f3..8b4269d202 100644 --- a/include/ignition/gazebo/Joint.hh +++ b/include/ignition/gazebo/Joint.hh @@ -14,271 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_JOINT_HH_ -#define IGNITION_GAZEBO_JOINT_HH_ -#include -#include -#include -#include - -#include -#include - -#include -#include -#include - -#include -#include - -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Model.hh" -#include "ignition/gazebo/Types.hh" - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // - /// \class Joint Joint.hh ignition/gazebo/Joint.hh - /// \brief This class provides wrappers around entities and components - /// which are more convenient and straight-forward to use than dealing - /// with the `EntityComponentManager` directly. - /// All the functions provided here are meant to be used with a joint - /// entity. - /// - /// For example, given a joint's entity, find the value of its - /// name component, one could use the entity-component manager (`ecm`) - /// directly as follows: - /// - /// std::string name = ecm.Component(entity)->Data(); - /// - /// Using this class however, the same information can be obtained with - /// a simpler function call: - /// - /// Joint joint(entity); - /// std::string name = joint.Name(ecm); - /// - class IGNITION_GAZEBO_VISIBLE Joint - { - /// \brief Constructor - /// \param[in] _entity Joint entity - public: explicit Joint(gazebo::Entity _entity = kNullEntity); - - /// \brief Get the entity which this Joint is related to. - /// \return Joint entity. - public: gazebo::Entity Entity() const; - - /// \brief Reset Entity to a new one - /// \param[in] _newEntity New joint entity. - public: void ResetEntity(gazebo::Entity _newEntity); - - /// \brief Check whether this joint correctly refers to an entity that - /// has a components::Joint. - /// \param[in] _ecm Entity-component manager. - /// \return True if it's a valid joint in the manager. - public: bool Valid(const EntityComponentManager &_ecm) const; - - /// \brief Get the joint's unscoped name. - /// \param[in] _ecm Entity-component manager. - /// \return Joint's name or nullopt if the entity does not have a - /// components::Name component - public: std::optional Name( - const EntityComponentManager &_ecm) const; - - /// \brief Get the parent link name - /// \param[in] _ecm Entity-component manager. - /// \return Parent link name or nullopt if the entity does not have a - /// components::ParentLinkName component. - public: std::optional ParentLinkName( - const EntityComponentManager &_ecm) const; - - /// \brief Get the child link name - /// \param[in] _ecm Entity-component manager. - /// \return Child link name or nullopt if the entity does not have a - /// components::ChildLinkName component. - public: std::optional ChildLinkName( - const EntityComponentManager &_ecm) const; - - /// \brief Get the pose of the joint - /// \param[in] _ecm Entity-component manager. - /// \return Pose of the joint or nullopt if the entity does not - /// have a components::Pose component. - public: std::optional Pose( - const EntityComponentManager &_ecm) const; - - /// \brief Get the thread pitch of the joint - /// \param[in] _ecm Entity-component manager. - /// \return Thread pitch of the joint or nullopt if the entity does not - /// have a components::ThreadPitch component. - public: std::optional ThreadPitch( - const EntityComponentManager &_ecm) const; - - /// \brief Get the joint axis - /// \param[in] _ecm Entity-component manager. - /// \return Axis of the joint or nullopt if the entity does not - /// have a components::JointAxis or components::JointAxis2 component. - public: std::optional> Axis( - const EntityComponentManager &_ecm) const; - - /// \brief Get the joint type - /// \param[in] _ecm Entity-component manager. - /// \return Type of the joint or nullopt if the entity does not - /// have a components::JointType component. - public: std::optional Type( - const EntityComponentManager &_ecm) const; - - /// \brief Get the ID of a sensor entity which is an immediate child of - /// this joint. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _name Sensor name. - /// \return Sensor entity. - public: gazebo::Entity SensorByName(const EntityComponentManager &_ecm, - const std::string &_name) const; - - /// \brief Get all sensors which are immediate children of this joint. - /// \param[in] _ecm Entity-component manager. - /// \return All sensors in this joint. - public: std::vector Sensors( - const EntityComponentManager &_ecm) const; - - /// \brief Get the number of sensors which are immediate children of this - /// joint. - /// \param[in] _ecm Entity-component manager. - /// \return Number of sensors in this joint. - public: uint64_t SensorCount(const EntityComponentManager &_ecm) const; - - /// \brief Set velocity on this joint. Only applied if no forces are set - /// \param[in] _ecm Entity Component manager. - /// \param[in] _velocities Joint velocities commands (target velocities). - /// This is different from ResetVelocity in that this does not modify the - /// internal state of the joint. Instead, the physics engine is expected - /// to compute the necessary joint torque for the commanded velocity and - /// apply it in the next simulation step. The vector of velocities should - /// have the same size as the degrees of freedom of the joint. - public: void SetVelocity(EntityComponentManager &_ecm, - const std::vector &_velocities); - - /// \brief Set force on this joint. If both forces and velocities are set, - /// only forces are applied - /// \param[in] _ecm Entity Component manager. - /// \param[in] _forces Joint force or torque commands (target forces - /// or toruqes). The vector of forces should have the same size as the - /// degrees of freedom of the joint. - public: void SetForce(EntityComponentManager &_ecm, - const std::vector &_forces); - - /// \brief Set the velocity limits on a joint axis. - /// \param[in] _ecm Entity Component manager. - /// \param[in] _limits Joint limits to set to. The X() component of the - /// Vector2 specifies the minimum velocity limit, the Y() component stands - /// for maximum limit. The vector of limits should have the same size as - /// the degrees of freedom of the joint. - public: void SetVelocityLimits(EntityComponentManager &_ecm, - const std::vector &_limits); - - /// \brief Set the effort limits on a joint axis. - /// \param[in] _ecm Entity Component manager. - /// \param[in] _limits Joint limits to set to. The X() component of the - /// Vector2 specifies the minimum effort limit, the Y() component stands - /// for maximum limit. The vector of limits should have the same size as - /// the degrees of freedom of the joint. - public: void SetEffortLimits(EntityComponentManager &_ecm, - const std::vector &_limits); - - /// \brief Set the position limits on a joint axis. - /// \param[in] _ecm Entity Component manager. - /// \param[in] _limits Joint limits to set to. The X() component of the - /// Vector2 specifies the minimum position limit, the Y() component stands - /// for maximum limit. The vector of limits should have the same size as - /// the degrees of freedom of the joint. - public: void SetPositionLimits(EntityComponentManager &_ecm, - const std::vector &_limits); - - /// \brief Reset the joint positions - /// \param[in] _ecm Entity Component manager. - /// \param[in] _positions Joint positions to reset to. - /// The vector of positions should have the same size as the degrees of - /// freedom of the joint. - public: void ResetPosition(EntityComponentManager &_ecm, - const std::vector &_positions); - - /// \brief Reset the joint velocities - /// \param[in] _ecm Entity Component manager. - /// \param[in] _velocities Joint velocities to reset to. This is different - /// from SetVelocity as this modifies the internal state of the joint. - /// The vector of velocities should have the same size as the degrees of - /// freedom of the joint. - public: void ResetVelocity(EntityComponentManager &_ecm, - const std::vector &_velocities); - - /// \brief By default, Gazebo will not report velocities for a joint, so - /// functions like `Velocity` will return nullopt. This - /// function can be used to enable joint velocity check. - /// \param[in] _ecm Mutable reference to the ECM. - /// \param[in] _enable True to enable checks, false to disable. Defaults - /// to true. - public: void EnableVelocityCheck(EntityComponentManager &_ecm, - bool _enable = true) const; - - /// \brief By default, Gazebo will not report positions for a joint, so - /// functions like `Position` will return nullopt. This - /// function can be used to enable joint position check. - /// \param[in] _ecm Mutable reference to the ECM. - /// \param[in] _enable True to enable checks, false to disable. Defaults - /// to true. - public: void EnablePositionCheck(EntityComponentManager &_ecm, - bool _enable = true) const; - - /// \brief By default, Gazebo will not report transmitted wrench for a - /// joint, so functions like `TransmittedWrench` will return nullopt. This - /// function can be used to enable joint transmitted wrench check. - /// \param[in] _ecm Mutable reference to the ECM. - /// \param[in] _enable True to enable checks, false to disable. Defaults - /// to true. - public: void EnableTransmittedWrenchCheck(EntityComponentManager &_ecm, - bool _enable = true) const; - - /// \brief Get the velocity of the joint - /// \param[in] _ecm Entity-component manager. - /// \return Velocity of the joint or nullopt if velocity check - /// is not enabled. - /// \sa EnableVelocityCheck - public: std::optional> Velocity( - const EntityComponentManager &_ecm) const; - - /// \brief Get the position of the joint - /// \param[in] _ecm Entity-component manager. - /// \return Position of the joint or nullopt if position check - /// is not enabled. - /// \sa EnablePositionCheck - public: std::optional> Position( - const EntityComponentManager &_ecm) const; - - /// \brief Get the transmitted wrench of the joint - /// \param[in] _ecm Entity-component manager. - /// \return Transmitted wrench of the joint or nullopt if transmitted - /// wrench check is not enabled. - /// \sa EnableTransmittedWrenchCheck - public: std::optional> TransmittedWrench( - const EntityComponentManager &_ecm) const; - - /// \brief Get the parent model - /// \param[in] _ecm Entity-component manager. - /// \return Parent Model or nullopt if the entity does not have a - /// components::ParentEntity component. - public: std::optional ParentModel( - const EntityComponentManager &_ecm) const; - - /// \brief Private data pointer. - IGN_UTILS_IMPL_PTR(dataPtr) - }; - } - } -} -#endif +#include +#include diff --git a/include/ignition/gazebo/Light.hh b/include/ignition/gazebo/Light.hh index f3680991dd..087d73bc21 100644 --- a/include/ignition/gazebo/Light.hh +++ b/include/ignition/gazebo/Light.hh @@ -14,278 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_LIGHT_HH_ -#define IGNITION_GAZEBO_LIGHT_HH_ -#include -#include -#include -#include - -#include - -#include -#include -#include -#include - -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // - /// \class Light Light.hh ignition/gazebo/Light.hh - /// \brief This class provides wrappers around entities and components - /// which are more convenient and straight-forward to use than dealing - /// with the `EntityComponentManager` directly. - /// All the functions provided here are meant to be used with a light - /// entity. - /// - /// For example, given a light's entity, find the value of its - /// name component, one could use the entity-component manager (`ecm`) - /// directly as follows: - /// - /// std::string name = ecm.Component(entity)->Data(); - /// - /// Using this class however, the same information can be obtained with - /// a simpler function call: - /// - /// Light light(entity); - /// std::string name = light.Name(ecm); - /// - class IGNITION_GAZEBO_VISIBLE Light - { - /// \brief Constructor - /// \param[in] _entity Light entity - public: explicit Light(gazebo::Entity _entity = kNullEntity); - - /// \brief Get the entity which this Light is related to. - /// \return Light entity. - public: gazebo::Entity Entity() const; - - /// \brief Reset Entity to a new one - /// \param[in] _newEntity New light entity. - public: void ResetEntity(gazebo::Entity _newEntity); - - /// \brief Check whether this light correctly refers to an entity that - /// has a components::Light. - /// \param[in] _ecm Entity-component manager. - /// \return True if it's a valid light in the manager. - public: bool Valid(const EntityComponentManager &_ecm) const; - - /// \brief Get the light's unscoped name. - /// \param[in] _ecm Entity-component manager. - /// \return Light's name or nullopt if the entity does not have a - /// components::Name component - public: std::optional Name( - const EntityComponentManager &_ecm) const; - - /// \brief Get the pose of the light. - /// The pose is given w.r.t the light's parent. which can be a world or - /// a link. - /// \param[in] _ecm Entity-component manager. - /// \return Pose of the light or nullopt if the entity does not - /// have a components::Pose component. - public: std::optional Pose( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light type - /// \param[in] _ecm Entity-component manager. - /// \return Type of the light or nullopt if the entity does not - /// have a components::LightType component. - public: std::optional Type( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light diffuse color - /// \param[in] _ecm Entity-component manager. - /// \return Diffuse color of the light or nullopt if the entity does not - /// have a components::Light component. - public: std::optional DiffuseColor( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light specular color - /// \param[in] _ecm Entity-component manager. - /// \return Specular color of the light or nullopt if the entity does not - /// have a components::Light component. - public: std::optional SpecularColor( - const EntityComponentManager &_ecm) const; - - /// \brief Get whether the light casts shadows - /// \param[in] _ecm Entity-component manager. - /// \return Cast shadow bool value of light or nullopt if the entity does - /// not have a components::CastShadows component. - public: std::optional CastShadows( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light intensity. - /// \param[in] _ecm Entity-component manager. - /// \return Intensity of light or nullopt if the entity does not - /// have a components::Light component. - public: std::optional Intensity( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light direction. - /// \param[in] _ecm Entity-component manager. - /// \return Direction of light or nullopt if the entity does not - /// have a components::Light component. - public: std::optional Direction( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light attenuation range. - /// Light attenuation is not applicable to directional lights. - /// \param[in] _ecm Entity-component manager. - /// \return Attenuation range of light or nullopt if the entity does not - /// have a components::Light component. - public: std::optional AttenuationRange( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light attenuation constant value. - /// Light attenuation is not applicable to directional lights. - /// \param[in] _ecm Entity-component manager. - /// \return Attenuation constant value of light or nullopt if the entity - /// does not have a components::Light component. - public: std::optional AttenuationConstant( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light attenuation linear value. - /// Light attenuation is not applicable to directional lights. - /// \param[in] _ecm Entity-component manager. - /// \return Attenuation linear value of light or nullopt if the entity - /// does not have a components::Light component. - public: std::optional AttenuationLinear( - const EntityComponentManager &_ecm) const; - - /// \brief Get the light attenuation quadratic value. - /// Light attenuation is not applicable to directional lights. - /// \param[in] _ecm Entity-component manager. - /// \return Attenuation quadratic value of light or nullopt if the entity - /// does not have a components::Light component. - public: std::optional AttenuationQuadratic( - const EntityComponentManager &_ecm) const; - - /// \brief Get the inner angle of light. Applies to spot lights only. - /// \param[in] _ecm Entity-component manager. - /// \return Inner angle of spot light or nullopt if the entity - /// does not have a components::Light component. - public: std::optional SpotInnerAngle( - const EntityComponentManager &_ecm) const; - - /// \brief Get the outer angle of light. Applies to spot lights only. - /// \param[in] _ecm Entity-component manager. - /// \return Outer angle of spot light or nullopt if the entity - /// does not have a components::Light component. - public: std::optional SpotOuterAngle( - const EntityComponentManager &_ecm) const; - - /// \brief Get the fall off value of light. Applies to spot lights only. - /// \param[in] _ecm Entity-component manager. - /// \return Fall off value of spot light or nullopt if the entity - /// does not have a components::Light component. - public: std::optional SpotFalloff( - const EntityComponentManager &_ecm) const; - - /// \brief Set the pose of this light. - /// \param[in] _ecm Entity-component manager. - /// Pose is set w.r.t. the light's parent which can be a world or a link. - /// \param[in] _pose Pose to set the light to. - public: void SetPose(EntityComponentManager &_ecm, - const math::Pose3d &_pose); - - /// \brief Set the diffuse color of this light. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _color Diffuse color to set the light to - public: void SetDiffuseColor(EntityComponentManager &_ecm, - const math::Color &_color); - - /// \brief Set the specular color of this light. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _color Specular color to set the light to - public: void SetSpecularColor(EntityComponentManager &_ecm, - const math::Color &_color); - - /// \brief Set whether the light casts shadows. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _bool True to cast shadows, false to not cast shadows. - public: void SetCastShadows(EntityComponentManager &_ecm, - bool _castShadows); - - /// \brief Set light intensity. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _value Intensity value - public: void SetIntensity(EntityComponentManager &_ecm, - double _value); - - /// \brief Set light direction. Applies to directional lights - /// \param[in] _ecm Entity-component manager. - /// and spot lights only. - /// \param[in] _dir Direction to set - public: void SetDirection(EntityComponentManager &_ecm, - const math::Vector3d &_dir); - - /// \brief Set attenuation range of this light. - /// \param[in] _ecm Entity-component manager. - /// Light attenuation is not applicable to directional lights. - /// \param[in] _bool True to cast shadows, false to not cast shadows. - public: void SetAttenuationRange(EntityComponentManager &_ecm, - double _range); - - /// \brief Set attenuation constant value of this light. - /// \param[in] _ecm Entity-component manager. - /// Light attenuation is not applicable to directional lights. - /// \param[in] _value Attenuation constant value to set - public: void SetAttenuationConstant(EntityComponentManager &_ecm, - double _value); - - /// \brief Set attenuation linear value of this light. - /// \param[in] _ecm Entity-component manager. - /// Light attenuation is not applicable to directional lights. - /// \param[in] _value Attenuation linear value to set - public: void SetAttenuationLinear(EntityComponentManager &_ecm, - double _value); - - /// \brief Set attenuation quadratic value of this light. - /// \param[in] _ecm Entity-component manager. - /// Light attenuation is not applicable to directional lights. - /// \param[in] _value Attenuation quadratic value to set - public: void SetAttenuationQuadratic(EntityComponentManager &_ecm, - double _value); - - /// \brief Set inner angle for this light. Applies to spot lights only. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _angle Angle to set. - public: void SetSpotInnerAngle(EntityComponentManager &_ecm, - const math::Angle &_angle); - - /// \brief Set outer angle for this light. Applies to spot lights only. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _angle Angle to set. - public: void SetSpotOuterAngle(EntityComponentManager &_ecm, - const math::Angle &_angle); - - /// \brief Set fall off value for this light. Applies to spot lights only. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _fallOff Fall off value - public: void SetSpotFalloff(EntityComponentManager &_ecm, - double _falloff); - - /// \brief Get the parent entity. This can be a world or a link. - /// \param[in] _ecm Entity-component manager. - /// \return Parent entity or nullopt if the entity does not have a - /// components::ParentEntity component. - public: std::optional Parent( - const EntityComponentManager &_ecm) const; - - /// \brief Private data pointer. - IGN_UTILS_IMPL_PTR(dataPtr) - }; - } - } -} -#endif +#include +#include diff --git a/include/ignition/gazebo/Primitives.hh b/include/ignition/gazebo/Primitives.hh index eff9a97b83..41c74f8880 100644 --- a/include/ignition/gazebo/Primitives.hh +++ b/include/ignition/gazebo/Primitives.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -15,69 +15,5 @@ * */ -#ifndef IGNITION_GAZEBO_PRIMITIVES_HH_ -#define IGNITION_GAZEBO_PRIMITIVES_HH_ - +#include #include -#include - -#include - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - - /// \brief Enumeration of available primitive shape types - enum class IGNITION_GAZEBO_VISIBLE PrimitiveShape - { - kBox, - kCapsule, - kCylinder, - kEllipsoid, - kSphere, - }; - - /// \brief Enumeration of available primitive light types - enum class IGNITION_GAZEBO_VISIBLE PrimitiveLight - { - kDirectional, - kPoint, - kSpot, - }; - - /// \brief Return an SDF string of one of the available primitive - /// shape types - /// \param[in] _type Type of shape to retrieve - /// \return String containing SDF description of primitive shape - /// Empty string if the _type is not supported. - std::string IGNITION_GAZEBO_VISIBLE - getPrimitiveShape(const PrimitiveShape &_type); - - /// \brief Return an SDF string of one of the available primitive - /// light types - /// \param[in] _type Type of light to retrieve - /// \return String containing SDF description of primitive light - /// Empty string if the _type is not supported. - std::string IGNITION_GAZEBO_VISIBLE - getPrimitiveLight(const PrimitiveLight &_type); - - /// \brief Return an SDF string of one of the available primitive shape or - /// light types. - /// \param[in] _typeName Type name of the of shape or light to retrieve. - /// Must be one of: box, sphere, cylinder, capsule, ellipsoid, directional, - /// point, or spot. - /// \return String containing SDF description of primitive shape or light. - /// Empty string if the _typeName is invalid. - std::string IGNITION_GAZEBO_VISIBLE - getPrimitive(const std::string &_typeName); - } - } // namespace gazebo -} // namespace ignition - - -#endif // IGNITION_GAZEBO_PRIMITIVES_HH_ - - diff --git a/include/ignition/gazebo/Sensor.hh b/include/ignition/gazebo/Sensor.hh index af677f252b..e6325f0464 100644 --- a/include/ignition/gazebo/Sensor.hh +++ b/include/ignition/gazebo/Sensor.hh @@ -14,102 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SENSOR_HH_ -#define IGNITION_GAZEBO_SENSOR_HH_ -#include -#include -#include - -#include - -#include - -#include - -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/Types.hh" - -namespace ignition -{ - namespace gazebo - { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - // - /// \class Sensor Sensor.hh ignition/gazebo/Sensor.hh - /// \brief This class provides wrappers around entities and components - /// which are more convenient and straight-forward to use than dealing - /// with the `EntityComponentManager` directly. - /// All the functions provided here are meant to be used with a sensor - /// entity. - /// - /// For example, given a sensor's entity, find the value of its - /// name component, one could use the entity-component manager (`ecm`) - /// directly as follows: - /// - /// std::string name = ecm.Component(entity)->Data(); - /// - /// Using this class however, the same information can be obtained with - /// a simpler function call: - /// - /// Sensor sensor(entity); - /// std::string name = sensor.Name(ecm); - /// - class IGNITION_GAZEBO_VISIBLE Sensor - { - /// \brief Constructor - /// \param[in] _entity Sensor entity - public: explicit Sensor(gazebo::Entity _entity = kNullEntity); - - /// \brief Get the entity which this Sensor is related to. - /// \return Sensor entity. - public: gazebo::Entity Entity() const; - - /// \brief Reset Entity to a new one - /// \param[in] _newEntity New sensor entity. - public: void ResetEntity(gazebo::Entity _newEntity); - - /// \brief Check whether this sensor correctly refers to an entity that - /// has a components::Sensor. - /// \param[in] _ecm Entity-component manager. - /// \return True if it's a valid sensor in the manager. - public: bool Valid(const EntityComponentManager &_ecm) const; - - /// \brief Get the sensor's unscoped name. - /// \param[in] _ecm Entity-component manager. - /// \return Sensor's name or nullopt if the entity does not have a - /// components::Name component - public: std::optional Name( - const EntityComponentManager &_ecm) const; - - /// \brief Get the pose of the sensor - /// \param[in] _ecm Entity-component manager. - /// \return Pose of the sensor or nullopt if the entity does not - /// have a components::Pose component. - public: std::optional Pose( - const EntityComponentManager &_ecm) const; - - /// \brief Get the topic of the sensor - /// \param[in] _ecm Entity-component manager. - /// \return Topic of the sensor or nullopt if the entity does not - /// have a components::SensorTopic component. - public: std::optional Topic( - const EntityComponentManager &_ecm) const; - - /// \brief Get the parent entity. This can be a link or a joint. - /// \param[in] _ecm Entity-component manager. - /// \return Parent entity or nullopt if the entity does not have a - /// components::ParentEntity component. - public: std::optional Parent( - const EntityComponentManager &_ecm) const; - - /// \brief Private data pointer. - IGN_UTILS_IMPL_PTR(dataPtr) - }; - } - } -} -#endif +#include +#include diff --git a/include/ignition/gazebo/comms/Broker.hh b/include/ignition/gazebo/comms/Broker.hh index bf06cdf383..91437357fe 100644 --- a/include/ignition/gazebo/comms/Broker.hh +++ b/include/ignition/gazebo/comms/Broker.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2022 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -15,140 +15,5 @@ * */ -#ifndef IGNITION_GAZEBO_BROKER_HH_ -#define IGNITION_GAZEBO_BROKER_HH_ - -#include - -#include -#include -#include "ignition/gazebo/comms/MsgManager.hh" -#include "ignition/gazebo/config.hh" - -namespace ignition -{ -namespace msgs -{ - // Forward declarations. - class Boolean; - class Dataframe; - class StringMsg_V; -} -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace comms -{ - // Forward declarations. - class MsgManager; - - /// \brief A class to store messages to be delivered using a comms model. - /// This class should be used in combination with a specific comms model that - /// implements the ICommsModel interface. - /// \sa ICommsModel.hh - /// The broker maintains two queues: inbound and outbound. When a client - /// sends a communication request, we'll store it in the outbound queue of - /// the sender's address. When the comms model decides that a message needs - /// to be delivered to one of the destination, it'll be stored in the inbound - /// queue of the destination's address. - /// - /// The main goal of this class is to receive the comms requests, stamp the - /// time, and place them in the appropriate outbound queue, as well as deliver - /// the messages that are in the inbound queues. - /// - /// The instance of the comms model is responsible for moving around the - /// messages from the outbound queues to the inbound queues. - /// - /// The broker can be configured with the following SDF parameters: - /// - /// * Optional parameters: - /// Element used to capture the broker parameters. This block can - /// contain any of the next parameters: - /// : Topic name where the broker receives all the incoming - /// messages. The default value is "/broker/msgs" - /// : Service name used to bind an address. - /// The default value is "/broker/bind" - /// : Service name used to unbind from an address. - /// The default value is "/broker/unbind" - /// - /// Here's an example: - /// - /// - /// /broker/inbound - /// /broker/bind_address - /// /broker/unbind_address - /// - /// - class IGNITION_GAZEBO_VISIBLE Broker - { - /// \brief Constructor. - public: Broker(); - - /// \brief Configure the broker via SDF. - /// \param[in] _sdf The SDF Element associated with the broker parameters. - public: void Load(std::shared_ptr _sdf); - - /// \brief Start handling comms services. - /// - /// This function allows us to wait to advertise capabilities to - /// clients until the broker has been entirely initialized. - public: void Start(); - - /// \brief Get the current time. - /// \return Current time. - public: std::chrono::steady_clock::duration Time() const; - - /// \brief Set the current time. - /// \param[in] _time Current time. - public: void SetTime(const std::chrono::steady_clock::duration &_time); - - /// \brief This method associates an address with a client topic used as - /// callback for receiving messages. This is a client requirement to - /// start receiving messages. - /// \param[in] _req Bind request containing the following content: - /// _req[0] Client address. - /// _req[1] Model name associated to the address. - /// _req[2] Client subscription topic. - /// \param[out] _rep Unused - /// \return True when the bind service succeeded or false otherwise. - public: bool OnBind(const ignition::msgs::StringMsg_V &_req, - ignition::msgs::Boolean &_rep); - - /// \brief Unbind a given client address. The client associated to this - /// address will not receive any more messages. - /// \param[in] _req Bind request containing the following content: - /// _req[0] Client address. - /// _req[1] Client subscription topic. - public: void OnUnbind(const ignition::msgs::StringMsg_V &_req); - - /// \brief Callback executed to process a communication request from one of - /// the clients. - /// \param[in] _msg The message from the client. - public: void OnMsg(const ignition::msgs::Dataframe &_msg); - - /// \brief Process all the messages in the inbound queue and deliver them - /// to the destination clients. - public: void DeliverMsgs(); - - /// \brief Get a mutable reference to the message manager. - /// \return The mutable reference. - public: MsgManager &DataManager(); - - /// \brief Lock the mutex to access the message manager. - public: void Lock(); - - /// \brief Unlock the mutex to access the message manager. - public: void Unlock(); - - /// \brief Private data pointer. - IGN_UTILS_UNIQUE_IMPL_PTR(dataPtr) - }; -} -} -} -} - -#endif +#include +#include diff --git a/include/ignition/gazebo/comms/ICommsModel.hh b/include/ignition/gazebo/comms/ICommsModel.hh index 367cbe975b..de2214ddfb 100644 --- a/include/ignition/gazebo/comms/ICommsModel.hh +++ b/include/ignition/gazebo/comms/ICommsModel.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2022 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -15,121 +15,5 @@ * */ -#ifndef IGNITION_GAZEBO_ICOMMSMODEL_HH_ -#define IGNITION_GAZEBO_ICOMMSMODEL_HH_ - -#include - -#include -#include -#include "ignition/gazebo/comms/MsgManager.hh" -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/System.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - - // Forward declarations - class EntityComponentManager; - class EventManager; - -namespace comms -{ - /// \brief Abstract interface to define how the environment should handle - /// communication simulation. As an example, this class could be responsible - /// for handling dropouts, decay and packet collisions. - /// - /// The derived comms models can be configured with the following SDF - /// parameters: - /// - /// * Optional parameters: - /// If defined this will allow the comms model to run at a - /// higher frequency than the physics engine. This is useful when dealing - /// with ranging. If the is set larger than the physics engine dt - /// then the comms model step size will default to dt. - /// Note: for consistency it is adviced that the dt is a multiple of timestep. - /// Units are in seconds. - /// - /// Here's an example: - /// - /// 2 - /// 1.0 - /// - /// - /// 1 - /// - class IGNITION_GAZEBO_VISIBLE ICommsModel: -#ifdef _MSC_VER - #pragma warning(push) - #pragma warning(disable:4275) -#endif - public System, -#ifdef _MSC_VER - #pragma warning(pop) -#endif - public ISystemConfigure, - public ISystemPreUpdate - { - /// \brief Constructor. - public: explicit ICommsModel(); - - // Documentation inherited. - public: void Configure(const Entity &_entity, - const std::shared_ptr &_sdf, - EntityComponentManager &_ecm, - EventManager &_eventMgr) override; - - // Documentation inherited. - public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; - - /// \brief This method is called when there is a timestep in the simulator. - /// \param[in] _info Simulator information about the current timestep. - /// will become the new registry. - /// \param[in] _ecm - Ignition's ECM. - public: virtual void StepImpl(const UpdateInfo &_info, - EntityComponentManager &_ecm); - - /// \brief This method is called when the system is being configured - /// override this to load any additional params for the comms model - /// \param[in] _entity The entity this plugin is attached to. - /// \param[in] _sdf The SDF Element associated with this system plugin. - /// \param[in] _ecm The EntityComponentManager of the given simulation - /// instance. - /// \param[in] _eventMgr The EventManager of the given simulation instance. - public: virtual void Load(const Entity &_entity, - std::shared_ptr _sdf, - EntityComponentManager &_ecm, - EventManager &_eventMgr) = 0; - - /// \brief This method is called when there is a timestep in the simulator - /// override this to update your data structures as needed. - /// - /// Note: this is an experimental interface and might change in the future. - /// - /// \param[in] _info Simulator information about the current timestep. - /// \param[in] _currentRegistry The current registry. - /// \param[out] _newRegistry The new registry. When Step() is finished this - /// will become the new registry. - /// \param[in] _ecm - Ignition's ECM. - public: virtual void Step(const UpdateInfo &_info, - const Registry &_currentRegistry, - Registry &_newRegistry, - EntityComponentManager &_ecm) = 0; - - /// \brief Private data pointer. - IGN_UTILS_UNIQUE_IMPL_PTR(dataPtr) - }; -} -} -} -} - -#endif +#include +#include diff --git a/include/ignition/gazebo/comms/MsgManager.hh b/include/ignition/gazebo/comms/MsgManager.hh index aa5bde7f4d..25f1ff139b 100644 --- a/include/ignition/gazebo/comms/MsgManager.hh +++ b/include/ignition/gazebo/comms/MsgManager.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2022 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -15,145 +15,5 @@ * */ -#ifndef IGNITION_GAZEBO_MSGMANAGER_HH_ -#define IGNITION_GAZEBO_MSGMANAGER_HH_ - -#include -#include -#include -#include - -#include -#include -#include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/System.hh" - -namespace ignition -{ -namespace msgs -{ - // Forward declarations. - class Dataframe; -} -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace comms -{ - -/// \brief A queue of message pointers. -using DataQueue = std::deque; - -/// \brief A map where the key is the topic subscribed to an address and -/// the value is a publisher to reach that topic. -using SubscriptionHandler = - std::unordered_map; - -/// \brief All the information associated to an address. -struct AddressContent -{ - /// \brief Queue of inbound messages. - public: DataQueue inboundMsgs; - - /// \brief Queue of outbound messages. - public: DataQueue outboundMsgs; - - /// \brief Subscribers. - public: SubscriptionHandler subscriptions; - - /// \brief Model name associated to this address. - public: std::string modelName; - - /// \brief Entity of the model associated to this address. - public: gazebo::Entity entity; -}; - -/// \brief A map where the key is an address and the value is all the -/// information associated to each address (subscribers, queues, ...). -using Registry = std::unordered_map; - -/// \brief Class to handle messages and subscriptions. -class IGNITION_GAZEBO_VISIBLE MsgManager -{ - /// \brief Default constructor. - public: MsgManager(); - - /// \brief Add a new subscriber. It's possible to associate multiple topics - /// to the same address/model pair. However, the same address cannot be - /// attached to multiple models. When all the subscribers are removed, it's - /// posible to bind to this address using a different model. - /// \param[in] _address The subscriber address. - /// \param[in] _modelName The model name. - /// \param[in] _topic The subscriber topic. - /// \return True if the subscriber was successfully added or false otherwise. - public: bool AddSubscriber(const std::string &_address, - const std::string &_modelName, - const std::string &_topic); - - /// \brief Add a new message to the inbound queue. - /// \param[in] _address The destination address. - /// \param[in] _msg The message. - public: void AddInbound(const std::string &_address, - const msgs::DataframeSharedPtr &_msg); - - /// \brief Add a new message to the outbound queue. - /// \param[in] _address The sender address. - /// \param[in] _msg The message. - public: void AddOutbound(const std::string &_address, - const msgs::DataframeSharedPtr &_msg); - - /// \brief Remove an existing subscriber. - /// \param[in] _address The subscriber address. - /// \param[in] _topic The Subscriber topic. - /// \return True if the subscriber was removed or false otherwise. - public: bool RemoveSubscriber(const std::string &_address, - const std::string &_topic); - - /// \brief Remove a message from the inbound queue. - /// \param[in] _address The destination address. - /// \param[in] _Msg Message pointer to remove. - /// \return True if the message was removed or false otherwise. - public: bool RemoveInbound(const std::string &_address, - const msgs::DataframeSharedPtr &_msg); - - /// \brief Remove a message from the outbound queue. - /// \param[in] _address The sender address. - /// \param[in] _msg Message pointer to remove. - /// \return True if the message was removed or false otherwise. - public: bool RemoveOutbound(const std::string &_address, - const msgs::DataframeSharedPtr &_msg); - - /// \brief This function delivers all the messages in the inbound queue to - /// the appropriate subscribers. This function also clears the inbound queue. - public: void DeliverMsgs(); - - /// \brief Get an inmutable reference to the data containing subscriptions and - /// data queues. - /// \return A const reference to the data. - public: const Registry &DataConst() const; - - /// \brief Get a mutable reference to the data containing subscriptions and - /// data queues. - /// \return A mutable reference to the data. - public: Registry &Data(); - - /// \brief Get a copy of the data structure containing subscriptions and data - /// queues. - /// \return A copy of the data. - public: Registry Copy() const; - - /// \brief Set the data structure containing subscriptions and data queues. - /// \param[in] _newContent New content to be set. - public: void Set(const Registry &_newContent); - - /// \brief Private data pointer. - IGN_UTILS_UNIQUE_IMPL_PTR(dataPtr) -}; -} -} -} -} - -#endif +#include +#include diff --git a/include/ignition/gazebo/components/BatteryPowerLoad.hh b/include/ignition/gazebo/components/BatteryPowerLoad.hh index 6cfb191678..1073d23e85 100644 --- a/include/ignition/gazebo/components/BatteryPowerLoad.hh +++ b/include/ignition/gazebo/components/BatteryPowerLoad.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2022 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,40 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_BATTERYPOWERLOAD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_BATTERYPOWERLOAD_HH_ + */ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Data structure to hold the consumer power load - /// and the name of the battery it uses. - struct BatteryPowerLoadInfo - { - /// \brief Entity of the battery to use. - Entity batteryId; - /// \brief Battery power load (W) to add to the battery. - double batteryPowerLoad; - }; - - /// \brief A component that indicates the total consumption of a battery. - using BatteryPowerLoad = - Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.BatteryPowerLoad", - BatteryPowerLoad) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/BoundingBoxCamera.hh b/include/ignition/gazebo/components/BoundingBoxCamera.hh index 2451fd8f24..14a78a1325 100644 --- a/include/ignition/gazebo/components/BoundingBoxCamera.hh +++ b/include/ignition/gazebo/components/BoundingBoxCamera.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2022 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,33 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_BOUNDINGBOXCAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_BOUNDINGBOXCAMERA_HH_ + */ -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains a BoundingBox camera sensor, - /// sdf::Camera, information. - using BoundingBoxCamera = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.BoundingBoxCamera", - BoundingBoxCamera) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/CustomSensor.hh b/include/ignition/gazebo/components/CustomSensor.hh index 9871249241..aa9e0acc33 100644 --- a/include/ignition/gazebo/components/CustomSensor.hh +++ b/include/ignition/gazebo/components/CustomSensor.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,33 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_CUSTOMSENSOR_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CUSTOMSENSOR_HH_ + */ -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains a custom sensor's information. - /// A custom sensor is any sensor that's not officially supported through - /// the SDF spec. - using CustomSensor = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.CustomSensor", - CustomSensor) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/ForceTorque.hh b/include/ignition/gazebo/components/ForceTorque.hh index 12da278077..059287fa34 100644 --- a/include/ignition/gazebo/components/ForceTorque.hh +++ b/include/ignition/gazebo/components/ForceTorque.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,35 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_FORCETORQUE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_FORCETORQUE_HH_ - -#include + */ +#include #include -#include - -#include -#include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains an FT sensor, - /// sdf::ForceTorque, information. - using ForceTorque = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ForceTorque", - ForceTorque) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/HaltMotion.hh b/include/ignition/gazebo/components/HaltMotion.hh index 2b44fa5bb8..c2064af00b 100644 --- a/include/ignition/gazebo/components/HaltMotion.hh +++ b/include/ignition/gazebo/components/HaltMotion.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,27 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_HALT_MOTION_HH_ -#define IGNITION_GAZEBO_COMPONENTS_HALT_MOTION_HH_ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component used to turn off a model's joint's movement. - using HaltMotion = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.HaltMotion", - HaltMotion) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/JointTransmittedWrench.hh b/include/ignition/gazebo/components/JointTransmittedWrench.hh index a723fdc285..3b605deca8 100644 --- a/include/ignition/gazebo/components/JointTransmittedWrench.hh +++ b/include/ignition/gazebo/components/JointTransmittedWrench.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,43 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - -namespace components -{ -/// \brief Joint Transmitted wrench in SI units (Nm for torque, N for force). -/// The wrench is expressed in the Joint frame and the force component is -/// applied at the joint origin. -/// \note The term Wrench is used here to mean a pair of 3D vectors representing -/// torque and force quantities expressed in a given frame and where the force -/// is applied at the origin of the frame. This is different from the Wrench -/// used in screw theory. -/// \note The value of force_offset in msgs::Wrench is ignored for this -/// component. The force is assumed to be applied at the origin of the joint -/// frame. -using JointTransmittedWrench = - Component; -IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.JointTransmittedWrench", - JointTransmittedWrench) -} // namespace components -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/LightCmd.hh b/include/ignition/gazebo/components/LightCmd.hh index fdba5858fc..d9a4c56bc3 100644 --- a/include/ignition/gazebo/components/LightCmd.hh +++ b/include/ignition/gazebo/components/LightCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,35 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LIGHTCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LIGHTCMD_HH_ - -#include +#include #include -#include -#include -#include -#include - -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains commanded light of an - /// entity in the world frame represented by msgs::Light. - using LightCmd = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LightCmd", - LightCmd) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/LightType.hh b/include/ignition/gazebo/components/LightType.hh index 249eb8602f..bb83332ce6 100644 --- a/include/ignition/gazebo/components/LightType.hh +++ b/include/ignition/gazebo/components/LightType.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,34 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_LIGHTTYPE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LIGHTTYPE_HH_ + */ -#include -#include -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that contains the light type. This is a simple wrapper - /// around std::string - using LightType = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LightType", LightType) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/NavSat.hh b/include/ignition/gazebo/components/NavSat.hh index ae3358b9b4..9dec2250cc 100644 --- a/include/ignition/gazebo/components/NavSat.hh +++ b/include/ignition/gazebo/components/NavSat.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,34 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_NAVSAT_HH_ -#define IGNITION_GAZEBO_COMPONENTS_NAVSAT_HH_ - -#include + */ +#include #include -#include - -#include -#include -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains an NavSat sensor, - /// sdf::NavSat, information. - using NavSat = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.NavSat", NavSat) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/ParticleEmitter.hh b/include/ignition/gazebo/components/ParticleEmitter.hh index 86fc36bd88..7c86a7a187 100644 --- a/include/ignition/gazebo/components/ParticleEmitter.hh +++ b/include/ignition/gazebo/components/ParticleEmitter.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,40 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ + */ -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that contains a particle emitter. - using ParticleEmitter = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ParticleEmitter", - ParticleEmitter) - - /// \brief A component that contains a particle emitter command. - using ParticleEmitterCmd = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ParticleEmitterCmd", - ParticleEmitterCmd) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Recreate.hh b/include/ignition/gazebo/components/Recreate.hh index bb053fe5f9..f11585232a 100644 --- a/include/ignition/gazebo/components/Recreate.hh +++ b/include/ignition/gazebo/components/Recreate.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,36 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_RECREATE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_RECREATE_HH_ + */ -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that identifies an entity needs to be recreated. - /// Currently, only Models will be processed for recreation by the - /// SimulationRunner in the ProcessRecreateEntitiesRemove and - /// ProcessRecreateEntitiesCreate functions. - /// - /// The GUI ModelEditor contains example code on how to use this - /// component. For example, the ModelEditor allows a user to add a link to an - /// existing model. The existing model is tagged with this component so - /// that it can be recreated by the server. - using Recreate = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Recreate", Recreate) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/RenderEngineServerHeadless.hh b/include/ignition/gazebo/components/RenderEngineServerHeadless.hh index 9746e4b0aa..dc0a7cfa38 100644 --- a/include/ignition/gazebo/components/RenderEngineServerHeadless.hh +++ b/include/ignition/gazebo/components/RenderEngineServerHeadless.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,33 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ -#define IGNITION_GAZEBO_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ + */ -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Holds the headless mode. - using RenderEngineServerHeadless = Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.RenderEngineServerHeadless", - RenderEngineServerHeadless) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/SegmentationCamera.hh b/include/ignition/gazebo/components/SegmentationCamera.hh index c476fc8ba8..0bcedbce99 100644 --- a/include/ignition/gazebo/components/SegmentationCamera.hh +++ b/include/ignition/gazebo/components/SegmentationCamera.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,33 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_SEGMENTATIONCAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SEGMENTATIONCAMERA_HH_ + */ -#include - -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains a Segmentation camera sensor, - /// sdf::Camera, information. - using SegmentationCamera = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SegmentationCamera", - SegmentationCamera) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/SemanticLabel.hh b/include/ignition/gazebo/components/SemanticLabel.hh index 3139b75310..985cd6b8d3 100644 --- a/include/ignition/gazebo/components/SemanticLabel.hh +++ b/include/ignition/gazebo/components/SemanticLabel.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,30 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LABEL_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LABEL_HH_ -#include "ignition/gazebo/Export.hh" -#include "ignition/gazebo/components/Component.hh" -#include "ignition/gazebo/components/Factory.hh" -#include "ignition/gazebo/config.hh" - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component that holds the label of an entity. One example use - /// case of the Label component is with Segmentation & Bounding box - /// sensors to generate dataset annotations. - using SemanticLabel = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SemanticLabel", - SemanticLabel) -} -} -} -} -#endif +#include +#include diff --git a/include/ignition/gazebo/components/SphericalCoordinates.hh b/include/ignition/gazebo/components/SphericalCoordinates.hh index 93ebd43fa8..ef6996f098 100644 --- a/include/ignition/gazebo/components/SphericalCoordinates.hh +++ b/include/ignition/gazebo/components/SphericalCoordinates.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,41 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ + */ -#include -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace serializers -{ - using SphericalCoordinatesSerializer = - serializers::ComponentToMsgSerializer; -} - -namespace components -{ - /// \brief This component holds the spherical coordinates of the world origin. - using SphericalCoordinates = - Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.SphericalCoordinates", SphericalCoordinates) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/SystemPluginInfo.hh b/include/ignition/gazebo/components/SystemPluginInfo.hh index 365886c1e4..96e9d65758 100644 --- a/include/ignition/gazebo/components/SystemPluginInfo.hh +++ b/include/ignition/gazebo/components/SystemPluginInfo.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2022 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,35 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_SYSTEMINFO_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SYSTEMINFO_HH_ + */ -#include -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief This component holds information about all the system plugins that - /// are attached to an entity. The content of each system is populated the - /// moment the plugin is instantiated and isn't modified throughout - /// simulation. - using SystemPluginInfo = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.SystemPluginInfo", - SystemPluginInfo) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/TemperatureRange.hh b/include/ignition/gazebo/components/TemperatureRange.hh index 99e4a26151..0ca9e81f40 100644 --- a/include/ignition/gazebo/components/TemperatureRange.hh +++ b/include/ignition/gazebo/components/TemperatureRange.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,87 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_TEMPERATURERANGE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_TEMPERATURERANGE_HH_ + */ -#include -#include - -#include - -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief Data structure to hold a temperature range, in kelvin - struct TemperatureRangeInfo - { - /// \brief The minimum temperature (kelvin) - math::Temperature min; - /// \brief The maximum temperature (kelvin) - math::Temperature max; - - public: bool operator==(const TemperatureRangeInfo &_info) const - { - return (this->min == _info.min) && - (this->max == _info.max); - } - - public: bool operator!=(const TemperatureRangeInfo &_info) const - { - return !(*this == _info); - } - }; -} - -namespace serializers -{ - /// \brief Serializer for components::TemperatureRangeInfo object - class TemperatureRangeInfoSerializer - { - /// \brief Serialization for components::TemperatureRangeInfo - /// \param[out] _out Output stream - /// \param[in] _info Object for the stream - /// \return The stream - public: static std::ostream &Serialize(std::ostream &_out, - const components::TemperatureRangeInfo &_info) - { - _out << _info.min << " " << _info.max; - return _out; - } - - /// \brief Deserialization for components::TemperatureRangeInfo - /// \param[in] _in Input stream - /// \param[out] _info The object to populate - /// \return The stream - public: static std::istream &Deserialize(std::istream &_in, - components::TemperatureRangeInfo &_info) - { - _in >> _info.min >> _info.max; - return _in; - } - }; -} - -namespace components -{ - /// \brief A component that stores a temperature range in kelvin - using TemperatureRange = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.TemperatureRange", - TemperatureRange) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/Visibility.hh b/include/ignition/gazebo/components/Visibility.hh index 7a53ddbb3e..a3f52c491e 100644 --- a/include/ignition/gazebo/components/Visibility.hh +++ b/include/ignition/gazebo/components/Visibility.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -13,36 +13,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * -*/ -#ifndef IGNITION_GAZEBO_COMPONENTS_VISIBILITY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_VISIBILITY_HH_ + */ -#include -#include -#include +#include #include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief This component holds an entity's visibility flags (visual entities) - using VisibilityFlags = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.VisibilityFlags", - VisibilityFlags) - - /// \brief This component holds an entity's visibility mask - /// (camera sensor entities) - using VisibilityMask = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.VisibilityMask", - VisibilityMask) -} -} -} -} - -#endif diff --git a/include/ignition/gazebo/components/VisualCmd.hh b/include/ignition/gazebo/components/VisualCmd.hh index 794057aabb..bd6a95e618 100644 --- a/include/ignition/gazebo/components/VisualCmd.hh +++ b/include/ignition/gazebo/components/VisualCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2021 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,35 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_VISUALCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_VISUALCMD_HH_ +#include #include -#include -#include -#include -#include - -#include - -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains commanded visual of an - /// entity in the world frame represented by msgs::Visual. - using VisualCmd = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.VisualCmd", - VisualCmd) -} -} -} -} -#endif diff --git a/include/ignition/gazebo/components/WheelSlipCmd.hh b/include/ignition/gazebo/components/WheelSlipCmd.hh index 4daf7ee249..8c90b88a7b 100644 --- a/include/ignition/gazebo/components/WheelSlipCmd.hh +++ b/include/ignition/gazebo/components/WheelSlipCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2022 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,33 +14,6 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ +#include #include -#include -#include -#include -#include - -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace components -{ - /// \brief A component type that contains commanded wheel slip parameters of - /// an entity in the world frame represented by msgs::WheelSlipParameters. - using WheelSlipCmd = Component; - IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WheelSlipCmd", - WheelSlipCmd) -} -} -} -} -#endif From 5f1458ac6c8c9014b1aa44b9aa44110002ac47d5 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Thu, 25 May 2023 21:00:56 -0700 Subject: [PATCH 10/31] fixed comments Signed-off-by: Nate Koenig --- include/gz/sim/Actor.hh | 4 +- include/gz/sim/Joint.hh | 4 +- include/gz/sim/Light.hh | 4 +- include/gz/sim/Primitives.hh | 4 +- include/gz/sim/Sensor.hh | 4 +- include/gz/sim/comms/Broker.hh | 4 +- include/gz/sim/comms/ICommsModel.hh | 4 +- include/gz/sim/comms/MsgManager.hh | 4 +- include/gz/sim/components/BatteryPowerLoad.hh | 4 +- .../gz/sim/components/BoundingBoxCamera.hh | 4 +- include/gz/sim/components/CustomSensor.hh | 4 +- include/gz/sim/components/Factory.hh | 7 +-- include/gz/sim/components/ForceTorque.hh | 4 +- include/gz/sim/components/HaltMotion.hh | 4 +- .../sim/components/JointTransmittedWrench.hh | 4 +- include/gz/sim/components/LightCmd.hh | 4 +- include/gz/sim/components/LightType.hh | 4 +- include/gz/sim/components/NavSat.hh | 4 +- include/gz/sim/components/ParticleEmitter.hh | 4 +- include/gz/sim/components/Recreate.hh | 4 +- .../components/RenderEngineServerHeadless.hh | 4 +- .../gz/sim/components/SegmentationCamera.hh | 4 +- include/gz/sim/components/SemanticLabel.hh | 4 +- .../gz/sim/components/SphericalCoordinates.hh | 4 +- include/gz/sim/components/SystemPluginInfo.hh | 4 +- include/gz/sim/components/TemperatureRange.hh | 4 +- include/gz/sim/components/Visibility.hh | 4 +- include/gz/sim/components/VisualCmd.hh | 4 +- include/gz/sim/components/WheelSlipCmd.hh | 4 +- include/gz/sim/detail/BaseView.hh | 4 +- include/gz/sim/rendering/MarkerManager.hh | 1 + src/Server_TEST.cc | 12 ++--- src/gui/GuiRunner.cc | 14 +++--- src/gui/plugins/align_tool/AlignTool.cc | 2 +- .../banana_for_scale/BananaForScale.cc | 10 ++-- .../banana_for_scale/BananaForScale.hh | 2 +- .../ComponentInspectorEditor.cc | 18 +++---- .../component_inspector_editor/ModelEditor.cc | 8 ++-- src/gui/plugins/copy_paste/CopyPaste.cc | 16 +++---- .../EntityContextMenuPlugin.cc | 14 +++--- .../EntityContextMenuPlugin.hh | 2 +- src/gui/plugins/entity_tree/EntityTree.cc | 12 ++--- src/gui/plugins/lights/Lights.cc | 10 ++-- src/gui/plugins/lights/Lights.hh | 2 +- src/gui/plugins/plotting/Plotting.cc | 6 +-- src/gui/plugins/plotting/Plotting.hh | 2 +- src/gui/plugins/scene3d/Scene3D.cc | 16 +++---- .../plugins/scene_manager/GzSceneManager.cc | 22 ++++----- .../plugins/scene_manager/GzSceneManager.hh | 2 +- .../plugins/select_entities/SelectEntities.cc | 40 ++++++++-------- .../plugins/select_entities/SelectEntities.hh | 2 +- src/gui/plugins/shapes/Shapes.cc | 6 +-- src/gui/plugins/spawn/Spawn.cc | 48 +++++++++---------- src/gui/plugins/spawn/Spawn.hh | 4 +- .../transform_control/TransformControl.cc | 40 ++++++++-------- .../plugins/video_recorder/VideoRecorder.cc | 4 +- src/gui/plugins/view_angle/ViewAngle.cc | 6 +-- .../VisualizationCapabilities.cc | 8 ++-- .../visualize_contacts/VisualizeContacts.cc | 2 +- .../plugins/visualize_lidar/VisualizeLidar.cc | 12 ++--- 60 files changed, 234 insertions(+), 232 deletions(-) diff --git a/include/gz/sim/Actor.hh b/include/gz/sim/Actor.hh index e19f154a0a..b95db5e897 100644 --- a/include/gz/sim/Actor.hh +++ b/include/gz/sim/Actor.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_ACTOR_HH_ -#define IGNITION_GAZEBO_ACTOR_HH_ +#ifndef GZ_GAZEBO_ACTOR_HH_ +#define GZ_GAZEBO_ACTOR_HH_ #include #include diff --git a/include/gz/sim/Joint.hh b/include/gz/sim/Joint.hh index e58ed60264..ea79b96a3e 100644 --- a/include/gz/sim/Joint.hh +++ b/include/gz/sim/Joint.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_JOINT_HH_ -#define IGNITION_GAZEBO_JOINT_HH_ +#ifndef GZ_GAZEBO_JOINT_HH_ +#define GZ_GAZEBO_JOINT_HH_ #include #include diff --git a/include/gz/sim/Light.hh b/include/gz/sim/Light.hh index 130809bac3..72c408beb1 100644 --- a/include/gz/sim/Light.hh +++ b/include/gz/sim/Light.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_LIGHT_HH_ -#define IGNITION_GAZEBO_LIGHT_HH_ +#ifndef GZ_GAZEBO_LIGHT_HH_ +#define GZ_GAZEBO_LIGHT_HH_ #include #include diff --git a/include/gz/sim/Primitives.hh b/include/gz/sim/Primitives.hh index cb68727af3..1a519b1e05 100644 --- a/include/gz/sim/Primitives.hh +++ b/include/gz/sim/Primitives.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_PRIMITIVES_HH_ -#define IGNITION_GAZEBO_PRIMITIVES_HH_ +#ifndef GZ_GAZEBO_PRIMITIVES_HH_ +#define GZ_GAZEBO_PRIMITIVES_HH_ #include #include diff --git a/include/gz/sim/Sensor.hh b/include/gz/sim/Sensor.hh index ee08c8a814..7f727b2247 100644 --- a/include/gz/sim/Sensor.hh +++ b/include/gz/sim/Sensor.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SENSOR_HH_ -#define IGNITION_GAZEBO_SENSOR_HH_ +#ifndef GZ_GAZEBO_SENSOR_HH_ +#define GZ_GAZEBO_SENSOR_HH_ #include #include diff --git a/include/gz/sim/comms/Broker.hh b/include/gz/sim/comms/Broker.hh index f25646d575..f8825a29a6 100644 --- a/include/gz/sim/comms/Broker.hh +++ b/include/gz/sim/comms/Broker.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_BROKER_HH_ -#define IGNITION_GAZEBO_BROKER_HH_ +#ifndef GZ_GAZEBO_BROKER_HH_ +#define GZ_GAZEBO_BROKER_HH_ #include diff --git a/include/gz/sim/comms/ICommsModel.hh b/include/gz/sim/comms/ICommsModel.hh index e91ee63335..add9811a3f 100644 --- a/include/gz/sim/comms/ICommsModel.hh +++ b/include/gz/sim/comms/ICommsModel.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_ICOMMSMODEL_HH_ -#define IGNITION_GAZEBO_ICOMMSMODEL_HH_ +#ifndef GZ_GAZEBO_ICOMMSMODEL_HH_ +#define GZ_GAZEBO_ICOMMSMODEL_HH_ #include diff --git a/include/gz/sim/comms/MsgManager.hh b/include/gz/sim/comms/MsgManager.hh index 68ebfbd54b..8b50a33f06 100644 --- a/include/gz/sim/comms/MsgManager.hh +++ b/include/gz/sim/comms/MsgManager.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_MSGMANAGER_HH_ -#define IGNITION_GAZEBO_MSGMANAGER_HH_ +#ifndef GZ_GAZEBO_MSGMANAGER_HH_ +#define GZ_GAZEBO_MSGMANAGER_HH_ #include #include diff --git a/include/gz/sim/components/BatteryPowerLoad.hh b/include/gz/sim/components/BatteryPowerLoad.hh index 47764ca4b2..2a25996a4c 100644 --- a/include/gz/sim/components/BatteryPowerLoad.hh +++ b/include/gz/sim/components/BatteryPowerLoad.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_BATTERYPOWERLOAD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_BATTERYPOWERLOAD_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_BATTERYPOWERLOAD_HH_ +#define GZ_GAZEBO_COMPONENTS_BATTERYPOWERLOAD_HH_ #include #include diff --git a/include/gz/sim/components/BoundingBoxCamera.hh b/include/gz/sim/components/BoundingBoxCamera.hh index 39d56f1d84..cc9fd8f29f 100644 --- a/include/gz/sim/components/BoundingBoxCamera.hh +++ b/include/gz/sim/components/BoundingBoxCamera.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_BOUNDINGBOXCAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_BOUNDINGBOXCAMERA_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_BOUNDINGBOXCAMERA_HH_ +#define GZ_GAZEBO_COMPONENTS_BOUNDINGBOXCAMERA_HH_ #include diff --git a/include/gz/sim/components/CustomSensor.hh b/include/gz/sim/components/CustomSensor.hh index 63b79d63d1..54965bf58e 100644 --- a/include/gz/sim/components/CustomSensor.hh +++ b/include/gz/sim/components/CustomSensor.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_CUSTOMSENSOR_HH_ -#define IGNITION_GAZEBO_COMPONENTS_CUSTOMSENSOR_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_CUSTOMSENSOR_HH_ +#define GZ_GAZEBO_COMPONENTS_CUSTOMSENSOR_HH_ #include #include diff --git a/include/gz/sim/components/Factory.hh b/include/gz/sim/components/Factory.hh index 7883333888..456cf3fc20 100644 --- a/include/gz/sim/components/Factory.hh +++ b/include/gz/sim/components/Factory.hh @@ -512,9 +512,10 @@ namespace components public: IgnGazeboComponents##_classname() \ { \ using namespace ignition; \ - using Desc = gazebo::components::ComponentDescriptor<_classname>; \ - gazebo::components::Factory::Instance()->Register<_classname>(\ - _compType, new Desc(), gazebo::components::RegistrationObjectId(this));\ + using Desc = gz::sim::components::ComponentDescriptor<_classname>; \ + gz::sim::components::Factory::Instance()->Register<_classname>(\ + _compType, new Desc(), \ + gz::sim::components::RegistrationObjectId(this));\ } \ public: IgnGazeboComponents##_classname( \ const IgnGazeboComponents##_classname&) = delete; \ diff --git a/include/gz/sim/components/ForceTorque.hh b/include/gz/sim/components/ForceTorque.hh index 98c42c1f67..1801ed85de 100644 --- a/include/gz/sim/components/ForceTorque.hh +++ b/include/gz/sim/components/ForceTorque.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_FORCETORQUE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_FORCETORQUE_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_FORCETORQUE_HH_ +#define GZ_GAZEBO_COMPONENTS_FORCETORQUE_HH_ #include diff --git a/include/gz/sim/components/HaltMotion.hh b/include/gz/sim/components/HaltMotion.hh index ece6c659df..3d231b54dd 100644 --- a/include/gz/sim/components/HaltMotion.hh +++ b/include/gz/sim/components/HaltMotion.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_HALT_MOTION_HH_ -#define IGNITION_GAZEBO_COMPONENTS_HALT_MOTION_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_HALT_MOTION_HH_ +#define GZ_GAZEBO_COMPONENTS_HALT_MOTION_HH_ #include #include diff --git a/include/gz/sim/components/JointTransmittedWrench.hh b/include/gz/sim/components/JointTransmittedWrench.hh index e082f1ab1a..2affd4f6a5 100644 --- a/include/gz/sim/components/JointTransmittedWrench.hh +++ b/include/gz/sim/components/JointTransmittedWrench.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ -#define IGNITION_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ +#define GZ_GAZEBO_COMPONENTS_JOINTTRANSMITTEDWRENCH_HH_ #include diff --git a/include/gz/sim/components/LightCmd.hh b/include/gz/sim/components/LightCmd.hh index b4e36b8ddd..3dbc6803cd 100644 --- a/include/gz/sim/components/LightCmd.hh +++ b/include/gz/sim/components/LightCmd.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LIGHTCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LIGHTCMD_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_LIGHTCMD_HH_ +#define GZ_GAZEBO_COMPONENTS_LIGHTCMD_HH_ #include diff --git a/include/gz/sim/components/LightType.hh b/include/gz/sim/components/LightType.hh index ffc3ed62c7..e40f114b3c 100644 --- a/include/gz/sim/components/LightType.hh +++ b/include/gz/sim/components/LightType.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LIGHTTYPE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LIGHTTYPE_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_LIGHTTYPE_HH_ +#define GZ_GAZEBO_COMPONENTS_LIGHTTYPE_HH_ #include #include diff --git a/include/gz/sim/components/NavSat.hh b/include/gz/sim/components/NavSat.hh index 35c864563a..29e9af8ddc 100644 --- a/include/gz/sim/components/NavSat.hh +++ b/include/gz/sim/components/NavSat.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_NAVSAT_HH_ -#define IGNITION_GAZEBO_COMPONENTS_NAVSAT_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_NAVSAT_HH_ +#define GZ_GAZEBO_COMPONENTS_NAVSAT_HH_ #include diff --git a/include/gz/sim/components/ParticleEmitter.hh b/include/gz/sim/components/ParticleEmitter.hh index 7d70532c22..4771bb89fc 100644 --- a/include/gz/sim/components/ParticleEmitter.hh +++ b/include/gz/sim/components/ParticleEmitter.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ -#define IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ +#define GZ_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ #include #include diff --git a/include/gz/sim/components/Recreate.hh b/include/gz/sim/components/Recreate.hh index d15ea5fdf4..6f9eb082a0 100644 --- a/include/gz/sim/components/Recreate.hh +++ b/include/gz/sim/components/Recreate.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_RECREATE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_RECREATE_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_RECREATE_HH_ +#define GZ_GAZEBO_COMPONENTS_RECREATE_HH_ #include #include diff --git a/include/gz/sim/components/RenderEngineServerHeadless.hh b/include/gz/sim/components/RenderEngineServerHeadless.hh index 0f9ea36ebc..05ab542dc4 100644 --- a/include/gz/sim/components/RenderEngineServerHeadless.hh +++ b/include/gz/sim/components/RenderEngineServerHeadless.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ -#define IGNITION_GAZEBO_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ +#define GZ_GAZEBO_COMPONENTS_RENDERENGINESERVERHEADLESS_HH_ #include #include diff --git a/include/gz/sim/components/SegmentationCamera.hh b/include/gz/sim/components/SegmentationCamera.hh index b84658a6ef..35cf4399d5 100644 --- a/include/gz/sim/components/SegmentationCamera.hh +++ b/include/gz/sim/components/SegmentationCamera.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_SEGMENTATIONCAMERA_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SEGMENTATIONCAMERA_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_SEGMENTATIONCAMERA_HH_ +#define GZ_GAZEBO_COMPONENTS_SEGMENTATIONCAMERA_HH_ #include diff --git a/include/gz/sim/components/SemanticLabel.hh b/include/gz/sim/components/SemanticLabel.hh index 9282751be8..0416d1b310 100644 --- a/include/gz/sim/components/SemanticLabel.hh +++ b/include/gz/sim/components/SemanticLabel.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_LABEL_HH_ -#define IGNITION_GAZEBO_COMPONENTS_LABEL_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_LABEL_HH_ +#define GZ_GAZEBO_COMPONENTS_LABEL_HH_ #include "gz/sim/Export.hh" #include "gz/sim/components/Component.hh" diff --git a/include/gz/sim/components/SphericalCoordinates.hh b/include/gz/sim/components/SphericalCoordinates.hh index 1f98bf7331..ea19224625 100644 --- a/include/gz/sim/components/SphericalCoordinates.hh +++ b/include/gz/sim/components/SphericalCoordinates.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ +#define GZ_GAZEBO_COMPONENTS_SPHERICALCOORDINATES_HH_ #include #include diff --git a/include/gz/sim/components/SystemPluginInfo.hh b/include/gz/sim/components/SystemPluginInfo.hh index 4990b2a2ee..6e0389d0e4 100644 --- a/include/gz/sim/components/SystemPluginInfo.hh +++ b/include/gz/sim/components/SystemPluginInfo.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_SYSTEMINFO_HH_ -#define IGNITION_GAZEBO_COMPONENTS_SYSTEMINFO_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_SYSTEMINFO_HH_ +#define GZ_GAZEBO_COMPONENTS_SYSTEMINFO_HH_ #include #include diff --git a/include/gz/sim/components/TemperatureRange.hh b/include/gz/sim/components/TemperatureRange.hh index 668fa2a7ef..24a5e5f4ff 100644 --- a/include/gz/sim/components/TemperatureRange.hh +++ b/include/gz/sim/components/TemperatureRange.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_TEMPERATURERANGE_HH_ -#define IGNITION_GAZEBO_COMPONENTS_TEMPERATURERANGE_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_TEMPERATURERANGE_HH_ +#define GZ_GAZEBO_COMPONENTS_TEMPERATURERANGE_HH_ #include #include diff --git a/include/gz/sim/components/Visibility.hh b/include/gz/sim/components/Visibility.hh index 3465db7eaa..d39f263794 100644 --- a/include/gz/sim/components/Visibility.hh +++ b/include/gz/sim/components/Visibility.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_VISIBILITY_HH_ -#define IGNITION_GAZEBO_COMPONENTS_VISIBILITY_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_VISIBILITY_HH_ +#define GZ_GAZEBO_COMPONENTS_VISIBILITY_HH_ #include #include diff --git a/include/gz/sim/components/VisualCmd.hh b/include/gz/sim/components/VisualCmd.hh index 71a424ec9b..7bfcfcbd05 100644 --- a/include/gz/sim/components/VisualCmd.hh +++ b/include/gz/sim/components/VisualCmd.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_VISUALCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_VISUALCMD_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_VISUALCMD_HH_ +#define GZ_GAZEBO_COMPONENTS_VISUALCMD_HH_ #include #include diff --git a/include/gz/sim/components/WheelSlipCmd.hh b/include/gz/sim/components/WheelSlipCmd.hh index ec6ae1b3bb..b87e756f50 100644 --- a/include/gz/sim/components/WheelSlipCmd.hh +++ b/include/gz/sim/components/WheelSlipCmd.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ -#define IGNITION_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ +#ifndef GZ_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ +#define GZ_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_ #include #include diff --git a/include/gz/sim/detail/BaseView.hh b/include/gz/sim/detail/BaseView.hh index 6452524bd8..3fc53d4453 100644 --- a/include/gz/sim/detail/BaseView.hh +++ b/include/gz/sim/detail/BaseView.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_DETAIL_BASEVIEW_HH_ -#define IGNITION_GAZEBO_DETAIL_BASEVIEW_HH_ +#ifndef GZ_GAZEBO_DETAIL_BASEVIEW_HH_ +#define GZ_GAZEBO_DETAIL_BASEVIEW_HH_ #include #include diff --git a/include/gz/sim/rendering/MarkerManager.hh b/include/gz/sim/rendering/MarkerManager.hh index 5139505772..26c4b0d716 100644 --- a/include/gz/sim/rendering/MarkerManager.hh +++ b/include/gz/sim/rendering/MarkerManager.hh @@ -20,6 +20,7 @@ #include #include +#include #include #include "gz/rendering/RenderTypes.hh" diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc index 509c730c95..5e1a89b5da 100644 --- a/src/Server_TEST.cc +++ b/src/Server_TEST.cc @@ -170,7 +170,7 @@ TEST_P(ServerFixture, ServerConfigSdfPluginInfo) plugin.SetName("interface"); pluginInfo.SetPlugin(plugin); - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.AddPlugin(pluginInfo); const std::list &plugins = serverConfig.Plugins(); @@ -364,7 +364,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(SdfServerConfig)) ///////////////////////////////////////////////// TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(SdfRootServerConfig)) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetSdfString(TestWorldSansPhysics::World()); EXPECT_TRUE(serverConfig.SdfFile().empty()); @@ -386,7 +386,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(SdfRootServerConfig)) EXPECT_TRUE(serverConfig.SdfFile().empty()); EXPECT_TRUE(serverConfig.SdfString().empty()); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_TRUE(*server.Paused()); @@ -693,7 +693,7 @@ TEST_P(ServerFixture, RunNonBlockingMultiple) { ServerConfig serverConfig; serverConfig.SetSdfString(TestWorldSansPhysics::World()); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); @@ -1113,7 +1113,7 @@ TEST_P(ServerFixture, ResolveResourcePaths) common::setenv("IGN_FILE_PATH", ""); ServerConfig serverConfig; - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); EXPECT_FALSE(*server.Running(0)); @@ -1186,7 +1186,7 @@ TEST_P(ServerFixture, Stop) serverConfig.SetSdfFile(common::joinPaths((PROJECT_SOURCE_PATH), "test", "worlds", "shapes.sdf")); - gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); // The simulation runner should not be running. EXPECT_FALSE(*server.Running(0)); diff --git a/src/gui/GuiRunner.cc b/src/gui/GuiRunner.cc index 27f82039dc..5d2580eb5c 100644 --- a/src/gui/GuiRunner.cc +++ b/src/gui/GuiRunner.cc @@ -154,8 +154,8 @@ GuiRunner::GuiRunner(const std::string &_worldName) this->dataPtr->controlService = "/world/" + _worldName + "/control/state"; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); } ///////////////////////////////////////////////// @@ -164,10 +164,10 @@ GuiRunner::~GuiRunner() = default; ///////////////////////////////////////////////// bool GuiRunner::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::WorldControl::kType) + if (_event->type() == gz::gui::events::WorldControl::kType) { auto worldControlEvent = - reinterpret_cast(_event); + reinterpret_cast(_event); if (worldControlEvent) { msgs::WorldControlState req; @@ -232,7 +232,7 @@ bool GuiRunner::eventFilter(QObject *_obj, QEvent *_event) void GuiRunner::RequestState() { // set up service for async state response callback - std::string id = std::to_string(ignition::gui::App()->applicationPid()); + std::string id = std::to_string(gz::gui::App()->applicationPid()); std::string reqSrv = this->dataPtr->node.Options().NameSpace() + "/" + id + "/state_async"; auto reqSrvValid = transport::TopicUtils::AsValidTopic(reqSrv); @@ -286,7 +286,7 @@ void GuiRunner::OnStateAsyncService(const msgs::SerializedStepMap &_res) // todo(anyone) store reqSrv string in a member variable and use it here // and in RequestState() - std::string id = std::to_string(ignition::gui::App()->applicationPid()); + std::string id = std::to_string(gz::gui::App()->applicationPid()); std::string reqSrv = this->dataPtr->node.Options().NameSpace() + "/" + id + "/state_async"; this->dataPtr->node.UnadvertiseSrv(reqSrv); @@ -326,7 +326,7 @@ void GuiRunner::OnStateQt(const msgs::SerializedStepMap &_msg) void GuiRunner::UpdatePlugins() { // gui plugins - auto plugins = ignition::gui::App()->findChildren(); + auto plugins = gz::gui::App()->findChildren(); for (auto plugin : plugins) { plugin->Update(this->dataPtr->updateInfo, this->dataPtr->ecm); diff --git a/src/gui/plugins/align_tool/AlignTool.cc b/src/gui/plugins/align_tool/AlignTool.cc index 5fdbcf4f62..3a864e9016 100644 --- a/src/gui/plugins/align_tool/AlignTool.cc +++ b/src/gui/plugins/align_tool/AlignTool.cc @@ -551,7 +551,7 @@ rendering::NodePtr AlignTool::TopLevelNode(rendering::ScenePtr &_scene, ///////////////////////////////////////////////// bool AlignTool::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { // This event is called in Scene3d's RenderThread, so it's safe to make // rendering calls here diff --git a/src/gui/plugins/banana_for_scale/BananaForScale.cc b/src/gui/plugins/banana_for_scale/BananaForScale.cc index a134466d00..f0627d57fc 100644 --- a/src/gui/plugins/banana_for_scale/BananaForScale.cc +++ b/src/gui/plugins/banana_for_scale/BananaForScale.cc @@ -54,7 +54,7 @@ using namespace gazebo; ///////////////////////////////////////////////// BananaForScale::BananaForScale() - : ignition::gui::Plugin(), + : gz::gui::Plugin(), dataPtr(std::make_unique()) { this->dataPtr->fuelClient = @@ -101,12 +101,12 @@ void BananaForScale::OnMode(const QString &_mode) sdfPath = ignition::common::joinPaths(localPath, "model.sdf"); } - ignition::gui::events::SpawnFromPath event(sdfPath); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::SpawnFromPath event(sdfPath); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); } // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::BananaForScale, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/banana_for_scale/BananaForScale.hh b/src/gui/plugins/banana_for_scale/BananaForScale.hh index 36e71d28f5..668f8a570c 100644 --- a/src/gui/plugins/banana_for_scale/BananaForScale.hh +++ b/src/gui/plugins/banana_for_scale/BananaForScale.hh @@ -29,7 +29,7 @@ namespace gazebo class BananaPrivate; /// \brief Provides buttons for adding a banana for scale - class BananaForScale: public ignition::gui::Plugin + class BananaForScale: public gz::gui::Plugin { Q_OBJECT diff --git a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc index 6aacd3b4dc..6c3655abe9 100644 --- a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc +++ b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc @@ -479,8 +479,8 @@ void ComponentInspectorEditor::LoadConfig(const tinyxml2::XMLElement *) if (this->title.empty()) this->title = "Component inspector editor"; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); // Connect model this->Context()->setContextProperty( @@ -1348,8 +1348,8 @@ void ComponentInspectorEditor::OnAddEntity(const QString &_entity, ignition::gazebo::gui::events::ModelEditorAddEntity addEntityEvent( _entity, _type, this->dataPtr->entity); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &addEntityEvent); } @@ -1364,8 +1364,8 @@ void ComponentInspectorEditor::OnAddJoint(const QString &_jointType, addEntityEvent.Data().insert("parent_link", _parentLink); addEntityEvent.Data().insert("child_link", _childLink); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &addEntityEvent); } @@ -1391,12 +1391,12 @@ void ComponentInspectorEditor::OnLoadMesh(const QString &_entity, addEntityEvent.Data().insert("uri", QString(meshStr.c_str())); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &addEntityEvent); } } // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::ComponentInspectorEditor, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/component_inspector_editor/ModelEditor.cc b/src/gui/plugins/component_inspector_editor/ModelEditor.cc index 2f88fcd717..b6d108d324 100644 --- a/src/gui/plugins/component_inspector_editor/ModelEditor.cc +++ b/src/gui/plugins/component_inspector_editor/ModelEditor.cc @@ -145,8 +145,8 @@ ModelEditor::~ModelEditor() = default; ///////////////////////////////////////////////// void ModelEditor::Load() { - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); } ////////////////////////////////////////////////// @@ -240,8 +240,8 @@ void ModelEditor::Update(const UpdateInfo &, std::set removedEntities; ignition::gazebo::gui::events::GuiNewRemovedEntities event( newEntities, removedEntities); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); this->dataPtr->entitiesToAdd.clear(); diff --git a/src/gui/plugins/copy_paste/CopyPaste.cc b/src/gui/plugins/copy_paste/CopyPaste.cc index 52bb86b9ce..3ec045b913 100644 --- a/src/gui/plugins/copy_paste/CopyPaste.cc +++ b/src/gui/plugins/copy_paste/CopyPaste.cc @@ -90,10 +90,10 @@ void CopyPaste::LoadConfig(const tinyxml2::XMLElement *) if (this->title.empty()) this->title = "Copy/Paste"; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->QuickWindow()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->QuickWindow()->installEventFilter(this); } ///////////////////////////////////////////////// @@ -123,9 +123,9 @@ void CopyPaste::OnPaste() // we should only paste if something has been copied if (!this->dataPtr->copiedData.empty()) { - ignition::gui::events::SpawnCloneFromName event(this->dataPtr->copiedData); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::SpawnCloneFromName event(this->dataPtr->copiedData); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); } } @@ -182,4 +182,4 @@ bool CopyPaste::PasteServiceCB(const ignition::msgs::Empty &/*_req*/, // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::CopyPaste, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc index ff916ff00b..d1dc2c17c2 100644 --- a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc +++ b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc @@ -112,21 +112,21 @@ void EntityContextMenu::LoadConfig(const tinyxml2::XMLElement *) if (this->title.empty()) this->title = "Entity Context Menu"; - ignition::gui::App()->findChild - ()->installEventFilter(this); + gz::gui::App()->findChild + ()->installEventFilter(this); } //////////////////////////////////////////////// bool EntityContextMenu::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { this->dataPtr->OnRender(); } - else if (_event->type() == ignition::gui::events::RightClickOnScene::kType) + else if (_event->type() == gz::gui::events::RightClickOnScene::kType) { - ignition::gui::events::RightClickOnScene *_e = - static_cast(_event); + gz::gui::events::RightClickOnScene *_e = + static_cast(_event); if (_e) { this->dataPtr->entityContextMenuHandler.HandleMouseContextMenu( @@ -205,4 +205,4 @@ void EntityContextMenuHandler::HandleMouseContextMenu( // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::EntityContextMenu, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh index e7fd8b0966..a0c0cd79d7 100644 --- a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh +++ b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh @@ -34,7 +34,7 @@ namespace gazebo /// \brief This plugin is in charge of showing the entity context menu when /// the right button is clicked on a visual. - class EntityContextMenu : public ignition::gui::Plugin + class EntityContextMenu : public gz::gui::Plugin { Q_OBJECT diff --git a/src/gui/plugins/entity_tree/EntityTree.cc b/src/gui/plugins/entity_tree/EntityTree.cc index b00ebf169f..828c872d9f 100644 --- a/src/gui/plugins/entity_tree/EntityTree.cc +++ b/src/gui/plugins/entity_tree/EntityTree.cc @@ -468,9 +468,9 @@ void EntityTree::DeselectAllEntities() void EntityTree::OnInsertEntity(const QString &_type) { std::string modelSdfString = getPrimitive(_type.toStdString()); - ignition::gui::events::SpawnFromDescription event(modelSdfString); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::SpawnFromDescription event(modelSdfString); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); } @@ -515,9 +515,9 @@ void EntityTree::OnLoadMesh(const QString &_mesh) "" ""; - ignition::gui::events::SpawnFromDescription event(sdf); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::SpawnFromDescription event(sdf); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); } diff --git a/src/gui/plugins/lights/Lights.cc b/src/gui/plugins/lights/Lights.cc index 395c4607d9..996eeed87a 100644 --- a/src/gui/plugins/lights/Lights.cc +++ b/src/gui/plugins/lights/Lights.cc @@ -47,7 +47,7 @@ using namespace gazebo; ///////////////////////////////////////////////// Lights::Lights() - : ignition::gui::Plugin(), + : gz::gui::Plugin(), dataPtr(std::make_unique()) { } @@ -70,13 +70,13 @@ void Lights::OnNewLightClicked(const QString &_sdfString) if (!modelSdfString.empty()) { - ignition::gui::events::SpawnFromDescription event(modelSdfString); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::SpawnFromDescription event(modelSdfString); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); } } // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::Lights, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/lights/Lights.hh b/src/gui/plugins/lights/Lights.hh index 49fd8dd063..dee445ff87 100644 --- a/src/gui/plugins/lights/Lights.hh +++ b/src/gui/plugins/lights/Lights.hh @@ -30,7 +30,7 @@ namespace gazebo /// \brief Provides buttons for adding a point, directional, or spot light /// to the scene - class Lights : public ignition::gui::Plugin + class Lights : public gz::gui::Plugin { Q_OBJECT diff --git a/src/gui/plugins/plotting/Plotting.cc b/src/gui/plugins/plotting/Plotting.cc index 902e0e5962..23b3486381 100644 --- a/src/gui/plugins/plotting/Plotting.cc +++ b/src/gui/plugins/plotting/Plotting.cc @@ -69,13 +69,13 @@ namespace ignition::gazebo /// \brief attributes of the components, /// ex: x,y,z attributes in Vector3d type component public: std::map> data; + std::shared_ptr> data; }; } using namespace ignition; using namespace ignition::gazebo; -using namespace ignition::gui; +using namespace gz::gui; ////////////////////////////////////////////////// PlotComponent::PlotComponent(const std::string &_type, @@ -552,4 +552,4 @@ void Plotting::Update(const ignition::gazebo::UpdateInfo &_info, // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::Plotting, ignition::gazebo::GuiSystem, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/plotting/Plotting.hh b/src/gui/plugins/plotting/Plotting.hh index 578bb7ff6c..29b003fb34 100644 --- a/src/gui/plugins/plotting/Plotting.hh +++ b/src/gui/plugins/plotting/Plotting.hh @@ -76,7 +76,7 @@ class PlotComponent /// \brief Get all attributes of the component /// \return component attributes - public: std::map> + public: std::map> Data() const; /// \brief Get the Component entity ID diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 20a4212356..80cf24845a 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -2112,7 +2112,7 @@ std::string IgnRenderer::Initialize() } this->dataPtr->renderUtil.SetWinID(std::to_string( - ignition::gui::App()->findChild()-> + gz::gui::App()->findChild()-> QuickWindow()->winId())); this->dataPtr->renderUtil.SetUseCurrentGLContext(true); this->dataPtr->renderUtil.Init(); @@ -3713,7 +3713,7 @@ bool Scene3D::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - gui::events::DeselectAllEntities::kType) + gz::sim::gui::events::DeselectAllEntities::kType) { auto deselectEvent = reinterpret_cast( @@ -3727,9 +3727,9 @@ bool Scene3D::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gui::events::SnapIntervals::kType) + gz::gui::events::SnapIntervals::kType) { - auto snapEvent = reinterpret_cast( + auto snapEvent = reinterpret_cast( _event); if (snapEvent) { @@ -3740,20 +3740,20 @@ bool Scene3D::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gui::events::SpawnFromDescription::kType) + gz::gui::events::SpawnFromDescription::kType) { auto spawnPreviewEvent = reinterpret_cast< - ignition::gui::events::SpawnFromDescription *>(_event); + gz::gui::events::SpawnFromDescription *>(_event); if (spawnPreviewEvent) { auto renderWindow = this->PluginItem()->findChild(); renderWindow->SetModel(spawnPreviewEvent->Description()); } } - else if (_event->type() == ignition::gui::events::SpawnFromPath::kType) + else if (_event->type() == gz::gui::events::SpawnFromPath::kType) { auto spawnPreviewPathEvent = - reinterpret_cast(_event); + reinterpret_cast(_event); if (spawnPreviewPathEvent) { auto renderWindow = this->PluginItem()->findChild(); diff --git a/src/gui/plugins/scene_manager/GzSceneManager.cc b/src/gui/plugins/scene_manager/GzSceneManager.cc index 62bdf3c70d..3cfd836fb4 100644 --- a/src/gui/plugins/scene_manager/GzSceneManager.cc +++ b/src/gui/plugins/scene_manager/GzSceneManager.cc @@ -111,8 +111,8 @@ void GzSceneManager::LoadConfig(const tinyxml2::XMLElement *) } done = true; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); this->dataPtr->initialized = true; } @@ -177,8 +177,8 @@ void GzSceneManager::Update(const UpdateInfo &_info, // Send the new VisualPlugins event ignition::gazebo::gui::events::VisualPlugins visualPluginsEvent( it.first, it.second); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &visualPluginsEvent); // Send the old VisualPlugin event @@ -186,8 +186,8 @@ void GzSceneManager::Update(const UpdateInfo &_info, { ignition::gazebo::gui::events::VisualPlugin visualPluginEvent( it.first, plugin.ToElement()); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &visualPluginEvent); } } @@ -211,15 +211,15 @@ void GzSceneManager::Update(const UpdateInfo &_info, ignition::gazebo::gui::events::NewRemovedEntities removedEvent( created, removed); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &removedEvent); } ///////////////////////////////////////////////// bool GzSceneManager::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { this->dataPtr->OnRender(); } @@ -254,7 +254,7 @@ void GzSceneManagerPrivate::OnRender() this->renderUtil.SetScene(this->scene); - auto runners = ignition::gui::App()->findChildren(); + auto runners = gz::gui::App()->findChildren(); if (runners.empty() || runners[0] == nullptr) { ignerr << "Internal error: no GuiRunner found." << std::endl; @@ -270,4 +270,4 @@ void GzSceneManagerPrivate::OnRender() // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::GzSceneManager, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/scene_manager/GzSceneManager.hh b/src/gui/plugins/scene_manager/GzSceneManager.hh index c84f33322e..54f0cdb3ef 100644 --- a/src/gui/plugins/scene_manager/GzSceneManager.hh +++ b/src/gui/plugins/scene_manager/GzSceneManager.hh @@ -33,7 +33,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Updates a 3D scene based on information coming from the ECM. /// This plugin doesn't instantiate a new 3D scene. Instead, it relies on /// another plugin being loaded alongside it that will create and paint the - /// scene to the window, such as `ignition::gui::plugins::Scene3D`. + /// scene to the window, such as `gz::gui::plugins::Scene3D`. /// /// Only one GzSceneManager can be used at a time. class GzSceneManager : public GuiSystem diff --git a/src/gui/plugins/select_entities/SelectEntities.cc b/src/gui/plugins/select_entities/SelectEntities.cc index fb5ab946f6..8ae535f598 100644 --- a/src/gui/plugins/select_entities/SelectEntities.cc +++ b/src/gui/plugins/select_entities/SelectEntities.cc @@ -186,8 +186,8 @@ void SelectEntitiesPrivate::HandleEntitySelection() ignition::gazebo::gui::events::EntitiesSelected selectEvent( this->selectedEntities); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &selectEvent); } this->receivedSelectedEntities = false; @@ -375,8 +375,8 @@ void SelectEntitiesPrivate::SetSelectedEntity( this->HighlightNode(topLevelVisual); ignition::gazebo::gui::events::EntitiesSelected entitiesSelected( this->selectedEntities); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &entitiesSelected); } @@ -396,8 +396,8 @@ void SelectEntitiesPrivate::DeselectAllEntities() this->selectedEntitiesID.clear(); ignition::gazebo::gui::events::DeselectAllEntities deselectEvent(true); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &deselectEvent); } @@ -425,8 +425,8 @@ void SelectEntitiesPrivate::UpdateSelectedEntity( { ignition::gazebo::gui::events::EntitiesSelected selectEvent( this->selectedEntities); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &selectEvent); } } @@ -488,17 +488,17 @@ void SelectEntities::LoadConfig(const tinyxml2::XMLElement *) } done = true; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); } ///////////////////////////////////////////////// bool SelectEntities::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::LeftClickOnScene::kType) + if (_event->type() == gz::gui::events::LeftClickOnScene::kType) { - ignition::gui::events::LeftClickOnScene *_e = - static_cast(_event); + gz::gui::events::LeftClickOnScene *_e = + static_cast(_event); this->dataPtr->mouseEvent = _e->Mouse(); if (this->dataPtr->mouseEvent.Button() == common::MouseEvent::LEFT && @@ -514,7 +514,7 @@ bool SelectEntities::eventFilter(QObject *_obj, QEvent *_event) } } } - else if (_event->type() == ignition::gui::events::Render::kType) + else if (_event->type() == gz::gui::events::Render::kType) { this->dataPtr->Initialize(); this->dataPtr->HandleEntitySelection(); @@ -569,16 +569,16 @@ bool SelectEntities::eventFilter(QObject *_obj, QEvent *_event) this->dataPtr->selectedEntities.clear(); } else if (_event->type() == - ignition::gui::events::SpawnFromDescription::kType || - _event->type() == ignition::gui::events::SpawnFromPath::kType) + gz::gui::events::SpawnFromDescription::kType || + _event->type() == gz::gui::events::SpawnFromPath::kType) { this->dataPtr->isSpawning = true; this->dataPtr->mouseDirty = true; } - else if (_event->type() == ignition::gui::events::KeyReleaseOnScene::kType) + else if (_event->type() == gz::gui::events::KeyReleaseOnScene::kType) { - ignition::gui::events::KeyReleaseOnScene *_e = - static_cast(_event); + gz::gui::events::KeyReleaseOnScene *_e = + static_cast(_event); if (_e->Key().Key() == Qt::Key_Escape) { this->dataPtr->mouseDirty = true; @@ -612,4 +612,4 @@ bool SelectEntities::eventFilter(QObject *_obj, QEvent *_event) // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::gui::SelectEntities, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/select_entities/SelectEntities.hh b/src/gui/plugins/select_entities/SelectEntities.hh index 6643ab539e..ff50a3e21a 100644 --- a/src/gui/plugins/select_entities/SelectEntities.hh +++ b/src/gui/plugins/select_entities/SelectEntities.hh @@ -32,7 +32,7 @@ namespace gui /// \brief This plugin is in charge of selecting and deselecting the entities /// from the Scene3D and emit the corresponding events. - class SelectEntities : public ignition::gui::Plugin + class SelectEntities : public gz::gui::Plugin { Q_OBJECT diff --git a/src/gui/plugins/shapes/Shapes.cc b/src/gui/plugins/shapes/Shapes.cc index 37c006a613..057bbd17cb 100644 --- a/src/gui/plugins/shapes/Shapes.cc +++ b/src/gui/plugins/shapes/Shapes.cc @@ -73,9 +73,9 @@ void Shapes::OnMode(const QString &_mode) if (!modelSdfString.empty()) { - ignition::gui::events::SpawnFromDescription event(modelSdfString); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::SpawnFromDescription event(modelSdfString); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); } } diff --git a/src/gui/plugins/spawn/Spawn.cc b/src/gui/plugins/spawn/Spawn.cc index cc33737aa4..ebf435d5b8 100644 --- a/src/gui/plugins/spawn/Spawn.cc +++ b/src/gui/plugins/spawn/Spawn.cc @@ -154,7 +154,7 @@ using namespace gazebo; ///////////////////////////////////////////////// Spawn::Spawn() - : ignition::gui::Plugin(), + : gz::gui::Plugin(), dataPtr(std::make_unique()) { } @@ -184,8 +184,8 @@ void Spawn::LoadConfig(const tinyxml2::XMLElement *) if (!worldNames.empty()) this->dataPtr->worldName = worldNames[0].toStdString(); - ignition::gui::App()->findChild - ()->installEventFilter(this); + gz::gui::App()->findChild + ()->installEventFilter(this); } ///////////////////////////////////////////////// @@ -477,63 +477,63 @@ bool SpawnPrivate::GeneratePreview(const std::string &_name) //////////////////////////////////////////////// bool Spawn::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { this->dataPtr->OnRender(); } - else if (_event->type() == ignition::gui::events::LeftClickOnScene::kType) + else if (_event->type() == gz::gui::events::LeftClickOnScene::kType) { - ignition::gui::events::LeftClickOnScene *_e = - static_cast(_event); + gz::gui::events::LeftClickOnScene *_e = + static_cast(_event); this->dataPtr->mouseEvent = _e->Mouse(); if (this->dataPtr->generatePreview || this->dataPtr->isPlacing) this->dataPtr->mouseDirty = true; } - else if (_event->type() == ignition::gui::events::HoverOnScene::kType) + else if (_event->type() == gz::gui::events::HoverOnScene::kType) { - ignition::gui::events::HoverOnScene *_e = - static_cast(_event); + gz::gui::events::HoverOnScene *_e = + static_cast(_event); this->dataPtr->mouseHoverPos = _e->Mouse().Pos(); this->dataPtr->hoverDirty = true; } else if (_event->type() == - ignition::gui::events::SpawnFromDescription::kType) + gz::gui::events::SpawnFromDescription::kType) { - ignition::gui::events::SpawnFromDescription *_e = - static_cast(_event); + gz::gui::events::SpawnFromDescription *_e = + static_cast(_event); this->dataPtr->spawnSdfString = _e->Description(); this->dataPtr->generatePreview = true; } - else if (_event->type() == ignition::gui::events::SpawnFromPath::kType) + else if (_event->type() == gz::gui::events::SpawnFromPath::kType) { auto spawnPreviewPathEvent = - reinterpret_cast(_event); + reinterpret_cast(_event); this->dataPtr->spawnSdfPath = spawnPreviewPathEvent->FilePath(); this->dataPtr->generatePreview = true; } - else if (_event->type() == ignition::gui::events::SpawnCloneFromName::kType) + else if (_event->type() == gz::gui::events::SpawnCloneFromName::kType) { auto spawnCloneEvent = - reinterpret_cast(_event); + reinterpret_cast(_event); if (spawnCloneEvent) { this->dataPtr->spawnCloneName = spawnCloneEvent->Name(); this->dataPtr->generatePreview = true; } } - else if (_event->type() == ignition::gui::events::KeyReleaseOnScene::kType) + else if (_event->type() == gz::gui::events::KeyReleaseOnScene::kType) { - ignition::gui::events::KeyReleaseOnScene *_e = - static_cast(_event); + gz::gui::events::KeyReleaseOnScene *_e = + static_cast(_event); if (_e->Key().Key() == Qt::Key_Escape) { this->dataPtr->escapeReleased = true; } } - else if (_event->type() == ignition::gui::events::DropOnScene::kType) + else if (_event->type() == gz::gui::events::DropOnScene::kType) { auto dropOnSceneEvent = - reinterpret_cast(_event); + reinterpret_cast(_event); if (dropOnSceneEvent) { this->OnDropped(dropOnSceneEvent); @@ -544,7 +544,7 @@ bool Spawn::eventFilter(QObject *_obj, QEvent *_event) } ///////////////////////////////////////////////// -void Spawn::OnDropped(const ignition::gui::events::DropOnScene *_event) +void Spawn::OnDropped(const gz::gui::events::DropOnScene *_event) { if (nullptr == _event || nullptr == this->dataPtr->camera || nullptr == this->dataPtr->rayQuery) @@ -647,4 +647,4 @@ void Spawn::SetErrorPopupText(const QString &_errorTxt) // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::Spawn, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/spawn/Spawn.hh b/src/gui/plugins/spawn/Spawn.hh index 43e5844919..fc7bb5d621 100644 --- a/src/gui/plugins/spawn/Spawn.hh +++ b/src/gui/plugins/spawn/Spawn.hh @@ -31,7 +31,7 @@ namespace gazebo /// \brief Allows to spawn models and lights using the spawn gui events or /// drag and drop. - class Spawn : public ignition::gui::Plugin + class Spawn : public gz::gui::Plugin { Q_OBJECT @@ -54,7 +54,7 @@ namespace gazebo /// \brief Handle drop events. /// \param[in] _event Event with drop information. - public: void OnDropped(const ignition::gui::events::DropOnScene *_event); + public: void OnDropped(const gz::gui::events::DropOnScene *_event); /// \brief Get the text for the popup error message /// \return The error text diff --git a/src/gui/plugins/transform_control/TransformControl.cc b/src/gui/plugins/transform_control/TransformControl.cc index 5f51340eac..bb7e77bf58 100644 --- a/src/gui/plugins/transform_control/TransformControl.cc +++ b/src/gui/plugins/transform_control/TransformControl.cc @@ -289,8 +289,8 @@ void TransformControl::OnMode(const QString &_mode) gazebo::gui::events::TransformControlModeActive transformControlModeActive(this->dataPtr->transformMode); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &transformControlModeActive); this->dataPtr->mouseDirty = true; } @@ -350,7 +350,7 @@ void TransformControl::LoadGrid() ///////////////////////////////////////////////// bool TransformControl::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { // This event is called in Scene3d's RenderThread, so it's safe to make // rendering calls here @@ -381,31 +381,31 @@ bool TransformControl::eventFilter(QObject *_obj, QEvent *_event) this->dataPtr->selectedEntities.clear(); } } - else if (_event->type() == ignition::gui::events::LeftClickOnScene::kType) + else if (_event->type() == gz::gui::events::LeftClickOnScene::kType) { - ignition::gui::events::LeftClickOnScene *_e = - static_cast(_event); + gz::gui::events::LeftClickOnScene *_e = + static_cast(_event); this->dataPtr->mouseEvent = _e->Mouse(); this->dataPtr->mouseDirty = true; } - else if (_event->type() == ignition::gui::events::MousePressOnScene::kType) + else if (_event->type() == gz::gui::events::MousePressOnScene::kType) { auto event = - static_cast(_event); + static_cast(_event); this->dataPtr->mouseEvent = event->Mouse(); this->dataPtr->mouseDirty = true; } - else if (_event->type() == ignition::gui::events::DragOnScene::kType) + else if (_event->type() == gz::gui::events::DragOnScene::kType) { auto event = - static_cast(_event); + static_cast(_event); this->dataPtr->mouseEvent = event->Mouse(); this->dataPtr->mouseDirty = true; } - else if (_event->type() == ignition::gui::events::KeyPressOnScene::kType) + else if (_event->type() == gz::gui::events::KeyPressOnScene::kType) { - ignition::gui::events::KeyPressOnScene *_e = - static_cast(_event); + gz::gui::events::KeyPressOnScene *_e = + static_cast(_event); this->dataPtr->keyEvent = _e->Key(); if (this->dataPtr->keyEvent.Key() == Qt::Key_T) @@ -417,10 +417,10 @@ bool TransformControl::eventFilter(QObject *_obj, QEvent *_event) this->activateRotate(); } } - else if (_event->type() == ignition::gui::events::KeyReleaseOnScene::kType) + else if (_event->type() == gz::gui::events::KeyReleaseOnScene::kType) { - ignition::gui::events::KeyReleaseOnScene *_e = - static_cast(_event); + gz::gui::events::KeyReleaseOnScene *_e = + static_cast(_event); this->dataPtr->keyEvent = _e->Key(); if (this->dataPtr->keyEvent.Key() == Qt::Key_Escape) { @@ -580,9 +580,9 @@ void TransformControlPrivate::HandleTransform() this->HandleMouseEvents(); - ignition::gui::events::BlockOrbit blockOrbitEvent(this->blockOrbit); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::BlockOrbit blockOrbitEvent(this->blockOrbit); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &blockOrbitEvent); } @@ -677,7 +677,7 @@ void TransformControlPrivate::HandleMouseEvents() if (this->poseCmdService.empty()) { std::string worldName; - auto worldNames = ignition::gui::worldNames(); + auto worldNames = gz::gui::worldNames(); if (!worldNames.empty()) worldName = worldNames[0].toStdString(); diff --git a/src/gui/plugins/video_recorder/VideoRecorder.cc b/src/gui/plugins/video_recorder/VideoRecorder.cc index 061e008b84..ab38e977ae 100644 --- a/src/gui/plugins/video_recorder/VideoRecorder.cc +++ b/src/gui/plugins/video_recorder/VideoRecorder.cc @@ -360,8 +360,8 @@ void VideoRecorder::LoadConfig(const tinyxml2::XMLElement * _pluginElem) << "MinimalScene." << std::endl; } - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); } ///////////////////////////////////////////////// diff --git a/src/gui/plugins/view_angle/ViewAngle.cc b/src/gui/plugins/view_angle/ViewAngle.cc index f3471ea3de..5c68056e93 100644 --- a/src/gui/plugins/view_angle/ViewAngle.cc +++ b/src/gui/plugins/view_angle/ViewAngle.cc @@ -199,14 +199,14 @@ void ViewAngle::LoadConfig(const tinyxml2::XMLElement *_pluginElem) ignmsg << "Move to model service on [" << this->dataPtr->moveToModelService << "]" << std::endl; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); } ///////////////////////////////////////////////// bool ViewAngle::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { this->dataPtr->OnRender(); diff --git a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc index 34305ecc5a..22938db16d 100644 --- a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc +++ b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc @@ -2854,14 +2854,14 @@ void VisualizationCapabilities::LoadConfig(const tinyxml2::XMLElement *) ignmsg << "View frames service on [" << this->dataPtr->viewFramesService << "]" << std::endl; - ignition::gui::App()->findChild - ()->installEventFilter(this); + gz::gui::App()->findChild + ()->installEventFilter(this); } //////////////////////////////////////////////// bool VisualizationCapabilities::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { this->dataPtr->OnRender(); } @@ -2871,4 +2871,4 @@ bool VisualizationCapabilities::eventFilter(QObject *_obj, QEvent *_event) // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::VisualizationCapabilities, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/visualize_contacts/VisualizeContacts.cc b/src/gui/plugins/visualize_contacts/VisualizeContacts.cc index 58b4339c4a..e7ddbc2833 100644 --- a/src/gui/plugins/visualize_contacts/VisualizeContacts.cc +++ b/src/gui/plugins/visualize_contacts/VisualizeContacts.cc @@ -311,4 +311,4 @@ void VisualizeContacts::UpdatePeriod(double _period) // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::VisualizeContacts, - ignition::gui::Plugin) + gz::gui::Plugin) diff --git a/src/gui/plugins/visualize_lidar/VisualizeLidar.cc b/src/gui/plugins/visualize_lidar/VisualizeLidar.cc index 1a1a0ea6a7..f76ad7d3cc 100644 --- a/src/gui/plugins/visualize_lidar/VisualizeLidar.cc +++ b/src/gui/plugins/visualize_lidar/VisualizeLidar.cc @@ -197,8 +197,8 @@ void VisualizeLidar::LoadLidar() scene->DestroyVisual(this->dataPtr->lidar); - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->removeEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->removeEventFilter(this); } else { @@ -214,14 +214,14 @@ void VisualizeLidar::LoadConfig(const tinyxml2::XMLElement *) if (this->title.empty()) this->title = "Visualize lidar"; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); } ///////////////////////////////////////////////// bool VisualizeLidar::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { // This event is called in Scene3d's RenderThread, so it's safe to make // rendering calls here @@ -526,4 +526,4 @@ QString VisualizeLidar::MinRange() const // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::VisualizeLidar, - ignition::gui::Plugin) + gz::gui::Plugin) From e79972b01f360581b3030aa4e10738fb11bd86bd Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 21 Jun 2023 05:07:30 -0700 Subject: [PATCH 11/31] Missing files Signed-off-by: Nate Koenig --- include/gz/sim/config.hh.in | 44 +++++++++++++++++++++++++++ include/gz/sim/playback_server.config | 14 +++++++++ include/gz/sim/server.config | 19 ++++++++++++ test/worlds/joints_in_world.sdf | 44 +++++++++++++++++++++++++++ 4 files changed, 121 insertions(+) create mode 100644 include/gz/sim/config.hh.in create mode 100644 include/gz/sim/playback_server.config create mode 100644 include/gz/sim/server.config create mode 100644 test/worlds/joints_in_world.sdf diff --git a/include/gz/sim/config.hh.in b/include/gz/sim/config.hh.in new file mode 100644 index 0000000000..894bd0d754 --- /dev/null +++ b/include/gz/sim/config.hh.in @@ -0,0 +1,44 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +/* Config.hh. Generated by CMake for @PROJECT_NAME_NO_VERSION@. */ + +#ifndef GZ_SIM__CONFIG_HH_ +#define GZ_SIM__CONFIG_HH_ + +/* Version number */ +#define GZ_SIM_MAJOR_VERSION ${PROJECT_VERSION_MAJOR} +#define GZ_SIM_MINOR_VERSION ${PROJECT_VERSION_MINOR} +#define GZ_SIM_PATCH_VERSION ${PROJECT_VERSION_PATCH} + +#define GZ_SIM_VERSION "${PROJECT_VERSION}" +#define GZ_SIM_VERSION_FULL "${PROJECT_VERSION_FULL}" +#define GZ_SIM_MAJOR_VERSION_STR "${PROJECT_VERSION_MAJOR}" + +#define GZ_SIM_VERSION_NAMESPACE v${PROJECT_VERSION_MAJOR} + +#define GZ_SIM_VERSION_HEADER "Gazebo Sim, version ${PROJECT_VERSION_FULL}\nCopyright (C) 2018 Open Source Robotics Foundation.\nReleased under the Apache 2.0 License.\n\n" + +#define GZ_SIM_GUI_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}/gui" +#define GZ_SIM_SYSTEM_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}/systems" +#define GZ_SIM_SERVER_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}" +#define GZ_SIM_PLUGIN_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins" +#define GZ_SIM_GUI_PLUGIN_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins/gui" +#define GZ_SIM_WORLD_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}/worlds" +#define GZ_DISTRIBUTION "${GZ_DISTRIBUTION}" + +#endif diff --git a/include/gz/sim/playback_server.config b/include/gz/sim/playback_server.config new file mode 100644 index 0000000000..dd8e5ac91f --- /dev/null +++ b/include/gz/sim/playback_server.config @@ -0,0 +1,14 @@ + + + + + + + + diff --git a/include/gz/sim/server.config b/include/gz/sim/server.config new file mode 100644 index 0000000000..99029de3ea --- /dev/null +++ b/include/gz/sim/server.config @@ -0,0 +1,19 @@ + + + + + + + + + + diff --git a/test/worlds/joints_in_world.sdf b/test/worlds/joints_in_world.sdf new file mode 100644 index 0000000000..d838bbecb4 --- /dev/null +++ b/test/worlds/joints_in_world.sdf @@ -0,0 +1,44 @@ + + + + + world + m1 + + + + + + + + 0.5 + + + + + + + + + m1 + m2 + + 0 1 0 + + + + + 2 0 0 0 0 0 + + + + + 0.5 + + + + + + + + From b8a8a18d888ec4a03cba5386cdab0f832970ce9e Mon Sep 17 00:00:00 2001 From: shameekganguly Date: Mon, 3 Jul 2023 02:34:37 -0700 Subject: [PATCH 12/31] Several minor fixes (#2027) Signed-off-by: Shameek Ganguly --- src/ServerConfig.cc | 5 +++- src/SystemLoader_TEST.cc | 5 ++-- .../component_inspector/ComponentInspector.cc | 18 ++++++------- src/rendering/RenderUtil.cc | 2 +- src/rendering/SceneManager.cc | 16 ++++++------ .../battery_plugin/LinearBatteryPlugin.cc | 6 ++--- src/systems/buoyancy/Buoyancy.cc | 2 +- .../environment_preload/EnvironmentPreload.cc | 2 +- src/systems/hydrodynamics/Hydrodynamics.cc | 4 +-- .../MulticopterVelocityControl.hh | 3 +++ .../performer_detector/PerformerDetector.hh | 1 + src/systems/physics/Physics.cc | 3 +-- src/systems/sensors/Sensors.cc | 2 +- src/systems/thruster/Thruster.cc | 16 ++++++------ .../triggered_publisher/TriggeredPublisher.cc | 26 +++++++++---------- test/integration/log_system.cc | 2 +- test/test_config.hh.in | 1 + tutorials/battery.md | 6 ++--- 18 files changed, 63 insertions(+), 57 deletions(-) diff --git a/src/ServerConfig.cc b/src/ServerConfig.cc index b7e79b0cde..b3dd1b12ef 100644 --- a/src/ServerConfig.cc +++ b/src/ServerConfig.cc @@ -265,7 +265,8 @@ class gz::sim::ServerConfigPrivate networkSecondaries(_cfg->networkSecondaries), seed(_cfg->seed), logRecordTopics(_cfg->logRecordTopics), - isHeadlessRendering(_cfg->isHeadlessRendering) { } + isHeadlessRendering(_cfg->isHeadlessRendering), + source(_cfg->source){ } // \brief The SDF file that the server should load public: std::string sdfFile = ""; @@ -811,6 +812,7 @@ ServerConfig::SourceType ServerConfig::Source() const } ///////////////////////////////////////////////// +namespace { void copyElement(sdf::ElementPtr _sdf, const tinyxml2::XMLElement *_xml) { _sdf->SetName(_xml->Value()); @@ -917,6 +919,7 @@ parsePluginsFromDoc(const tinyxml2::XMLDocument &_doc) } return ret; } +} // namespace ///////////////////////////////////////////////// std::list diff --git a/src/SystemLoader_TEST.cc b/src/SystemLoader_TEST.cc index b654924f34..4709af5fd8 100644 --- a/src/SystemLoader_TEST.cc +++ b/src/SystemLoader_TEST.cc @@ -97,9 +97,8 @@ TEST(SystemLoader, PluginPaths) for (const auto &s : paths) { // the returned path string may not be exact match due to extra '/' - // appended at the end of the string. So use absPath to generate - // a path string that matches the format returned by joinPaths - if (common::absPath(s) == testBuildPath) + // appended at the end of the string. So use absPath to compare paths + if (common::absPath(s) == common::absPath(testBuildPath)) { hasPath = true; break; diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index ad261fb93f..cd5f0eadc3 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -1215,7 +1215,7 @@ void ComponentInspector::QuerySystems() "/system/info"}; if (!this->dataPtr->node.Request(service, req, timeout, res, result)) { - ignerr << "Unable to query available systems." << std::endl; + gzerr << "Unable to query available systems." << std::endl; return; } @@ -1225,8 +1225,8 @@ void ComponentInspector::QuerySystems() { if (plugin.filename().empty()) { - ignerr << "Received empty plugin name. This shouldn't happen." - << std::endl; + gzerr << "Received empty plugin name. This shouldn't happen." + << std::endl; continue; } @@ -1273,7 +1273,7 @@ void ComponentInspector::OnAddSystem(const QString &_name, auto it = this->dataPtr->systemMap.find(filenameStr); if (it == this->dataPtr->systemMap.end()) { - ignerr << "Internal error: failed to find [" << filenameStr + gzerr << "Internal error: failed to find [" << filenameStr << "] in system map." << std::endl; return; } @@ -1296,11 +1296,11 @@ void ComponentInspector::OnAddSystem(const QString &_name, "/entity/system/add"}; if (!this->dataPtr->node.Request(service, req, timeout, res, result)) { - ignerr << "Error adding new system to entity: " - << this->dataPtr->entity << "\n" - << "Name: " << name << "\n" - << "Filename: " << filename << "\n" - << "Inner XML: " << innerxml << std::endl; + gzerr << "Error adding new system to entity: " + << this->dataPtr->entity << "\n" + << "Name: " << name << "\n" + << "Filename: " << filename << "\n" + << "Inner XML: " << innerxml << std::endl; } } diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 3c5e3da2d3..e86c31c117 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -1266,7 +1266,7 @@ void RenderUtil::Update() } else { - ignerr << "Failed to create light" << std::endl; + gzerr << "Failed to create light" << std::endl; } } diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index 55d10e9534..f1f758e8e9 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -1191,7 +1191,7 @@ rendering::LightPtr SceneManager::CreateLight(Entity _id, if (this->HasEntity(_id)) { - ignerr << "Light with Id: [" << _id << "] can not be create there is " + gzerr << "Light with Id: [" << _id << "] can not be create there is " "another entity with the same entity number" << std::endl; return nullptr; } @@ -2376,8 +2376,8 @@ SceneManager::LoadAnimations(const sdf::Actor &_actor) { if (!meshSkel->AddBvhAnimation(animFilename, animScale)) { - ignerr << "Bvh animation in file " << animFilename - << " failed to load during actor creation" << std::endl; + gzerr << "Bvh animation in file " << animFilename + << " failed to load during actor creation" << std::endl; continue; } } @@ -2473,8 +2473,8 @@ SceneManagerPrivate::LoadTrajectories(const sdf::Actor &_actor, const sdf::Trajectory *trajSdf = _actor.TrajectoryByIndex(i); if (nullptr == trajSdf) { - ignerr << "Null trajectory SDF for [" << _actor.Name() << "]" - << std::endl; + gzerr << "Null trajectory SDF for [" << _actor.Name() << "]" + << std::endl; continue; } common::TrajectoryInfo trajInfo; @@ -2517,9 +2517,9 @@ SceneManagerPrivate::LoadTrajectories(const sdf::Actor &_actor, } else { - ignwarn << "Animation has no x displacement. " - << "Ignoring for the animation in '" - << animation->Filename() << "'." << std::endl; + gzwarn << "Animation has no x displacement. " + << "Ignoring for the animation in '" + << animation->Filename() << "'." << std::endl; } animInterpolateCheck.insert(animation->Filename()); } diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.cc b/src/systems/battery_plugin/LinearBatteryPlugin.cc index 8f7cc41eb1..7dcf38bc3f 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.cc +++ b/src/systems/battery_plugin/LinearBatteryPlugin.cc @@ -394,8 +394,8 @@ void LinearBatteryPlugin::Configure(const Entity &_entity, std::bind(&LinearBatteryPluginPrivate::OnBatteryStopDrainingMsg, this->dataPtr.get(), std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); - ignmsg << "LinearBatteryPlugin subscribes to stop power draining topic [" - << topic << "]." << std::endl; + gzmsg << "LinearBatteryPlugin subscribes to stop power draining topic [" + << topic << "]." << std::endl; sdfElem = sdfElem->GetNextElement("power_draining_topic"); } } @@ -498,7 +498,7 @@ void LinearBatteryPlugin::PreUpdate( bool success = this->dataPtr->battery->SetPowerLoad( this->dataPtr->consumerId, total_power_load); if (!success) - ignerr << "Failed to set consumer power load." << std::endl; + gzerr << "Failed to set consumer power load." << std::endl; // Start draining the battery if the robot has started moving if (!this->dataPtr->startDraining) diff --git a/src/systems/buoyancy/Buoyancy.cc b/src/systems/buoyancy/Buoyancy.cc index a2c21b9c5a..5bd0ae54b4 100644 --- a/src/systems/buoyancy/Buoyancy.cc +++ b/src/systems/buoyancy/Buoyancy.cc @@ -643,7 +643,7 @@ void Buoyancy::PostUpdate( bool Buoyancy::IsEnabled(Entity _entity, const EntityComponentManager &_ecm) const { - return this->IsEnabled(_entity, _ecm); + return this->dataPtr->IsEnabled(_entity, _ecm); } GZ_ADD_PLUGIN(Buoyancy, diff --git a/src/systems/environment_preload/EnvironmentPreload.cc b/src/systems/environment_preload/EnvironmentPreload.cc index fe5b57f940..5c678aa2db 100644 --- a/src/systems/environment_preload/EnvironmentPreload.cc +++ b/src/systems/environment_preload/EnvironmentPreload.cc @@ -134,7 +134,7 @@ void EnvironmentPreload::PreUpdate( } else if (unitName != "radians") { - ignerr << "Unrecognized unit " << unitName << "\n"; + gzerr << "Unrecognized unit " << unitName << "\n"; } } } diff --git a/src/systems/hydrodynamics/Hydrodynamics.cc b/src/systems/hydrodynamics/Hydrodynamics.cc index ba54d315eb..e657ad8bb5 100644 --- a/src/systems/hydrodynamics/Hydrodynamics.cc +++ b/src/systems/hydrodynamics/Hydrodynamics.cc @@ -295,7 +295,7 @@ void Hydrodynamics::Configure( { if (_sdf->HasElement("waterDensity")) { - ignwarn << + gzwarn << " parameter is deprecated and will be removed Ignition G.\n" << "\tPlease update your SDF to use instead."; } @@ -342,7 +342,7 @@ void Hydrodynamics::Configure( if (warnBehaviourChange) { - ignwarn << "You are using parameters that may cause instabilities " + gzwarn << "You are using parameters that may cause instabilities " << "in your simulation. If your simulation crashes we recommend " << "renaming -> and likewise for other axis " << "for more information see:" << std::endl diff --git a/src/systems/multicopter_control/MulticopterVelocityControl.hh b/src/systems/multicopter_control/MulticopterVelocityControl.hh index 2c1f4b37af..c414d1ec53 100644 --- a/src/systems/multicopter_control/MulticopterVelocityControl.hh +++ b/src/systems/multicopter_control/MulticopterVelocityControl.hh @@ -21,6 +21,9 @@ #include #include +#include +#include +#include #include #include diff --git a/src/systems/performer_detector/PerformerDetector.hh b/src/systems/performer_detector/PerformerDetector.hh index 84c8e12d9c..bbdb9e3ddf 100644 --- a/src/systems/performer_detector/PerformerDetector.hh +++ b/src/systems/performer_detector/PerformerDetector.hh @@ -23,6 +23,7 @@ #include #include +#include #include #include "gz/sim/Model.hh" diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 8fa201a12a..c70e2103db 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -3763,8 +3763,7 @@ void PhysicsPrivate::UpdateCollisions(EntityComponentManager &_ecm) // Note that we are temporarily storing pointers to elements in this // ("allContacts") container. Thus, we must make sure it doesn't get destroyed // until the end of this function. - auto allContacts = - std::move(worldCollisionFeature->GetContactsFromLastStep()); + auto allContacts = worldCollisionFeature->GetContactsFromLastStep(); for (const auto &contactComposite : allContacts) { diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc index 4790345300..388fcbf953 100644 --- a/src/systems/sensors/Sensors.cc +++ b/src/systems/sensors/Sensors.cc @@ -621,7 +621,7 @@ void Sensors::Update(const UpdateInfo &_info, _ecm.HasComponentType(components::WideAngleCamera::typeId))) { std::unique_lock lock(this->dataPtr->renderMutex); - igndbg << "Initialization needed" << std::endl; + gzdbg << "Initialization needed" << std::endl; this->dataPtr->renderUtil.Init(); this->dataPtr->nextUpdateTime = _info.simTime; } diff --git a/src/systems/thruster/Thruster.cc b/src/systems/thruster/Thruster.cc index c8a4492210..30b1a3e2b1 100644 --- a/src/systems/thruster/Thruster.cc +++ b/src/systems/thruster/Thruster.cc @@ -451,7 +451,7 @@ void Thruster::Configure( { if (!_sdf->HasElement("battery_name")) { - ignerr << "Specified a but missing ." + gzerr << "Specified a but missing ." "Specify a battery name so the power load can be assigned to it." << std::endl; } @@ -586,17 +586,17 @@ void Thruster::PreUpdate( }); if (numBatteriesWithName == 0) { - ignerr << "Can't assign battery consumption to battery: [" - << this->dataPtr->batteryName << "]. No batteries" - "were found with the given name." << std::endl; + gzerr << "Can't assign battery consumption to battery: [" + << this->dataPtr->batteryName << "]. No batteries" + "were found with the given name." << std::endl; return; } if (numBatteriesWithName > 1) { - ignerr << "More than one battery found with name: [" - << this->dataPtr->batteryName << "]. Please make" - "sure battery names are unique within the system." - << std::endl; + gzerr << "More than one battery found with name: [" + << this->dataPtr->batteryName << "]. Please make" + "sure battery names are unique within the system." + << std::endl; return; } diff --git a/src/systems/triggered_publisher/TriggeredPublisher.cc b/src/systems/triggered_publisher/TriggeredPublisher.cc index 87d0add654..80c92981c2 100644 --- a/src/systems/triggered_publisher/TriggeredPublisher.cc +++ b/src/systems/triggered_publisher/TriggeredPublisher.cc @@ -605,31 +605,31 @@ void TriggeredPublisher::Configure(const Entity &, serviceInfo.srvName = serviceElem->Get("name"); if (serviceInfo.srvName.empty()) { - ignerr << "Service name cannot be empty\n"; + gzerr << "Service name cannot be empty\n"; return; } serviceInfo.reqType = serviceElem->Get("reqType"); if (serviceInfo.reqType.empty()) { - ignerr << "Service request type cannot be empty\n"; + gzerr << "Service request type cannot be empty\n"; return; } serviceInfo.repType = serviceElem->Get("repType"); if (serviceInfo.repType.empty()) { - ignerr << "Service reply type cannot be empty\n"; + gzerr << "Service reply type cannot be empty\n"; return; } serviceInfo.reqMsg = serviceElem->Get("reqMsg"); if (serviceInfo.reqMsg.empty()) { - ignerr << "Service request message cannot be empty\n"; + gzerr << "Service request message cannot be empty\n"; return; } std::string timeoutInfo = serviceElem->Get("timeout"); if (timeoutInfo.empty()) { - ignerr << "Timeout value cannot be empty\n"; + gzerr << "Timeout value cannot be empty\n"; return; } @@ -639,7 +639,7 @@ void TriggeredPublisher::Configure(const Entity &, } if (!sdfClone->HasElement("service") && !sdfClone->HasElement("output")) { - ignerr << "No output and service specified. Make sure to specify at least" + gzerr << "No output and service specified. Make sure to specify at least" "one of them." << std::endl; return; } @@ -715,16 +715,16 @@ void TriggeredPublisher::CallService(std::size_t pendingSrv) auto req = msgs::Factory::New(serviceInfo.reqType, serviceInfo.reqMsg); if (!req) { - ignerr << "Unable to create request for type [" - << serviceInfo.reqType << "].\n"; + gzerr << "Unable to create request for type [" + << serviceInfo.reqType << "].\n"; return; } auto rep = msgs::Factory::New(serviceInfo.repType); if (!rep) { - ignerr << "Unable to create response for type [" - << serviceInfo.repType << "].\n"; + gzerr << "Unable to create response for type [" + << serviceInfo.repType << "].\n"; return; } @@ -734,16 +734,16 @@ void TriggeredPublisher::CallService(std::size_t pendingSrv) { if (!result) { - ignerr << "Service call [" << serviceInfo.srvName << "] failed\n"; + gzerr << "Service call [" << serviceInfo.srvName << "] failed\n"; } else { - ignmsg << "Service call [" << serviceInfo.srvName << "] succeeded\n"; + gzmsg << "Service call [" << serviceInfo.srvName << "] succeeded\n"; } } else { - ignerr << "Service call [" << serviceInfo.srvName << "] timed out\n"; + gzerr << "Service call [" << serviceInfo.srvName << "] timed out\n"; } } } diff --git a/test/integration/log_system.cc b/test/integration/log_system.cc index 54032c013f..fa3ba96734 100644 --- a/test/integration/log_system.cc +++ b/test/integration/log_system.cc @@ -1669,7 +1669,7 @@ TEST_F(LogSystemTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(RecordPeriod)) #ifndef __APPLE__ // Log from command line { - // Command line triggers ign.cc, which handles initializing ignLogDirectory + // Command line triggers gz.cc, which handles initializing gzlogDirectory std::string cmd = kGzCommand + " -r -v 4 --iterations " + std::to_string(numIterations) + " " + "--record-period 0.002 " diff --git a/test/test_config.hh.in b/test/test_config.hh.in index 4ccac6b3be..4681208058 100644 --- a/test/test_config.hh.in +++ b/test/test_config.hh.in @@ -18,6 +18,7 @@ #define GZ_SIM_TEST_CONFIG_HH_ #include +#include #include #define PROJECT_SOURCE_PATH "${PROJECT_SOURCE_DIR}" diff --git a/tutorials/battery.md b/tutorials/battery.md index fea877ca5e..c2156cbd0f 100644 --- a/tutorials/battery.md +++ b/tutorials/battery.md @@ -187,7 +187,7 @@ At the configure step the parameters are read and saved: { if (!_sdf->HasElement("battery_name")) { - ignerr << "Specified a but missing ." + gzerr << "Specified a but missing ." "Specify a battery name so the power load can be assigned to it." << std::endl; } @@ -246,14 +246,14 @@ are found with the specified name. ``` if (numBatteriesWithName == 0) { - ignerr << "Can't assign battery consumption to battery: [" + gzerr << "Can't assign battery consumption to battery: [" << this->dataPtr->batteryName << "]. No batteries" "were found with the given name." << std::endl; return; } if (numBatteriesWithName > 1) { - ignerr << "More than one battery found with name: [" + gzerr << "More than one battery found with name: [" << this->dataPtr->batteryName << "]. Please make" "sure battery names are unique within the system." << std::endl; From 171a6da203034bbe5db17acd0241c1229d51fee0 Mon Sep 17 00:00:00 2001 From: Silvio Traversaro Date: Fri, 7 Jul 2023 19:38:13 +0200 Subject: [PATCH 13/31] Add optional binary relocatability (#1968) * Add optional binary relocatability Signed-off-by: Silvio Traversaro * Fix GZ_SIM_WORLD_RELATIVE_INSTALL_DIR definition Signed-off-by: Silvio Traversaro --------- Signed-off-by: Silvio Traversaro --- include/gz/sim/InstallationDirectories.hh | 57 ++++++++++++++++ include/gz/sim/config.hh.in | 12 ++-- src/CMakeLists.txt | 18 +++++ src/InstallationDirectories.cc | 67 +++++++++++++++++++ src/ServerConfig.cc | 3 +- src/SystemLoader.cc | 5 +- src/Util.cc | 3 +- src/gui/CMakeLists.txt | 2 + src/gui/Gui.cc | 7 +- src/gui/QuickStartHandler.cc | 5 +- src/gui/QuickStartHandler.hh | 4 +- src/gui/plugins/CMakeLists.txt | 4 +- src/gz.cc | 4 +- .../CMakeLists.txt | 2 + .../CMakeLists.txt | 2 + src/systems/physics/CMakeLists.txt | 2 + test/integration/CMakeLists.txt | 2 + test/performance/CMakeLists.txt | 2 + test/regression/CMakeLists.txt | 2 + 19 files changed, 186 insertions(+), 17 deletions(-) create mode 100644 include/gz/sim/InstallationDirectories.hh create mode 100644 src/InstallationDirectories.cc diff --git a/include/gz/sim/InstallationDirectories.hh b/include/gz/sim/InstallationDirectories.hh new file mode 100644 index 0000000000..08e3b2b29e --- /dev/null +++ b/include/gz/sim/InstallationDirectories.hh @@ -0,0 +1,57 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#ifndef GZ_SIM_INSTALLATION_DIRECTORIES_HH_ +#define GZ_SIM_INSTALLATION_DIRECTORIES_HH_ + +#include + +#include +#include + +namespace gz +{ + namespace sim + { + inline namespace GZ_SIM_VERSION_NAMESPACE { + + /// \brief getInstallPrefix return the install prefix of the library + /// i.e. CMAKE_INSTALL_PREFIX unless the library has been moved + GZ_SIM_VISIBLE std::string getInstallPrefix(); + + /// \brief getGUIConfigPath return the GUI config path + GZ_SIM_VISIBLE std::string getGUIConfigPath(); + + /// \brief getSystemConfigPath return the system config path + GZ_SIM_VISIBLE std::string getSystemConfigPath(); + + /// \brief getServerConfigPath return the server config path + GZ_SIM_VISIBLE std::string getServerConfigPath(); + + /// \brief getPluginInstallDir return the plugin install dir + GZ_SIM_VISIBLE std::string getPluginInstallDir(); + + /// \brief getGUIPluginInstallDir return the GUI plugin install dir + GZ_SIM_VISIBLE std::string getGUIPluginInstallDir(); + + /// \brief getWorldInstallDir return the world install dir + GZ_SIM_VISIBLE std::string getWorldInstallDir(); + } + } +} + +#endif diff --git a/include/gz/sim/config.hh.in b/include/gz/sim/config.hh.in index 894bd0d754..a13b62aa1e 100644 --- a/include/gz/sim/config.hh.in +++ b/include/gz/sim/config.hh.in @@ -33,12 +33,12 @@ #define GZ_SIM_VERSION_HEADER "Gazebo Sim, version ${PROJECT_VERSION_FULL}\nCopyright (C) 2018 Open Source Robotics Foundation.\nReleased under the Apache 2.0 License.\n\n" -#define GZ_SIM_GUI_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}/gui" -#define GZ_SIM_SYSTEM_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}/systems" -#define GZ_SIM_SERVER_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}" -#define GZ_SIM_PLUGIN_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins" -#define GZ_SIM_GUI_PLUGIN_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins/gui" -#define GZ_SIM_WORLD_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}/worlds" +#define GZ_SIM_GUI_CONFIG_PATH _Pragma ("GCC warning \"'GZ_SIM_GUI_CONFIG_PATH' macro is deprecated, use gz::sim::getGUIConfigPath() function instead. \"") "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}/gui" +#define GZ_SIM_SYSTEM_CONFIG_PATH _Pragma ("GCC warning \"'GZ_SIM_SYSTEM_CONFIG_PATH' macro is deprecated, use gz::sim::getSystemConfigPath() function instead. \"") "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}/systems" +#define GZ_SIM_SERVER_CONFIG_PATH _Pragma ("GCC warning \"'GZ_SIM_SERVER_CONFIG_PATH' macro is deprecated, use gz::sim::getServerConfigPath() function instead. \"") "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}" +#define GZ_SIM_PLUGIN_INSTALL_DIR _Pragma ("GCC warning \"'GZ_SIM_PLUGIN_INSTALL_DIR' macro is deprecated, use gz::sim::getPluginInstallDir() function instead. \"") "${CMAKE_INSTALL_PREFIX}/${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins" +#define GZ_SIM_GUI_PLUGIN_INSTALL_DIR _Pragma ("GCC warning \"'GZ_SIM_GUI_PLUGIN_INSTALL_DIR' macro is deprecated, use gz::sim::getGUIPluginInstallDir() function instead. \"") "${CMAKE_INSTALL_PREFIX}/${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins/gui" +#define GZ_SIM_WORLD_INSTALL_DIR _Pragma ("GCC warning \"'GZ_SIM_WORLD_INSTALL_DIR' macro is deprecated, use gz::sim::getWorldInstallDir() function instead. \"") "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}/worlds" #define GZ_DISTRIBUTION "${GZ_DISTRIBUTION}" #endif diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 7f35532ce1..fe188f1c48 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -54,6 +54,7 @@ set (sources ComponentFactory.cc EntityComponentManager.cc EntityComponentManagerDiff.cc + InstallationDirectories.cc Joint.cc LevelManager.cc Light.cc @@ -168,6 +169,21 @@ target_link_libraries(${gz_lib_target} # Create the library target gz_create_core_library(SOURCES ${sources} CXX_STANDARD 17) +gz_add_get_install_prefix_impl(GET_INSTALL_PREFIX_FUNCTION gz::sim::getInstallPrefix + GET_INSTALL_PREFIX_HEADER gz/sim/InstallationDirectories.hh + OVERRIDE_INSTALL_PREFIX_ENV_VARIABLE GZ_SIM_INSTALL_PREFIX) + +set_property( + SOURCE InstallationDirectories.cc + PROPERTY COMPILE_DEFINITIONS + GZ_SIM_GUI_CONFIG_RELATIVE_PATH="${GZ_DATA_INSTALL_DIR}/gui" + GZ_SIM_SYSTEM_CONFIG_RELATIVE_PATH="${GZ_DATA_INSTALL_DIR}/systems" + GZ_SIM_SERVER_CONFIG_RELATIVE_PATH="${GZ_DATA_INSTALL_DIR}" + GZ_SIM_PLUGIN_RELATIVE_INSTALL_DIR="${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins" + GZ_SIM_GUI_PLUGIN_RELATIVE_INSTALL_DIR="${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins/gui" + GZ_SIM_WORLD_RELATIVE_INSTALL_DIR="${GZ_DATA_INSTALL_DIR}/worlds" +) + target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME} PUBLIC gz-math${GZ_MATH_VER} @@ -213,6 +229,8 @@ gz_build_tests(TYPE UNIT ${PROJECT_LIBRARY_TARGET_NAME} ${EXTRA_TEST_LIB_DEPS} gz-sim${PROJECT_VERSION_MAJOR} + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} ) # Some server unit tests require rendering. diff --git a/src/InstallationDirectories.cc b/src/InstallationDirectories.cc new file mode 100644 index 0000000000..2aa64e334d --- /dev/null +++ b/src/InstallationDirectories.cc @@ -0,0 +1,67 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include + +#include + +namespace gz +{ +namespace sim +{ +inline namespace GZ_SIM_VERSION_NAMESPACE { + +std::string getGUIConfigPath() +{ + return gz::common::joinPaths( + getInstallPrefix(), GZ_SIM_GUI_CONFIG_RELATIVE_PATH); +} + +std::string getSystemConfigPath() +{ + return gz::common::joinPaths( + getInstallPrefix(), GZ_SIM_SYSTEM_CONFIG_RELATIVE_PATH); +} + +std::string getServerConfigPath() +{ + return gz::common::joinPaths( + getInstallPrefix(), GZ_SIM_SERVER_CONFIG_RELATIVE_PATH); +} + +std::string getPluginInstallDir() +{ + return gz::common::joinPaths( + getInstallPrefix(), GZ_SIM_PLUGIN_RELATIVE_INSTALL_DIR); +} + +std::string getGUIPluginInstallDir() +{ + return gz::common::joinPaths( + getInstallPrefix(), GZ_SIM_GUI_PLUGIN_RELATIVE_INSTALL_DIR); +} + +std::string getWorldInstallDir() +{ + return gz::common::joinPaths( + getInstallPrefix(), GZ_SIM_WORLD_RELATIVE_INSTALL_DIR); +} + +} +} +} diff --git a/src/ServerConfig.cc b/src/ServerConfig.cc index b3dd1b12ef..59af90581b 100644 --- a/src/ServerConfig.cc +++ b/src/ServerConfig.cc @@ -25,6 +25,7 @@ #include #include +#include "gz/sim/InstallationDirectories.hh" #include "gz/sim/Util.hh" using namespace gz; @@ -1016,7 +1017,7 @@ sim::loadPluginInfo(bool _isPlayback) if (!common::exists(defaultConfig)) { auto installedConfig = common::joinPaths( - GZ_SIM_SERVER_CONFIG_PATH, + gz::sim::getServerConfigPath(), configFilename); if (!common::createDirectories(defaultConfigDir)) diff --git a/src/SystemLoader.cc b/src/SystemLoader.cc index 90d86748e2..d68e8d4819 100644 --- a/src/SystemLoader.cc +++ b/src/SystemLoader.cc @@ -32,6 +32,7 @@ #include +#include "gz/sim/InstallationDirectories.hh" #include using namespace gz::sim; @@ -54,12 +55,12 @@ class gz::sim::SystemLoaderPrivate common::env(GZ_HOMEDIR, homePath); systemPaths.AddPluginPaths(common::joinPaths( homePath, ".gz", "sim", "plugins")); - systemPaths.AddPluginPaths(GZ_SIM_PLUGIN_INSTALL_DIR); + systemPaths.AddPluginPaths(gz::sim::getPluginInstallDir()); // TODO(CH3): Deprecated. Remove on tock. systemPaths.AddPluginPaths(homePath + "/.ignition/gazebo/plugins"); - systemPaths.AddPluginPaths(GZ_SIM_PLUGIN_INSTALL_DIR); + systemPaths.AddPluginPaths(gz::sim::getPluginInstallDir()); return systemPaths.PluginPaths(); } diff --git a/src/Util.cc b/src/Util.cc index 552c68b2e1..db9918272f 100644 --- a/src/Util.cc +++ b/src/Util.cc @@ -49,6 +49,7 @@ #include "gz/sim/components/World.hh" #include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/InstallationDirectories.hh" #include "gz/sim/Util.hh" namespace gz @@ -829,7 +830,7 @@ std::string resolveSdfWorldFile(const std::string &_sdfFile, systemPaths.SetFilePathEnv(kResourcePathEnv); // Worlds installed with gz-sim - systemPaths.AddFilePaths(GZ_SIM_WORLD_INSTALL_DIR); + systemPaths.AddFilePaths(gz::sim::getWorldInstallDir()); filePath = systemPaths.FindFile(_sdfFile); } diff --git a/src/gui/CMakeLists.txt b/src/gui/CMakeLists.txt index 0f774b50f2..472eba232d 100644 --- a/src/gui/CMakeLists.txt +++ b/src/gui/CMakeLists.txt @@ -75,6 +75,8 @@ gz_build_tests(TYPE UNIT gz-sim${PROJECT_VERSION_MAJOR} gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER} gz-transport${GZ_TRANSPORT_VER}::gz-transport${GZ_TRANSPORT_VER} + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} ) if(TARGET UNIT_Gui_clean_exit_TEST) diff --git a/src/gui/Gui.cc b/src/gui/Gui.cc index f7ff4f0d8f..ef95a468d3 100644 --- a/src/gui/Gui.cc +++ b/src/gui/Gui.cc @@ -29,6 +29,7 @@ #include #include +#include "gz/sim/InstallationDirectories.hh" #include "gz/sim/Util.hh" #include "gz/sim/config.hh" #include "gz/sim/gui/Gui.hh" @@ -92,7 +93,7 @@ std::string defaultGuiConfigFile(bool _isPlayback, } auto installedConfig = common::joinPaths( - GZ_SIM_GUI_CONFIG_PATH, defaultGuiConfigName); + gz::sim::getGUIConfigPath(), defaultGuiConfigName); if (!common::copyFile(installedConfig, defaultConfig)) { gzerr << "Failed to copy installed config [" << installedConfig @@ -275,7 +276,7 @@ std::unique_ptr createGui( auto app = std::make_unique( _argc, _argv, gz::gui::WindowType::kMainWindow); - app->AddPluginPath(GZ_SIM_GUI_PLUGIN_INSTALL_DIR); + app->AddPluginPath(gz::sim::getGUIPluginInstallDir()); auto aboutDialogHandler = new gz::sim::gui::AboutDialogHandler(); aboutDialogHandler->setParent(app->Engine()); @@ -287,7 +288,7 @@ std::unique_ptr createGui( pathManager->setParent(app->Engine()); // add import path so we can load custom modules - app->Engine()->addImportPath(GZ_SIM_GUI_PLUGIN_INSTALL_DIR); + app->Engine()->addImportPath(gz::sim::getGUIPluginInstallDir().c_str()); app->SetDefaultConfigPath(defaultConfig); diff --git a/src/gui/QuickStartHandler.cc b/src/gui/QuickStartHandler.cc index c420bffc64..8659b2756d 100644 --- a/src/gui/QuickStartHandler.cc +++ b/src/gui/QuickStartHandler.cc @@ -17,13 +17,16 @@ #include "QuickStartHandler.hh" +#include "gz/sim/InstallationDirectories.hh" + using namespace gz; using namespace sim::gui; ///////////////////////////////////////////////// QString QuickStartHandler::WorldsPath() const { - return QString::fromUtf8(this->worldsPath.c_str()); + std::string worldsPathLocal = gz::sim::getWorldInstallDir(); + return QString::fromUtf8(worldsPathLocal.c_str()); } ///////////////////////////////////////////////// diff --git a/src/gui/QuickStartHandler.hh b/src/gui/QuickStartHandler.hh index e4648b5bb8..5814adce08 100644 --- a/src/gui/QuickStartHandler.hh +++ b/src/gui/QuickStartHandler.hh @@ -68,7 +68,9 @@ class GZ_SIM_GUI_VISIBLE QuickStartHandler : public QObject private: bool showAgain{true}; /// \brief Installed worlds path. - private: std::string worldsPath{GZ_SIM_WORLD_INSTALL_DIR}; + /// \warning This variable is unused and can be removed + /// once an ABI break is allowed + private: std::string worldsPath{""}; /// \brief Get starting world url. private: std::string startingWorld{""}; diff --git a/src/gui/plugins/CMakeLists.txt b/src/gui/plugins/CMakeLists.txt index 956158f39c..2a837a3e0e 100644 --- a/src/gui/plugins/CMakeLists.txt +++ b/src/gui/plugins/CMakeLists.txt @@ -118,7 +118,9 @@ function(gz_add_gui_plugin plugin_name) # Used to make test-directory headers visible to the unit tests ${PROJECT_SOURCE_DIR} # Used to make test_config.h visible to the unit tests - ${PROJECT_BINARY_DIR}) + ${PROJECT_BINARY_DIR} + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX}) endif() endif() diff --git a/src/gz.cc b/src/gz.cc index aa0f908518..cd71e586bf 100644 --- a/src/gz.cc +++ b/src/gz.cc @@ -33,6 +33,7 @@ #include #include "gz/sim/config.hh" +#include "gz/sim/InstallationDirectories.hh" #include "gz/sim/Server.hh" #include "gz/sim/ServerConfig.hh" @@ -70,7 +71,8 @@ extern "C" void cmdVerbosity( ////////////////////////////////////////////////// extern "C" const char *worldInstallDir() { - return GZ_SIM_WORLD_INSTALL_DIR; + static std::string worldInstallDir = gz::sim::getWorldInstallDir(); + return worldInstallDir.c_str(); } ////////////////////////////////////////////////// diff --git a/src/systems/environmental_sensor_system/CMakeLists.txt b/src/systems/environmental_sensor_system/CMakeLists.txt index c589a464bf..ff91c6e175 100644 --- a/src/systems/environmental_sensor_system/CMakeLists.txt +++ b/src/systems/environmental_sensor_system/CMakeLists.txt @@ -12,4 +12,6 @@ gz_build_tests(TYPE UNIT TransformTypes_TEST.cc LIB_DEPS gz-math${GZ_MATH_VER}::gz-math${GZ_MATH_VER} + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} ) diff --git a/src/systems/logical_audio_sensor_plugin/CMakeLists.txt b/src/systems/logical_audio_sensor_plugin/CMakeLists.txt index 607c0705d0..9bd43e073e 100644 --- a/src/systems/logical_audio_sensor_plugin/CMakeLists.txt +++ b/src/systems/logical_audio_sensor_plugin/CMakeLists.txt @@ -18,4 +18,6 @@ gz_build_tests(TYPE UNIT ${gtest_sources} LIB_DEPS ${PROJECT_LIBRARY_TARGET_NAME}-logicalaudiosensorplugin-system + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} ) diff --git a/src/systems/physics/CMakeLists.txt b/src/systems/physics/CMakeLists.txt index ad18e3f494..006fe39fa4 100644 --- a/src/systems/physics/CMakeLists.txt +++ b/src/systems/physics/CMakeLists.txt @@ -27,4 +27,6 @@ gz_build_tests(TYPE UNIT ${gtest_sources} LIB_DEPS gz-physics${GZ_PHYSICS_VER}::core + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} ) diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index df21fb46ec..d702cd4012 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -148,6 +148,8 @@ gz_build_tests(TYPE INTEGRATION ${tests} LIB_DEPS ${EXTRA_TEST_LIB_DEPS} + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} ) diff --git a/test/performance/CMakeLists.txt b/test/performance/CMakeLists.txt index 81cbd25f75..b43c3cba4f 100644 --- a/test/performance/CMakeLists.txt +++ b/test/performance/CMakeLists.txt @@ -41,6 +41,8 @@ gz_build_tests(TYPE PERFORMANCE ${tests} LIB_DEPS ${EXTRA_TEST_LIB_DEPS} + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} ) add_executable( diff --git a/test/regression/CMakeLists.txt b/test/regression/CMakeLists.txt index cad4ba516d..126c2b66b4 100644 --- a/test/regression/CMakeLists.txt +++ b/test/regression/CMakeLists.txt @@ -19,4 +19,6 @@ gz_build_tests(TYPE REGRESSION ${tests} LIB_DEPS ${EXTRA_TEST_LIB_DEPS} + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} ) From b2c576ba7fb8d9707b12b0c35afe14b081fad2fa Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 7 Jul 2023 13:44:17 -0700 Subject: [PATCH 14/31] add time out to wait to avoid deadlock (#2025) Signed-off-by: Ian Chen --- src/systems/sensors/Sensors.cc | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc index 388fcbf953..a346076f6d 100644 --- a/src/systems/sensors/Sensors.cc +++ b/src/systems/sensors/Sensors.cc @@ -280,12 +280,15 @@ void SensorsPrivate::RunOnce() { { std::unique_lock cvLock(this->renderMutex); - this->renderCv.wait(cvLock, [this]() + this->renderCv.wait_for(cvLock, std::chrono::microseconds(1000), [this]() { return !this->running || this->updateAvailable; }); } + if (!this->updateAvailable) + return; + if (!this->running) return; From 59b972358034817dd02bc69a6689b3fc85c58ba5 Mon Sep 17 00:00:00 2001 From: Mabel Zhang Date: Thu, 13 Jul 2023 21:48:16 -0400 Subject: [PATCH 15/31] Categorize tutorials list (#2028) * categorize tutorials * fix subheadings Signed-off-by: Mabel Zhang --- tutorials.md.in | 88 ++++++++++++++++++++------------ tutorials/gui_config.md | 2 +- tutorials/install.md | 6 +-- tutorials/light_config.md | 4 +- tutorials/model_command.md | 1 - tutorials/model_photo_shoot.md | 2 +- tutorials/python_interfaces.md | 6 +-- tutorials/reset_simulation.md | 6 +-- tutorials/underwater_vehicles.md | 23 ++++++--- 9 files changed, 81 insertions(+), 57 deletions(-) diff --git a/tutorials.md.in b/tutorials.md.in index 451e2c35ea..39329b050e 100644 --- a/tutorials.md.in +++ b/tutorials.md.in @@ -4,48 +4,25 @@ Welcome to the Gazebo @GZ_DESIGNATION_CAP@ tutorials. These tutorials will guide you through the process of understanding the capabilities of the Gazebo @GZ_DESIGNATION_CAP@ library and how to use the library effectively. +## Getting Started -**Tutorials** - +* \subpage install "Installation": Install instructions. * \subpage terminology "Terminology": List of terms used across the documentation. -* \subpage install "Install instructions": Install instructions. -* \subpage createsystemplugins "Create System Plugins": Programmatically access simulation using C++ plugins. -* \subpage rendering_plugins "Rendering plugins": Write plugins that use Gazebo Rendering on the server and client. -* \subpage levels "Levels": Load entities on demand in large environments. -* \subpage distributedsimulation "Distributed Simulation": Spread simulation across several processes. -* \subpage resources "Finding resources": The different ways in which Gazebo looks for files. -* \subpage entity_creation "Entity creation": Insert models or lights using services. -* \subpage log "Logging": Record and play back time series of world state. -* \subpage physics "Physics engines": Loading different physics engines. -* \subpage light_config "Light config": Configure lights in the scene. -* \subpage battery "Battery": Keep track of battery charge on robot models. * \subpage gui_config "GUI configuration": Customizing your layout. * \subpage server_config "Server configuration": Customizing what system plugins are loaded. -* \subpage debugging "Debugging": Information about debugging Gazebo. -* \subpage pointcloud "Converting a Point Cloud to a 3D Model": Turn point cloud data into 3D models for use in simulations. -* \subpage meshtofuel "Importing a Mesh to Fuel": Build a model directory around a mesh so it can be added to the Gazebo Fuel app. -* \subpage erbtemplate "ERB Template": Use ERB, a templating language, to generate SDF files for simulation worlds. -* \subpage detachablejoints "Detachable Joints": Creating models that start off rigidly attached and then get detached during simulation. -* \subpage triggeredpublisher "Triggered Publisher": Using the TriggeredPublisher system to orchestrate actions in simulation. -* \subpage logicalaudiosensor "Logical Audio Sensor": Using the LogicalAudioSensor system to mimic logical audio emission and detection in simulation. -* \subpage videorecorder "Video Recorder": Record videos from the 3D render window. -* \subpage collada_world_exporter "Collada World Exporter": Export an entire world to a single Collada mesh. -* \subpage underwater_vehicles "Underwater Vehicles": Understand how to simulate underwater vehicles. -* \subpage particle_emitter "Particle emitter": Using particle emitters in simulation -* \subpage blender_sdf_exporter "Blender SDF Exporter": Use a Blender script to export a model to the SDF format. -* \subpage blender_distort_meshes "Blender mesh distortion": Use a Blender Python script to programmatically deform and distort meshes to customized extents. -* \subpage blender_procedural_datasets "Generation of Procedural Datasets with Blender": Use Blender with a Python script to generate procedural datasets of SDF models. -* \subpage model_and_optimize_meshes "Model and optimize meshes": Some recomendations when creating meshes in blender for simulations. * \subpage model_command "Model Command": Use the CLI to get information about the models in a simulation. -* \subpage test_fixture "Test Fixture": Writing automated CI tests -* \subpage model_photo_shoot "Model Photo Shoot" Taking perspective, top, front, and side pictures of a model. -* \subpage spherical_coordinates "Spherical coordinates": Working with latitude and longitude -* \subpage python_interfaces Python interfaces -* \subpage headless_rendering "Headless rendering": Access the GPU on a remote machine to produce sensor data without an X server. * \subpage reset_simulation Reset simulation +* \subpage resources "Finding resources": The different ways in which Gazebo looks for files. +* \subpage debugging "Debugging": Information about debugging Gazebo. + +### GUI and rendering features + * \subpage move_camera_to_model Move camera to model +* \subpage model_photo_shoot "Model Photo Shoot" Taking perspective, top, front, and side pictures of a model. +* \subpage videorecorder "Video Recorder": Record videos from the 3D render window. +* \subpage headless_rendering "Headless rendering": Access the GPU on a remote machine to produce sensor data without an X server. -**Migration from Gazebo classic** +### Migration from Gazebo classic * \subpage migrationplugins "Plugins": Walk through the differences between writing plugins for Gazebo classic and Gazebo * \subpage migrationsdf "SDF": Migrating SDF files from Gazebo classic to Gazebo @@ -57,6 +34,49 @@ Gazebo @GZ_DESIGNATION_CAP@ library and how to use the library effectively. * \subpage migrationlinkapi "Link API": Guide on what Link C++ functions to call in Gazebo when migrating from Gazebo classic * \subpage ardupilot "Case Study": Migrating the ArduPilot ModelPlugin from Gazebo classic to Gazebo. +## Intermediate + +* \subpage log "Logging": Record and play back time series of world state. +* \subpage light_config "Light config": Configure lights in the scene. +* \subpage levels "Levels": Load entities on demand in large environments. +* \subpage python_interfaces Python interfaces + +### Specific systems and features + +* \subpage detachablejoints "Detachable Joints": Creating models that start off rigidly attached and then get detached during simulation. +* \subpage triggeredpublisher "Triggered Publisher": Using the TriggeredPublisher system to orchestrate actions in simulation. +* \subpage battery "Battery": Keep track of battery charge on robot models. +* \subpage particle_emitter "Particle emitter": Using particle emitters in simulation +* \subpage spherical_coordinates "Spherical coordinates": Working with latitude and longitude +* \subpage underwater_vehicles "Underwater Vehicles": Understand how to simulate underwater vehicles. +* \subpage logicalaudiosensor "Logical Audio Sensor": Using the LogicalAudioSensor system to mimic logical audio emission and detection in simulation. + +## Advanced users + +* \subpage physics "Physics engines": Loading different physics engines. +* \subpage entity_creation "Entity creation": Insert models or lights using services. +* \subpage erbtemplate "ERB Template": Use ERB, a templating language, to generate SDF files for simulation worlds. +* \subpage distributedsimulation "Distributed Simulation": Spread simulation across several processes. + +## Developers + +* \subpage createsystemplugins "Create System Plugins": Programmatically access simulation using C++ plugins. +* \subpage rendering_plugins "Rendering plugins": Write plugins that use Gazebo Rendering on the server and client. +* \subpage test_fixture "Test Fixture": Writing automated CI tests + +## 3D modeling help + +* \subpage collada_world_exporter "Collada World Exporter": Export an entire world to a single Collada mesh. +* \subpage meshtofuel "Importing a Mesh to Fuel": Build a model directory around a mesh so it can be added to the Gazebo Fuel app. +* \subpage pointcloud "Converting a Point Cloud to a 3D Model": Turn point cloud data into 3D models for use in simulations. + +### Blender help + +* \subpage model_and_optimize_meshes "Model and optimize meshes in Blender": Some recomendations when creating meshes in Blender for simulations. +* \subpage blender_sdf_exporter "Blender SDF Exporter": Use a Blender script to export a model to the SDF format. +* \subpage blender_distort_meshes "Blender mesh distortion": Use a Blender Python script to programmatically deform and distort meshes to customized extents. +* \subpage blender_procedural_datasets "Generation of Procedural Datasets with Blender": Use Blender with a Python script to generate procedural datasets of SDF models. + ## License The code associated with this documentation is licensed under an [Apache 2.0 License](https://www.apache.org/licenses/LICENSE-2.0). diff --git a/tutorials/gui_config.md b/tutorials/gui_config.md index 20cbfbb8f8..a1a8679450 100644 --- a/tutorials/gui_config.md +++ b/tutorials/gui_config.md @@ -159,7 +159,7 @@ hand, we'll create it from the UI. 1. Let's start loading the SDF world we created above, with the `` element back: -`gz sim /fuel_preview.sdf` + `gz sim /fuel_preview.sdf` 2. Now from the top-right menu, choose to add the "View Angle" plugin. This plugin has convenient buttons to change the camera angle, try them out! diff --git a/tutorials/install.md b/tutorials/install.md index aa98cfcc5b..2e5bbecea7 100644 --- a/tutorials/install.md +++ b/tutorials/install.md @@ -1,7 +1,5 @@ \page install Installation -# Install - These instructions are for installing only Gazebo. If you're interested in using all the Gazebo libraries, not only Igniton Gazebo, check out this [Gazebo installation](https://gazebosim.org/docs/latest/install). @@ -117,7 +115,7 @@ feature which hasn't been released yet. sudo make install ``` -# Documentation +## Documentation API documentation and tutorials can be accessed at [https://gazebosim.org/libs/gazebo](https://gazebosim.org/libs/gazebo) @@ -147,7 +145,7 @@ You can also generate the documentation from a clone of this repository by follo firefox doxygen/html/index.html ``` -# Testing +## Testing Follow these steps to run tests and static code analysis in your clone of this repository. diff --git a/tutorials/light_config.md b/tutorials/light_config.md index 4cb5c6f1de..24378aa798 100644 --- a/tutorials/light_config.md +++ b/tutorials/light_config.md @@ -3,7 +3,7 @@ This tutorial gives an introduction to Gazebo Sim's service `/world//light_config`. This service will allow to modify lights in the scene. -# Modifying lights +## Modifying lights To modify lights inside the scene we need to use the service `/world//light_config` and fill the message [`gz::msgs::Light`](https://gazebosim.org/api/msgs/6.0/classignition_1_1msgs_1_1Light.html). @@ -21,7 +21,7 @@ In this case we are creating random numbers to fill the diffuse and specular. \snippet examples/standalone/light_control/light_control.cc random numbers -# Run the example +## Run the example To run this example you should `cd` into `examples/standalone/light_control` and build the code: diff --git a/tutorials/model_command.md b/tutorials/model_command.md index 100219ad52..6947b14254 100644 --- a/tutorials/model_command.md +++ b/tutorials/model_command.md @@ -21,7 +21,6 @@ Open a new terminal and enter: And available models should be printed: - Available models: - ground_plane - vehicle_blue diff --git a/tutorials/model_photo_shoot.md b/tutorials/model_photo_shoot.md index 0624a1882c..0c90ef1ec6 100644 --- a/tutorials/model_photo_shoot.md +++ b/tutorials/model_photo_shoot.md @@ -1,6 +1,6 @@ \page model_photo_shoot Model Photo Shoot -## Using the model photo shot plugin +## Using the Model Photo Shoot plugin Gazebo offers a model photo taking tool that will take perspective, top, front, and both sides pictures of a model. You can test the demo world diff --git a/tutorials/python_interfaces.md b/tutorials/python_interfaces.md index 297c07c0e5..c4e8f42735 100644 --- a/tutorials/python_interfaces.md +++ b/tutorials/python_interfaces.md @@ -1,8 +1,8 @@ \page python_interfaces Python interfaces -# Overview +## Overview -Gazebo provides a Python API to interact with world. +Gazebo provides a Python API to interact with the world. For now, we provide a `TestFixture` class that allows to load a world file, step simulation and check entities and components. @@ -40,7 +40,7 @@ fixture.finalize() server.run(True, 1000, False) ``` -# Run the example +## Run the example In the [examples/scripts/python_api](https://github.com/gazebosim/gz-sim/tree/gz-sim7/examples/scripts/python_api) diff --git a/tutorials/reset_simulation.md b/tutorials/reset_simulation.md index df3f5b7634..d095164580 100644 --- a/tutorials/reset_simulation.md +++ b/tutorials/reset_simulation.md @@ -4,7 +4,7 @@ The Reset Gazebo transport API is exposed to allow resetting simulation to time It's possible to call this API using the command line or through the GUI. In addition to the API, we have also expanded the simulation system API with a Reset interface. -# Reset interface +## Reset interface System authors may now choose to implement the Reset interface to have a more intelligent reset process (avoiding reloading assets or regenerating scene graphs being the motivating examples). @@ -13,7 +13,7 @@ The [physics](https://github.com/gazebosim/gz-sim/blob/gz-sim7/src/systems/physi Following the tutorial \subpage createsystemplugins we should implement `ISystemReset` interface. -# Transport API +## Transport API To call the reset transport API we should call the service `/world/default/control` and fill the request message type `gz.msgs.WorldControl`, this service return a `gz.msgs.Boolean` with the status of the reset (true is everything was fine, false otherwise) @@ -24,7 +24,7 @@ The `WorldControl` message now contains a reset field that we should filled if w gz service -s /world/default/control --reqtype gz.msgs.WorldControl --reptype gz.msgs.Boolean --timeout 3000 --req 'reset: {all: true}' ``` -# GUI +## GUI We included a new button in the `World Control` plugin allowing to reset the simulation from the GUI diff --git a/tutorials/underwater_vehicles.md b/tutorials/underwater_vehicles.md index 1a938e0563..dfed5a7d9a 100644 --- a/tutorials/underwater_vehicles.md +++ b/tutorials/underwater_vehicles.md @@ -1,5 +1,6 @@ \page underwater_vehicles Underwater vehicles -# Simulating Autnomous Underwater Vehicles + +## Simulating Autnomous Underwater Vehicles Gazebo now supports basic simulation of underwater vehicles. This capability is based on the equations described in Fossen's ["Guidance and @@ -10,14 +11,16 @@ guide you through the setup of the [MBARI Tethys](https://app.gazebosim.org/accu One can find the final sdf file for this tutorial in the `examples/worlds/auv_controls.sdf` file. -# Understanding Hydrodynamic Forces +## Understanding Hydrodynamic Forces + The behaviour of a moving body through water is different from the behaviour of a ground based vehicle. In particular bodies moving underwater experience much more forces derived from drag, buoyancy and lift. The way these forces act on a body can be seen in the following diagram: ![force diagram](https://raw.githubusercontent.com/gazebosim/gz-sim/ign-gazebo5/tutorials/files/underwater/MBARI%20forces.png) -# Setting up the buoyancy plugin +## Setting up the buoyancy plugin + The buoyancy plugin in Gazebo uses the collision mesh to calculate the volume of the vehicle. The calculated volume is used to determine the buoyancy force, which is then applied at the pose of the collision mesh in the link frame. Note @@ -35,7 +38,9 @@ tag: 1000 ``` -# Setting up the thrusters + +## Setting up the thrusters + We need the vehicle to move, so we will be adding the `Thruster` plugin. The thruster plugin takes in a force and applies it along with calculating the desired rpm. Under the `` or `` tag add the following: @@ -64,7 +69,8 @@ constant is normally determined by individual manufacturers. In this case we are using the Tethys's thrust coefficient. you may also build a test rig to measure your thruster's thrust coefficient. -# Adding Hydrodynamic behaviour +## Adding Hydrodynamic behaviour + You may notice that the robot now keeps getting faster and faster. This is because there is no drag to oppose the thruster's force. We will be using Fossen's equations which describe the motion of a craft through the water for @@ -97,7 +103,8 @@ name="gz::sim::systems::Hydrodynamics"> ``` -# Control surfaces +## Control surfaces + Just like aeroplanes, an underwater vehicle may also use fins for stability and control. Fortunately, Gazebo already has a version of the LiftDrag plugin. In this tutorial, we will simply add two liftdrag plugins to the rudder and @@ -169,7 +176,7 @@ gz topic -t /model/tethys/joint/vertical_fins_joint/0/cmd_pos \ -m gz.msgs.Double -p 'data: -0.17' ``` -# Testing the system out +## Testing the system out To control the rudder of the craft run the following ``` @@ -183,7 +190,7 @@ gz topic -t /model/tethys/joint/propeller_joint/cmd_pos \ ``` The vehicle should move in a circle. -# Ocean Currents +## Ocean Currents When underwater, vehicles are often subject to ocean currents. The hydrodynamics plugin allows simulation of such currents. We can add a current simply by From e749020e1ea5cbd4a07a9f22438eb01ec3ee1b01 Mon Sep 17 00:00:00 2001 From: Henrique Barros Oliveira Date: Sat, 15 Jul 2023 02:50:54 -0300 Subject: [PATCH 16/31] Send BlockOrbit false events only once from TransformControl plugin (#2030) Currently, the TransformControl plugin sends a BlockOrbit event on every rendering call, even if it does not wish to block the camera orbit. Because of this, if another plugin sends a BlockOrbit event, it might get overwritten by TransformControl's and not have the desired effect. This PR fixes this by making TransformControl send BlockOrbit false events only once (to unblock after a transform), allowing other plugins to block the camera while TransformControl is idle. true events are unchanged, and are still sent on every rendering call. Signed-off-by: Henrique-BO --- .../transform_control/TransformControl.cc | 22 +++++++++++++++---- 1 file changed, 18 insertions(+), 4 deletions(-) diff --git a/src/gui/plugins/transform_control/TransformControl.cc b/src/gui/plugins/transform_control/TransformControl.cc index fafbe40f03..ad1a8aa48f 100644 --- a/src/gui/plugins/transform_control/TransformControl.cc +++ b/src/gui/plugins/transform_control/TransformControl.cc @@ -173,6 +173,9 @@ namespace gz::sim /// \brief Block orbit public: bool blockOrbit = false; + + /// \brief True if BlockOrbit events should be sent + public: bool sendBlockOrbit = false; }; } @@ -499,10 +502,17 @@ void TransformControlPrivate::HandleTransform() this->HandleMouseEvents(); - gz::gui::events::BlockOrbit blockOrbitEvent(this->blockOrbit); - gz::gui::App()->sendEvent( - gz::gui::App()->findChild(), - &blockOrbitEvent); + if (this->sendBlockOrbit) + { + // Events with false should only be sent once + if (!this->blockOrbit) + this->sendBlockOrbit = false; + + gz::gui::events::BlockOrbit blockOrbitEvent(this->blockOrbit); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), + &blockOrbitEvent); + } } ///////////////////////////////////////////////// @@ -534,6 +544,7 @@ void TransformControlPrivate::HandleMouseEvents() if (axis != gz::math::Vector3d::Zero) { this->blockOrbit = true; + this->sendBlockOrbit = true; // start the transform process this->transformControl.SetActiveAxis(axis); this->transformControl.Start(); @@ -553,6 +564,7 @@ void TransformControlPrivate::HandleMouseEvents() else { this->blockOrbit = false; + this->sendBlockOrbit = true; return; } } @@ -560,6 +572,7 @@ void TransformControlPrivate::HandleMouseEvents() else if (this->mouseEvent.Type() == gz::common::MouseEvent::RELEASE) { this->blockOrbit = false; + this->sendBlockOrbit = true; this->isStartWorldPosSet = false; if (this->transformControl.Active()) @@ -706,6 +719,7 @@ void TransformControlPrivate::HandleMouseEvents() } this->blockOrbit = true; + this->sendBlockOrbit = true; // compute the the start and end mouse positions in normalized coordinates auto imageWidth = static_cast(this->camera->ImageWidth()); auto imageHeight = static_cast( From 0fe4ed066fb8b35e5bd6ccfdbd4676c9c6a847eb Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Mon, 17 Jul 2023 10:16:26 -0700 Subject: [PATCH 17/31] ComponentInspector: display PhysicsEnginePlugin (#2032) Signed-off-by: Steve Peters --- src/gui/plugins/component_inspector/ComponentInspector.cc | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index cd5f0eadc3..dc9d208c53 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -764,6 +764,13 @@ void ComponentInspector::Update(const UpdateInfo &, if (comp) setData(item, comp->Data()); } + else if (typeId == components::PhysicsEnginePlugin::typeId) + { + auto comp = _ecm.Component( + this->dataPtr->entity); + if (comp) + setData(item, comp->Data()); + } else if (typeId == components::PhysicsSolver::typeId) { auto comp = _ecm.Component( From 50a99e6c2c102c54471e6ba364ba73d73c428696 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 21 Jul 2023 10:56:05 -0700 Subject: [PATCH 18/31] Support loading mesh by mesh name in (#2007) Allow users to specify name of mesh in SDF via . Addresses this use case: User has created common:Mesh object and added it to the MeshManager via AddMesh call. They now want to spawn a new model with this mesh using an SDF string that has set to the name of their common::Mesh. --------- Signed-off-by: Ian Chen --- include/gz/sim/Util.hh | 7 + src/Util.cc | 41 +++ src/Util_TEST.cc | 21 ++ src/rendering/SceneManager.cc | 25 +- src/systems/physics/Physics.cc | 10 +- test/integration/CMakeLists.txt | 1 + test/integration/mesh_uri.cc | 240 ++++++++++++++++++ .../worlds/camera_sensor_scene_background.sdf | 4 + tutorials/resources.md | 8 + 9 files changed, 336 insertions(+), 21 deletions(-) create mode 100644 test/integration/mesh_uri.cc diff --git a/include/gz/sim/Util.hh b/include/gz/sim/Util.hh index 41a7ca3dab..0840c2c1c1 100644 --- a/include/gz/sim/Util.hh +++ b/include/gz/sim/Util.hh @@ -24,7 +24,9 @@ #include #include +#include #include +#include #include "gz/sim/components/Environment.hh" #include "gz/sim/config.hh" @@ -309,6 +311,11 @@ namespace gz const math::Vector3d& _worldPosition, const std::shared_ptr& _gridField); + /// \brief Load a mesh from a Mesh SDF DOM + /// \param[in] _meshSdf Mesh SDF DOM + /// \return The loaded mesh or null if the mesh can not be loaded. + GZ_SIM_VISIBLE const common::Mesh *loadMesh(const sdf::Mesh &_meshSdf); + /// \brief Environment variable holding resource paths. const std::string kResourcePathEnv{"GZ_SIM_RESOURCE_PATH"}; diff --git a/src/Util.cc b/src/Util.cc index db9918272f..e23013c241 100644 --- a/src/Util.cc +++ b/src/Util.cc @@ -18,7 +18,10 @@ #include #include +#include +#include #include +#include #include #include #include @@ -837,6 +840,44 @@ std::string resolveSdfWorldFile(const std::string &_sdfFile, return filePath; } + +const common::Mesh *loadMesh(const sdf::Mesh &_meshSdf) +{ + const common::Mesh *mesh = nullptr; + auto &meshManager = *common::MeshManager::Instance(); + if (common::URI(_meshSdf.Uri()).Scheme() == "name") + { + // if it has a name:// scheme, see if the mesh + // exists in the mesh manager and load it by name + const std::string basename = common::basename(_meshSdf.Uri()); + mesh = meshManager.MeshByName(basename); + if (nullptr == mesh) + { + gzwarn << "Failed to load mesh by name [" << basename + << "]." << std::endl; + return nullptr; + } + } + else if (meshManager.IsValidFilename(_meshSdf.Uri())) + { + // load mesh by file path + auto fullPath = asFullPath(_meshSdf.Uri(), _meshSdf.FilePath()); + mesh = meshManager.Load(fullPath); + if (nullptr == mesh) + { + gzwarn << "Failed to load mesh from [" << fullPath + << "]." << std::endl; + return nullptr; + } + } + else + { + gzwarn << "Failed to load mesh [" << _meshSdf.Uri() + << "]." << std::endl; + return nullptr; + } + return mesh; +} } } } diff --git a/src/Util_TEST.cc b/src/Util_TEST.cc index d4bd50edf8..6cc56dbd1b 100644 --- a/src/Util_TEST.cc +++ b/src/Util_TEST.cc @@ -40,6 +40,7 @@ #include "gz/sim/Util.hh" #include "helpers/EnvTestFixture.hh" +#include "test_config.hh" using namespace gz; using namespace sim; @@ -1003,3 +1004,23 @@ TEST_F(UtilTest, ResolveSdfWorldFile) // A bad relative path should return an empty string EXPECT_TRUE(resolveSdfWorldFile("../invalid/does_not_exist.sdf").empty()); } + +///////////////////////////////////////////////// +TEST_F(UtilTest, LoadMesh) +{ + sdf::Mesh meshSdf; + EXPECT_EQ(nullptr, loadMesh(meshSdf)); + + meshSdf.SetUri("invalid_uri"); + meshSdf.SetFilePath("invalid_filepath"); + EXPECT_EQ(nullptr, loadMesh(meshSdf)); + + meshSdf.SetUri("name://unit_box"); + EXPECT_NE(nullptr, loadMesh(meshSdf)); + + meshSdf.SetUri("duck.dae"); + std::string filePath = common::joinPaths(std::string(PROJECT_SOURCE_PATH), + "test", "media", "duck.dae"); + meshSdf.SetFilePath(filePath); + EXPECT_NE(nullptr, loadMesh(meshSdf)); +} diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index f1f758e8e9..5684d4b047 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -702,23 +702,22 @@ rendering::GeometryPtr SceneManager::LoadGeometry(const sdf::Geometry &_geom, } else if (_geom.Type() == sdf::GeometryType::MESH) { - auto fullPath = asFullPath(_geom.MeshShape()->Uri(), - _geom.MeshShape()->FilePath()); - if (fullPath.empty()) - { - gzerr << "Mesh geometry missing uri" << std::endl; - return geom; - } rendering::MeshDescriptor descriptor; - - // Assume absolute path to mesh file - descriptor.meshName = fullPath; + descriptor.mesh = loadMesh(*_geom.MeshShape()); + if (!descriptor.mesh) + return geom; + std::string meshUri = + (common::URI(_geom.MeshShape()->Uri()).Scheme() == "name") ? + common::basename(_geom.MeshShape()->Uri()) : + asFullPath(_geom.MeshShape()->Uri(), + _geom.MeshShape()->FilePath()); + auto a = asFullPath(_geom.MeshShape()->Uri(), + _geom.MeshShape()->FilePath()); + + descriptor.meshName = meshUri; descriptor.subMeshName = _geom.MeshShape()->Submesh(); descriptor.centerSubMesh = _geom.MeshShape()->CenterSubmesh(); - common::MeshManager *meshManager = - common::MeshManager::Instance(); - descriptor.mesh = meshManager->Load(descriptor.meshName); geom = this->dataPtr->scene->CreateMesh(descriptor); scale = _geom.MeshShape()->Scale(); } diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index c70e2103db..b81f17330a 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -1406,15 +1406,9 @@ void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm, return true; } - auto &meshManager = *common::MeshManager::Instance(); - auto fullPath = asFullPath(meshSdf->Uri(), meshSdf->FilePath()); - auto *mesh = meshManager.Load(fullPath); - if (nullptr == mesh) - { - gzwarn << "Failed to load mesh from [" << fullPath - << "]." << std::endl; + const common::Mesh *mesh = loadMesh(*meshSdf); + if (!mesh) return true; - } auto linkMeshFeature = this->entityLinkMap.EntityCast(_parent->Data()); diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index d702cd4012..59eae5c5c4 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -101,6 +101,7 @@ set(tests_needing_display depth_camera.cc distortion_camera.cc gpu_lidar.cc + mesh_uri.cc optical_tactile_plugin.cc reset_sensors.cc rgbd_camera.cc diff --git a/test/integration/mesh_uri.cc b/test/integration/mesh_uri.cc new file mode 100644 index 0000000000..8ce6891190 --- /dev/null +++ b/test/integration/mesh_uri.cc @@ -0,0 +1,240 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include + +#include + +#include +#include +#include +#include +#include + +#include "gz/sim/components/Model.hh" +#include "gz/sim/components/Name.hh" +#include "gz/sim/components/Pose.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/SystemLoader.hh" +#include "test_config.hh" + +#include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" + +using namespace gz; +using namespace sim; + +std::mutex mutex; +int g_count = 0; +msgs::Image g_image; + +///////////////////////////////////////////////// +void cameraCb(const msgs::Image & _msg) +{ + ASSERT_EQ(msgs::PixelFormatType::RGB_INT8, + _msg.pixel_format_type()); + + std::lock_guard lock(mutex); + g_image = _msg; + g_count++; +} + +std::string meshModelStr(bool _static = false) +{ + // SDF string consisting of a box mesh. Note that "unit_box" + // is a mesh that comes pre-registered with MeshManager so + // it should be able to load this as a mesh. + // Similarly the user can create a common::Mesh object and add that + // to the MeshManager by calling MeshManager::Instance()->AddMesh; + return std::string("") + + "" + + "" + + "" + + "" + + "name://unit_box" + + "" + + "" + + "name://unit_box" + + "" + + "" + + "" + std::to_string(_static) + "" + + "" + + ""; +} + +////////////////////////////////////////////////// +class MeshUriTest : public InternalFixture<::testing::Test> +{ +}; + +///////////////////////////////////////////////// +// Test spawning mesh by name and verify that the mesh is correctly +// spawned in both rendering and physics. Cameras should see the spawned +// mesh and spawend object should collide with one another on the physics +// side. +TEST_F(MeshUriTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(SpawnMeshByName)) +{ + // Start server + ServerConfig serverConfig; + const auto sdfFile = common::joinPaths(std::string(PROJECT_SOURCE_PATH), + "test", "worlds", "camera_sensor_scene_background.sdf"); + serverConfig.SetSdfFile(sdfFile); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + // Create a system just to get the ECM + EntityComponentManager *ecm{nullptr}; + test::Relay testSystem; + testSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &_ecm) + { + ecm = &_ecm; + }); + + server.AddSystem(testSystem.systemPtr); + + // Run server and check we have the ECM + EXPECT_EQ(nullptr, ecm); + server.Run(true, 1, false); + EXPECT_NE(nullptr, ecm); + + auto entityCount = ecm->EntityCount(); + + // Subscribe to the camera topic + transport::Node node; + g_count = 0; + node.Subscribe("/camera", &cameraCb); + + // Run and make sure we received camera images + server.Run(true, 100, false); + for (int i = 0; i < 100 && g_count <= 0; ++i) + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + EXPECT_LT(0u, g_count); + + unsigned char *imageBuffer = nullptr; + unsigned int midIdx = 0u; + unsigned int bufferSize = 0u; + // Empty scene - camera should see just red background + { + std::lock_guard lock(mutex); + bufferSize = g_image.width() *g_image.height() * 3u; + imageBuffer = new unsigned char[bufferSize]; + memcpy(imageBuffer, g_image.data().c_str(), bufferSize); + + midIdx = (g_image.height() * 0.5 * g_image.width() + + g_image.width() * 0.5) * 3; + } + unsigned int r = imageBuffer[midIdx]; + unsigned int g = imageBuffer[midIdx + 1]; + unsigned int b = imageBuffer[midIdx + 2]; + EXPECT_EQ(255u, r); + EXPECT_EQ(0u, g); + EXPECT_EQ(0u, b); + + // Spawn a static box (mesh) model in front of the camera + msgs::EntityFactory req; + req.set_sdf(meshModelStr(true)); + + auto pose = req.mutable_pose(); + auto pos = pose->mutable_position(); + pos->set_x(3); + pos->set_z(1); + + msgs::Boolean res; + bool result; + unsigned int timeout = 5000; + std::string service{"/world/sensors/create"}; + + EXPECT_TRUE(node.Request(service, req, timeout, res, result)); + EXPECT_TRUE(result); + EXPECT_TRUE(res.data()); + + // Check entity has not been created yet + EXPECT_EQ(kNullEntity, ecm->EntityByComponents(components::Model(), + components::Name("spawned_model"))); + + // Run an iteration and check it was created + server.Run(true, 1, false); + EXPECT_EQ(entityCount + 4, ecm->EntityCount()); + entityCount = ecm->EntityCount(); + + auto model = ecm->EntityByComponents(components::Model(), + components::Name("spawned_model")); + EXPECT_NE(kNullEntity, model); + auto poseComp = ecm->Component(model); + EXPECT_NE(nullptr, poseComp); + EXPECT_EQ(math::Pose3d(3, 0, 1, 0, 0, 0), poseComp->Data()); + + // Verify camera now sees a white box + g_count = 0u; + server.Run(true, 100, false); + for (int i = 0; i < 100 && g_count <= 1; ++i) + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + EXPECT_LT(0u, g_count); + + { + std::lock_guard lock(mutex); + memcpy(imageBuffer, g_image.data().c_str(), bufferSize); + } + r = imageBuffer[midIdx]; + g = imageBuffer[midIdx + 1]; + b = imageBuffer[midIdx + 2]; + EXPECT_EQ(255u, r); + EXPECT_EQ(255u, g); + EXPECT_EQ(255u, b); + + // Spawn another box over the static one + const std::string spawnedModel2Name = "spawned_model2"; + req.set_sdf(meshModelStr()); + req.set_name(spawnedModel2Name); + pose = req.mutable_pose(); + pos = pose->mutable_position(); + pos->set_x(3); + pos->set_z(5); + EXPECT_TRUE(node.Request(service, req, timeout, res, result)); + EXPECT_TRUE(result); + EXPECT_TRUE(res.data()); + + // Check entity has not been created yet + EXPECT_EQ(kNullEntity, ecm->EntityByComponents(components::Model(), + components::Name(spawnedModel2Name))); + + // Run an iteration and check it was created + server.Run(true, 1, false); + EXPECT_EQ(entityCount + 4, ecm->EntityCount()); + entityCount = ecm->EntityCount(); + + auto model2 = ecm->EntityByComponents(components::Model(), + components::Name(spawnedModel2Name)); + EXPECT_NE(kNullEntity, model2); + + poseComp = ecm->Component(model2); + EXPECT_NE(nullptr, poseComp); + EXPECT_EQ(math::Pose3d(3, 0, 5, 0, 0, 0), poseComp->Data()); + + // run and spawned model 2 should fall onto the previous box + server.Run(true, 1000, false); + poseComp = ecm->Component(model2); + EXPECT_NE(nullptr, poseComp); + EXPECT_EQ(math::Pose3d(3, 0, 2, 0, 0, 0), poseComp->Data()) << + poseComp->Data(); + + delete [] imageBuffer; + imageBuffer = nullptr; +} diff --git a/test/worlds/camera_sensor_scene_background.sdf b/test/worlds/camera_sensor_scene_background.sdf index b6357d6dec..f973da51fb 100644 --- a/test/worlds/camera_sensor_scene_background.sdf +++ b/test/worlds/camera_sensor_scene_background.sdf @@ -14,6 +14,10 @@ name="gz::sim::systems::Sensors"> ogre2 + + 1 0 0 diff --git a/tutorials/resources.md b/tutorials/resources.md index 09634ed9b7..02fdb5ad19 100644 --- a/tutorials/resources.md +++ b/tutorials/resources.md @@ -144,6 +144,14 @@ Gazebo will look for URIs (path / URL) in the following, in order: \* The `GZ_FILE_PATH` environment variable also works in some scenarios, but it's not recommended when using Gazebo. +If a ` starts with the `name://` scheme, +e.g. `name://my_mesh_name`, Gazebo will check to see if a mesh with the +specified name exists in the Mesh Manager and load that mesh if it exists. +This can happen when a `common::Mesh` object is created in memory and +registered with the Mesh Manager via the +[common::MeshManager::Instance()->AddMesh](https://gazebosim.org/api/common/5/classgz_1_1common_1_1MeshManager.html#a2eaddabc3a3109bd8757b2a8b2dd2d01) +call. + ### GUI configuration Gazebo Sim's From fbc3ca84b86cc3c0033ae3979797340b7bf1b361 Mon Sep 17 00:00:00 2001 From: Henrique Barros Oliveira Date: Wed, 26 Jul 2023 17:45:35 -0300 Subject: [PATCH 19/31] Apply Force and Torque GUI plugin (#2014) Adds a new ApplyForceTorque GUI plugin, essentially implementing the Apply Force and Torque interface that we have in Gazebo Classic. This allows users to apply a specified force and torque to a chosen link in a model upon pressing a button. The implementation takes advantage of the existing ApplyLinkWrench system, sending the wrenches to the /world//wrench topic. The ApplyLinkWrench system is automatically loaded once this plugin is loaded. --------- Signed-off-by: Henrique-BO --- src/gui/plugins/CMakeLists.txt | 1 + .../apply_force_torque/ApplyForceTorque.cc | 402 ++++++++++++++++++ .../apply_force_torque/ApplyForceTorque.hh | 133 ++++++ .../apply_force_torque/ApplyForceTorque.qml | 251 +++++++++++ .../apply_force_torque/ApplyForceTorque.qrc | 5 + .../plugins/apply_force_torque/CMakeLists.txt | 4 + 6 files changed, 796 insertions(+) create mode 100644 src/gui/plugins/apply_force_torque/ApplyForceTorque.cc create mode 100644 src/gui/plugins/apply_force_torque/ApplyForceTorque.hh create mode 100644 src/gui/plugins/apply_force_torque/ApplyForceTorque.qml create mode 100644 src/gui/plugins/apply_force_torque/ApplyForceTorque.qrc create mode 100644 src/gui/plugins/apply_force_torque/CMakeLists.txt diff --git a/src/gui/plugins/CMakeLists.txt b/src/gui/plugins/CMakeLists.txt index 2a837a3e0e..c663b8f392 100644 --- a/src/gui/plugins/CMakeLists.txt +++ b/src/gui/plugins/CMakeLists.txt @@ -131,6 +131,7 @@ add_subdirectory(modules) # Plugins add_subdirectory(align_tool) +add_subdirectory(apply_force_torque) add_subdirectory(banana_for_scale) add_subdirectory(component_inspector) add_subdirectory(component_inspector_editor) diff --git a/src/gui/plugins/apply_force_torque/ApplyForceTorque.cc b/src/gui/plugins/apply_force_torque/ApplyForceTorque.cc new file mode 100644 index 0000000000..d0f1a1848c --- /dev/null +++ b/src/gui/plugins/apply_force_torque/ApplyForceTorque.cc @@ -0,0 +1,402 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "ApplyForceTorque.hh" + +namespace gz +{ +namespace sim +{ + class ApplyForceTorquePrivate + { + /// \brief Publish EntityWrench messages in order to apply force and torque + /// \param[in] _applyForce True if the force should be applied + /// \param[in] _applyTorque True if the torque should be applied + public: void PublishWrench(bool _applyForce, bool _applyTorque); + + /// \brief Transport node + public: transport::Node node; + + /// \brief Publisher for EntityWrench messages + public: transport::Node::Publisher pub; + + /// \brief World name + public: std::string worldName; + + /// \brief True if the ApplyLinkWrench system is loaded + public: bool systemLoaded{false}; + + /// \brief To synchronize member access + public: std::mutex mutex; + + /// \brief Name of the selected model + public: QString modelName; + + /// \brief List of the name of the links in the selected model + public: QStringList linkNameList; + + /// \brief Index of selected link in list + public: int linkIndex{-1}; + + /// \brief Entity of the currently selected Link + public: std::optional selectedEntity; + + /// \brief True if a new entity was selected + public: bool changedEntity{false}; + + /// \brief True if a new link was selected from the dropdown + public: bool changedIndex{false}; + + /// \brief Force to be applied in link-fixed frame'' + public: math::Vector3d force{0.0, 0.0, 0.0}; + + /// \brief Torque to be applied in link-fixed frame + public: math::Vector3d torque{0.0, 0.0, 0.0}; + + /// \brief Offset from the link origin to the center of mass in world coords + public: math::Vector3d inertialPos; + + /// \brief Orientation of the link-fixed frame + public: math::Quaterniond linkRot; + }; +} +} + +using namespace gz; +using namespace sim; + +///////////////////////////////////////////////// +ApplyForceTorque::ApplyForceTorque() + : GuiSystem(), dataPtr(std::make_unique()) +{ +} + +///////////////////////////////////////////////// +ApplyForceTorque::~ApplyForceTorque() = default; + +///////////////////////////////////////////////// +void ApplyForceTorque::LoadConfig(const tinyxml2::XMLElement */*_pluginElem*/) +{ + if (this->title.empty()) + this->title = "Apply force and torque"; + + // Create wrench publisher + auto worldNames = gz::gui::worldNames(); + if (!worldNames.empty()) + { + this->dataPtr->worldName = worldNames[0].toStdString(); + auto topic = transport::TopicUtils::AsValidTopic( + "/world/" + this->dataPtr->worldName + "/wrench"); + if (topic == "") + { + gzerr << "Unable to create publisher" << std::endl; + return; + } + this->dataPtr->pub = + this->dataPtr->node.Advertise(topic); + gzdbg << "Created publisher to " << topic << std::endl; + } + + gz::gui::App()->findChild + ()->installEventFilter(this); +} + +///////////////////////////////////////////////// +bool ApplyForceTorque::eventFilter(QObject *_obj, QEvent *_event) +{ + std::lock_guard lock(this->dataPtr->mutex); + + if (_event->type() == + gz::sim::gui::events::EntitiesSelected::kType) + { + gz::sim::gui::events::EntitiesSelected *_e = + static_cast(_event); + this->dataPtr->selectedEntity = _e->Data().front(); + this->dataPtr->changedEntity = true; + } + else if (_event->type() == + gz::sim::gui::events::DeselectAllEntities::kType) + { + this->dataPtr->selectedEntity.reset(); + this->dataPtr->changedEntity = true; + } + + return QObject::eventFilter(_obj, _event); +} + +///////////////////////////////////////////////// +void ApplyForceTorque::Update(const UpdateInfo &/*_info*/, + EntityComponentManager &_ecm) +{ + std::lock_guard lock(this->dataPtr->mutex); + + // Load the ApplyLinkWrench system + if (!this->dataPtr->systemLoaded) + { + const std::string name{"gz::sim::systems::ApplyLinkWrench"}; + const std::string filename{"gz-sim-apply-link-wrench-system"}; + const std::string innerxml{"0"}; + + // Get world entity + Entity worldEntity; + _ecm.Each( + [&](const Entity &_entity, + const components::World */*_world*/, + const components::Name *_name)->bool + { + if (_name->Data() == this->dataPtr->worldName) + { + worldEntity = _entity; + return false; + } + return true; + }); + + // Check if already loaded + auto msg = _ecm.ComponentData(worldEntity); + if (!msg) + { + gzdbg << "Unable to find SystemPluginInfo component for entity " + << worldEntity << std::endl; + return; + } + for (const auto &plugin : msg->plugins()) + { + if (plugin.filename() == filename) + { + this->dataPtr->systemLoaded = true; + gzdbg << "ApplyLinkWrench system already loaded" << std::endl; + break; + } + } + + // Request to load system + if (!this->dataPtr->systemLoaded) + { + msgs::EntityPlugin_V req; + req.mutable_entity()->set_id(worldEntity); + auto plugin = req.add_plugins(); + plugin->set_name(name); + plugin->set_filename(filename); + plugin->set_innerxml(innerxml); + + msgs::Boolean res; + bool result; + unsigned int timeout = 5000; + std::string service{"/world/" + this->dataPtr->worldName + + "/entity/system/add"}; + if (this->dataPtr->node.Request(service, req, timeout, res, result)) + { + this->dataPtr->systemLoaded = true; + gzdbg << "ApplyLinkWrench system has been loaded" << std::endl; + } + else + { + gzerr << "Error adding new system to entity: " + << worldEntity << "\n" + << "Name: " << name << "\n" + << "Filename: " << filename << "\n" + << "Inner XML: " << innerxml << std::endl; + } + } + } + + if (this->dataPtr->changedEntity) + { + this->dataPtr->changedEntity = false; + + this->dataPtr->modelName = ""; + this->dataPtr->linkNameList.clear(); + this->dataPtr->linkIndex = -1; + + if (this->dataPtr->selectedEntity.has_value()) + { + Model parentModel(*this->dataPtr->selectedEntity); + Link selectedLink(*this->dataPtr->selectedEntity); + if (parentModel.Valid(_ecm)) + { + selectedLink = Link(parentModel.CanonicalLink(_ecm)); + } + else if (selectedLink.Valid(_ecm)) + { + parentModel = *selectedLink.ParentModel(_ecm); + } + else + { + this->dataPtr->selectedEntity.reset(); + return; + } + + this->dataPtr->modelName = QString::fromStdString( + parentModel.Name(_ecm)); + this->dataPtr->selectedEntity = selectedLink.Entity(); + + // Put all of the model's links into the list + auto links = parentModel.Links(_ecm); + unsigned int i{0}; + while (i < links.size()) + { + Link link(links[i]); + this->dataPtr->linkNameList.push_back( + QString::fromStdString(*link.Name(_ecm))); + if (link.Entity() == this->dataPtr->selectedEntity) + { + this->dataPtr->linkIndex = i; + } + ++i; + } + } + } + + if (this->dataPtr->changedIndex) + { + this->dataPtr->changedIndex = false; + + if (this->dataPtr->selectedEntity.has_value()) + { + auto parentModel = Link(*this->dataPtr->selectedEntity).ParentModel(_ecm); + std::string linkName = + this->dataPtr->linkNameList[this->dataPtr->linkIndex].toStdString(); + this->dataPtr->selectedEntity = parentModel->LinkByName(_ecm, linkName); + } + } + + // Get the position of the center of mass and link orientation + if (this->dataPtr->selectedEntity.has_value()) + { + auto linkWorldPose = worldPose(*this->dataPtr->selectedEntity, _ecm); + auto inertial = _ecm.Component( + *this->dataPtr->selectedEntity); + if (inertial) + { + this->dataPtr->inertialPos = + linkWorldPose.Rot().RotateVector(inertial->Data().Pose().Pos()); + this->dataPtr->linkRot = linkWorldPose.Rot(); + } + } + + emit this->ModelNameChanged(); + emit this->LinkNameListChanged(); + emit this->LinkIndexChanged(); +} + +///////////////////////////////////////////////// +QString ApplyForceTorque::ModelName() const +{ + return this->dataPtr->modelName; +} + +///////////////////////////////////////////////// +QStringList ApplyForceTorque::LinkNameList() const +{ + return this->dataPtr->linkNameList; +} + +///////////////////////////////////////////////// +int ApplyForceTorque::LinkIndex() const +{ + return this->dataPtr->linkIndex; +} + +///////////////////////////////////////////////// +void ApplyForceTorque::SetLinkIndex(int _linkIndex) +{ + this->dataPtr->linkIndex = _linkIndex; + this->dataPtr->changedIndex = true; +} + +///////////////////////////////////////////////// +void ApplyForceTorque::UpdateForce(double _x, double _y, double _z) +{ + this->dataPtr->force = {_x, _y, _z}; +} + +///////////////////////////////////////////////// +void ApplyForceTorque::UpdateTorque(double _x, double _y, double _z) +{ + this->dataPtr->torque = {_x, _y, _z}; +} + +///////////////////////////////////////////////// +void ApplyForceTorque::ApplyForce() +{ + this->dataPtr->PublishWrench(true, false); +} + +///////////////////////////////////////////////// +void ApplyForceTorque::ApplyTorque() +{ + this->dataPtr->PublishWrench(false, true); +} + +///////////////////////////////////////////////// +void ApplyForceTorque::ApplyAll() +{ + this->dataPtr->PublishWrench(true, true); +} + +///////////////////////////////////////////////// +void ApplyForceTorquePrivate::PublishWrench(bool _applyForce, bool _applyTorque) +{ + std::lock_guard lock(this->mutex); + + if (!this->selectedEntity.has_value()) + { + gzdbg << "No link selected" << std::endl; + return; + } + + // Force and torque in world coordinates + math::Vector3d forceToApply = this->linkRot.RotateVector( + _applyForce ? this->force : math::Vector3d::Zero); + math::Vector3d torqueToApply = this->linkRot.RotateVector( + _applyTorque ? this->torque : math::Vector3d::Zero) + + this->inertialPos.Cross(forceToApply); + + msgs::EntityWrench msg; + msg.mutable_entity()->set_id(*this->selectedEntity); + msgs::Set(msg.mutable_wrench()->mutable_force(), forceToApply); + msgs::Set(msg.mutable_wrench()->mutable_torque(), torqueToApply); + + this->pub.Publish(msg); +} + +// Register this plugin +GZ_ADD_PLUGIN(ApplyForceTorque, gz::gui::Plugin) diff --git a/src/gui/plugins/apply_force_torque/ApplyForceTorque.hh b/src/gui/plugins/apply_force_torque/ApplyForceTorque.hh new file mode 100644 index 0000000000..c6cc2bfa14 --- /dev/null +++ b/src/gui/plugins/apply_force_torque/ApplyForceTorque.hh @@ -0,0 +1,133 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#ifndef GZ_GUI_APPLYFORCETORQUE_HH_ +#define GZ_GUI_APPLYFORCETORQUE_HH_ + +#include + +#include +#include +#include +#include + +#include +#include + +namespace gz +{ +namespace sim +{ + class ApplyForceTorquePrivate; + + /// \brief Publish wrench to "/world//wrench" topic. + /// Automatically loads the ApplyLinkWrench system. + /// + /// ## Configuration + /// This plugin doesn't accept any custom configuration. + class ApplyForceTorque : public gz::sim::GuiSystem + { + Q_OBJECT + + /// \brief Model name + Q_PROPERTY( + QString modelName + READ ModelName + NOTIFY ModelNameChanged + ) + + /// \brief Link list + Q_PROPERTY( + QStringList linkNameList + READ LinkNameList + NOTIFY LinkNameListChanged + ) + + /// \brief Link index + Q_PROPERTY( + int linkIndex + READ LinkIndex + WRITE SetLinkIndex + NOTIFY LinkIndexChanged + ) + + /// \brief Constructor + public: ApplyForceTorque(); + + /// \brief Destructor + public: ~ApplyForceTorque() override; + + // Documentation inherited + public: void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override; + + // Documentation inherited + protected: bool eventFilter(QObject *_obj, QEvent *_event) override; + + // Documentation inherited + public: void Update(const UpdateInfo &_info, + EntityComponentManager &_ecm) override; + + /// \brief Get the name of the selected model + public: Q_INVOKABLE QString ModelName() const; + + /// \brief Notify that the model name changed + signals: void ModelNameChanged(); + + /// \brief Get the name of the links of the selected model + public: Q_INVOKABLE QStringList LinkNameList() const; + + /// \brief Notify that the link list changed + signals: void LinkNameListChanged(); + + /// \brief Get index of the link in the list + public: Q_INVOKABLE int LinkIndex() const; + + /// \brief Notify that the link index changed + signals: void LinkIndexChanged(); + + /// \brief Set the index of the link in the list + public: Q_INVOKABLE void SetLinkIndex(int _linkIndex); + + /// \brief Set components of force + /// \param[in] _x X component of force + /// \param[in] _y Y component of force + /// \param[in] _z Z component of force + public: Q_INVOKABLE void UpdateForce(double _x, double _y, double _z); + + /// \brief Set components of torque + /// \param[in] _x X component of torque + /// \param[in] _y Y component of torque + /// \param[in] _z Z component of torque + public: Q_INVOKABLE void UpdateTorque(double _x, double _y, double _z); + + /// \brief Apply the specified force + public: Q_INVOKABLE void ApplyForce(); + + /// \brief Apply the specified torque + public: Q_INVOKABLE void ApplyTorque(); + + /// \brief Apply the specified force and torque + public: Q_INVOKABLE void ApplyAll(); + + /// \internal + /// \brief Pointer to private data. + private: std::unique_ptr dataPtr; + }; +} +} + +#endif diff --git a/src/gui/plugins/apply_force_torque/ApplyForceTorque.qml b/src/gui/plugins/apply_force_torque/ApplyForceTorque.qml new file mode 100644 index 0000000000..762b68c863 --- /dev/null +++ b/src/gui/plugins/apply_force_torque/ApplyForceTorque.qml @@ -0,0 +1,251 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +import QtQuick 2.9 +import QtQuick.Controls 2.1 +import QtQuick.Layouts 1.3 +import "qrc:/qml" + +GridLayout { + columns: 8 + columnSpacing: 10 + Layout.minimumWidth: 350 + Layout.minimumHeight: 650 + anchors.fill: parent + anchors.leftMargin: 10 + anchors.rightMargin: 10 + + // Maximum value for GzSpinBoxes + property int maxValue: 1000000 + + // Minimum value for GzSpinBoxes + property int minValue: -1000000 + + // Precision of the GzSpinBoxes in decimal places + property int decimalPlaces: 2 + + // Step size of the GzSpinBoxes + property double step: 1.0 + + Label { + Layout.columnSpan: 8 + Layout.fillWidth: true + wrapMode: Text.WordWrap + id: frameText + text: "Forces and torques are given in link-fixed frame" + } + + Text { + Layout.columnSpan: 2 + id: modelText + color: "dimgrey" + text: qsTr("Model:") + } + + Text { + Layout.columnSpan: 6 + id: modelName + color: "dimgrey" + text: ApplyForceTorque.modelName + } + + Text { + Layout.columnSpan: 2 + id: linkText + color: "dimgrey" + text: qsTr("Link:") + } + + ComboBox { + Layout.columnSpan: 6 + id: linkCombo + Layout.fillWidth: true + model: ApplyForceTorque.linkNameList + currentIndex: ApplyForceTorque.linkIndex + onCurrentIndexChanged: { + ApplyForceTorque.linkIndex = currentIndex + } + } + + // Force + Text { + Layout.columnSpan: 8 + id: forceText + color: "dimgrey" + text: qsTr("Force (applied to the center of mass):") + } + + Label { + Layout.columnSpan: 2 + horizontalAlignment: Text.AlignRight + id: forceXText + color: "dimgrey" + text: qsTr("X (N)") + } + + GzSpinBox { + Layout.columnSpan: 6 + Layout.fillWidth: true + id: forceX + maximumValue: maxValue + minimumValue: minValue + value: 0 + decimals: decimalPlaces + stepSize: step + onValueChanged: ApplyForceTorque.UpdateForce( + forceX.value, forceY.value, forceZ.value) + } + + Label { + Layout.columnSpan: 2 + horizontalAlignment: Text.AlignRight + id: forceYText + color: "dimgrey" + text: qsTr("Y (N)") + } + + GzSpinBox { + Layout.columnSpan: 6 + Layout.fillWidth: true + id: forceY + maximumValue: maxValue + minimumValue: minValue + value: 0 + decimals: decimalPlaces + stepSize: step + onValueChanged: ApplyForceTorque.UpdateForce( + forceX.value,forceY.value, forceZ.value) + } + + Label { + Layout.columnSpan: 2 + horizontalAlignment: Text.AlignRight + id: forceZText + color: "dimgrey" + text: qsTr("Z (N)") + } + + GzSpinBox { + Layout.columnSpan: 6 + Layout.fillWidth: true + id: forceZ + maximumValue: maxValue + minimumValue: minValue + value: 0 + decimals: decimalPlaces + stepSize: step + onValueChanged: ApplyForceTorque.UpdateForce( + forceX.value, forceY.value, forceZ.value) + } + + Button { + text: qsTr("Apply Force") + Layout.columnSpan: 8 + Layout.fillWidth: true + onClicked: function() { + ApplyForceTorque.ApplyForce() + } + } + + // Torque + Text { + Layout.columnSpan: 8 + id: torqueText + color: "dimgrey" + text: qsTr("Torque:") + } + + Label { + Layout.columnSpan: 2 + horizontalAlignment: Text.AlignRight + id: torqueXText + color: "dimgrey" + text: qsTr("X (N.m)") + } + + GzSpinBox { + Layout.columnSpan: 6 + Layout.fillWidth: true + id: torqueX + maximumValue: maxValue + minimumValue: minValue + value: 0 + decimals: decimalPlaces + stepSize: step + onValueChanged: ApplyForceTorque.UpdateTorque( + torqueX.value,torqueY.value, torqueZ.value) + } + + Label { + Layout.columnSpan: 2 + horizontalAlignment: Text.AlignRight + id: torqueYText + color: "dimgrey" + text: qsTr("Y (N.m)") + } + + GzSpinBox { + Layout.columnSpan: 6 + Layout.fillWidth: true + id: torqueY + maximumValue: maxValue + minimumValue: minValue + value: 0 + decimals: decimalPlaces + stepSize: step + onValueChanged: ApplyForceTorque.UpdateTorque( + torqueX.value,torqueY.value, torqueZ.value) + } + + Label { + Layout.columnSpan: 2 + horizontalAlignment: Text.AlignRight + id: torqueZText + color: "dimgrey" + text: qsTr("Z (N.m)") + } + + GzSpinBox { + Layout.columnSpan: 6 + Layout.fillWidth: true + id: torqueZ + maximumValue: maxValue + minimumValue: minValue + value: 0 + decimals: decimalPlaces + stepSize: step + onValueChanged: ApplyForceTorque.UpdateTorque( + torqueX.value,torqueY.value, torqueZ.value) + } + + Button { + text: qsTr("Apply Torque") + Layout.columnSpan: 8 + Layout.fillWidth: true + onClicked: function() { + ApplyForceTorque.ApplyTorque() + } + } + + Button { + text: qsTr("Apply All") + Layout.columnSpan: 8 + Layout.fillWidth: true + onClicked: function() { + ApplyForceTorque.ApplyAll() + } + } +} diff --git a/src/gui/plugins/apply_force_torque/ApplyForceTorque.qrc b/src/gui/plugins/apply_force_torque/ApplyForceTorque.qrc new file mode 100644 index 0000000000..b95739311d --- /dev/null +++ b/src/gui/plugins/apply_force_torque/ApplyForceTorque.qrc @@ -0,0 +1,5 @@ + + + ApplyForceTorque.qml + + diff --git a/src/gui/plugins/apply_force_torque/CMakeLists.txt b/src/gui/plugins/apply_force_torque/CMakeLists.txt new file mode 100644 index 0000000000..a633ec6f47 --- /dev/null +++ b/src/gui/plugins/apply_force_torque/CMakeLists.txt @@ -0,0 +1,4 @@ +gz_add_gui_plugin(ApplyForceTorque + SOURCES ApplyForceTorque.cc + QT_HEADERS ApplyForceTorque.hh +) From f2ff574664574100989e3633e4debe16431fe00f Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Wed, 2 Aug 2023 14:29:51 -0500 Subject: [PATCH 20/31] Fix Github project automation for new project board (#2066) Signed-off-by: Addisu Z. Taddese --- .github/workflows/triage.yml | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/.github/workflows/triage.yml b/.github/workflows/triage.yml index 6f93ccd58f..2332244bf4 100644 --- a/.github/workflows/triage.yml +++ b/.github/workflows/triage.yml @@ -10,9 +10,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Add ticket to inbox - uses: technote-space/create-project-card-action@v1 + uses: actions/add-to-project@v0.5.0 with: - PROJECT: Core development - COLUMN: Inbox - GITHUB_TOKEN: ${{ secrets.TRIAGE_TOKEN }} - CHECK_ORG_PROJECT: true + project-url: https://github.com/orgs/gazebosim/projects/7 + github-token: ${{ secrets.TRIAGE_TOKEN }} From 0aadc81f0ccfb1f3b624b74b75a0edbd84a55733 Mon Sep 17 00:00:00 2001 From: Anton Bredenbeck <33020028+antbre@users.noreply.github.com> Date: Thu, 3 Aug 2023 16:00:52 +0200 Subject: [PATCH 21/31] Include contact force, normal, and depth in contact message (#2050) Previously the data contained by the ContactSensorPlugin did not include ExtraContactData. Now the message is also populated with this data. Now the EntityContactMap contains a deque of pairs of ContactPoint and ExtraContactData. That way the messages can be populated with Normals, Forces, and Depth. The force on body 2 is equal and opposite to the force on body 1. --------- Signed-off-by: Anton Bredenbeck Signed-off-by: Addisu Z. Taddese Co-authored-by: Addisu Z. Taddese --- src/systems/physics/Physics.cc | 66 ++++++++++++++---- test/integration/contact_system.cc | 93 +++++++++++++++++++++++++ test/worlds/contact_extra_data.sdf | 105 +++++++++++++++++++++++++++++ 3 files changed, 251 insertions(+), 13 deletions(-) create mode 100644 test/worlds/contact_extra_data.sdf diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index b81f17330a..8cd8991eed 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -31,6 +31,7 @@ #include #include #include +#include #include #include @@ -3742,12 +3743,21 @@ void PhysicsPrivate::UpdateCollisions(EntityComponentManager &_ecm) return; } + // Using ExtraContactData to expose contact Norm, Force & Depth + using Policy = physics::FeaturePolicy3d; + using GCFeature = physics::GetContactsFromLastStepFeature; + using ExtraContactData = GCFeature::ExtraContactDataT; + + // A contact is described by a contactPoint and the corresponding + // extraContactData which we bundle in a pair data structure + using ContactData = std::pair; // Each contact object we get from gz-physics contains the EntityPtrs of the // two colliding entities and other data about the contact such as the - // position. This map groups contacts so that it is easy to query all the + // position and extra contact date (wrench, normal and penetration depth). + // This map groups contacts so that it is easy to query all the // contacts of one entity. - using EntityContactMap = std::unordered_map>; + using EntityContactMap = std::unordered_map>; // This data structure is essentially a mapping between a pair of entities and // a list of pointers to their contact object. We use a map inside a map to @@ -3761,16 +3771,19 @@ void PhysicsPrivate::UpdateCollisions(EntityComponentManager &_ecm) for (const auto &contactComposite : allContacts) { - const auto &contact = contactComposite.Get(); - auto coll1Entity = - this->entityCollisionMap.GetByPhysicsId(contact.collision1->EntityID()); - auto coll2Entity = - this->entityCollisionMap.GetByPhysicsId(contact.collision2->EntityID()); + const auto &contactPoint = + contactComposite.Get(); + const auto &extraContactData = contactComposite.Query(); + auto coll1Entity = this->entityCollisionMap.GetByPhysicsId( + contactPoint.collision1->EntityID()); + auto coll2Entity = this->entityCollisionMap.GetByPhysicsId( + contactPoint.collision2->EntityID()); if (coll1Entity != kNullEntity && coll2Entity != kNullEntity) { - entityContactMap[coll1Entity][coll2Entity].push_back(&contact); - entityContactMap[coll2Entity][coll1Entity].push_back(&contact); + ContactData data = std::make_pair(&contactPoint, extraContactData); + entityContactMap[coll1Entity][coll2Entity].push_back(data); + entityContactMap[coll2Entity][coll1Entity].push_back(data); } } @@ -3811,9 +3824,36 @@ void PhysicsPrivate::UpdateCollisions(EntityComponentManager &_ecm) for (const auto &contact : contactData) { auto *position = contactMsg->add_position(); - position->set_x(contact->point.x()); - position->set_y(contact->point.y()); - position->set_z(contact->point.z()); + position->set_x(contact.first->point.x()); + position->set_y(contact.first->point.y()); + position->set_z(contact.first->point.z()); + + // Check if the extra contact data exists, + // since not all physics engines support it. + // Then, fill the msg with extra data. + if(contact.second != nullptr) + { + auto *normal = contactMsg->add_normal(); + normal->set_x(contact.second->normal.x()); + normal->set_y(contact.second->normal.y()); + normal->set_z(contact.second->normal.z()); + + auto *wrench = contactMsg->add_wrench(); + auto *body1Wrench = wrench->mutable_body_1_wrench(); + auto *body1Force = body1Wrench->mutable_force(); + body1Force->set_x(contact.second->force.x()); + body1Force->set_y(contact.second->force.y()); + body1Force->set_z(contact.second->force.z()); + + // The force on the second body is equal and opposite + auto *body2Wrench = wrench->mutable_body_2_wrench(); + auto *body2Force = body2Wrench->mutable_force(); + body2Force->set_x(-contact.second->force.x()); + body2Force->set_y(-contact.second->force.y()); + body2Force->set_z(-contact.second->force.z()); + + contactMsg->add_depth(contact.second->depth); + } } } diff --git a/test/integration/contact_system.cc b/test/integration/contact_system.cc index 10431e496e..2ac7694388 100644 --- a/test/integration/contact_system.cc +++ b/test/integration/contact_system.cc @@ -272,6 +272,99 @@ TEST_F(ContactSystemTest, } } +///////////////////////////////////////////////// +// The test checks that contacts are published with +// the correct extraContactData +TEST_F(ContactSystemTest, + GZ_UTILS_TEST_DISABLED_ON_WIN32(ExtraContactData)) +{ + // Start server + ServerConfig serverConfig; + const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + + "/test/worlds/contact_extra_data.sdf"; + serverConfig.SetSdfFile(sdfFile); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + using namespace std::chrono_literals; + server.SetUpdatePeriod(1ns); + + std::mutex contactMutex; + std::vector contactMsgs; + + auto contactCb = [&](const msgs::Contacts &_msg) -> void + { + std::lock_guard lock(contactMutex); + contactMsgs.push_back(_msg); + }; + + // subscribe to contacts topic + transport::Node node; + // Have to create an lvalue here for Node::Subscribe to work. + auto callbackFunc = std::function(contactCb); + node.Subscribe("/test_extra_collision_data", callbackFunc); + + // Run server for 10 iters to ensure + // contact solver has converged + size_t iters = 10; + server.Run(true, iters, false); + { + std::lock_guard lock(contactMutex); + ASSERT_GE(contactMsgs.size(), 1u); + } + + { + std::lock_guard lock(contactMutex); + const auto &lastContacts = contactMsgs.back(); + EXPECT_EQ(1, lastContacts.contact_size()); + + // The sphere weighs 1kg and gravity is set to 9.81 m/s^2 + // Hence the contact force should be m*g = 9.81 N + // along the z-axis. The force on body 2 should be equal + // and opposite. + // All torques should be zero. + // The normal should align with the world z-axis + for (const auto &contact : lastContacts.contact()) + { + ASSERT_EQ(1, contact.wrench_size()); + ASSERT_EQ(1, contact.normal_size()); + + EXPECT_NEAR(0.0, contact.wrench().Get(0).body_1_wrench().force().x(), + 5e-2); + EXPECT_NEAR(0.0, contact.wrench().Get(0).body_1_wrench().force().y(), + 5e-2); + EXPECT_NEAR(9.81, contact.wrench().Get(0).body_1_wrench().force().z(), + 5e-2); + EXPECT_NEAR(0.0, contact.wrench().Get(0).body_1_wrench().torque().x(), + 5e-2); + EXPECT_NEAR(0.0, contact.wrench().Get(0).body_1_wrench().torque().y(), + 5e-2); + EXPECT_NEAR(0.0, contact.wrench().Get(0).body_1_wrench().torque().z(), + 5e-2); + + EXPECT_NEAR(0.0, contact.wrench().Get(0).body_2_wrench().force().x(), + 5e-2); + EXPECT_NEAR(0.0, contact.wrench().Get(0).body_2_wrench().force().y(), + 5e-2); + EXPECT_NEAR(-9.81, contact.wrench().Get(0).body_2_wrench().force().z(), + 5e-2); + EXPECT_NEAR(0.0, contact.wrench().Get(0).body_2_wrench().torque().x(), + 5e-2); + EXPECT_NEAR(0.0, contact.wrench().Get(0).body_2_wrench().torque().y(), + 5e-2); + EXPECT_NEAR(0.0, contact.wrench().Get(0).body_2_wrench().torque().z(), + 5e-2); + + EXPECT_NEAR(0.0, contact.normal().Get(0).x(), 5e-2); + EXPECT_NEAR(0.0, contact.normal().Get(0).y(), 5e-2); + EXPECT_NEAR(1.0, contact.normal().Get(0).z(), 5e-2); + + } + } +} + TEST_F(ContactSystemTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(RemoveContactSensor)) { diff --git a/test/worlds/contact_extra_data.sdf b/test/worlds/contact_extra_data.sdf new file mode 100644 index 0000000000..def44661df --- /dev/null +++ b/test/worlds/contact_extra_data.sdf @@ -0,0 +1,105 @@ + + + + + 0 + + + + + + + + 0 0 -9.81 + + + true + + + + + 0 0 1 + 1 1 + + + + + + + + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + + 1 + 0 + 0 + 1 + 0 + 1 + + + false + + 0 0 0 0 -0 0 + false + + + + 0 0 0.5 0 0.0 0 + + 1.0 + + 0.4 + 0.4 + 0.4 + + + + + + + 1.0 + + + + + + + 1.0 + + + + + + collision_sphere + /test_extra_collision_data + + 1 + 1000 + + + + + From f3c5e2309676e35883b3a30967b1628b12f8b39f Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Thu, 3 Aug 2023 13:35:42 -0500 Subject: [PATCH 22/31] Remove unnecessary headers to fix ABI checker (#2070) Signed-off-by: Addisu Z. Taddese --- include/ignition/gazebo/ign/gazebo/Export.hh | 19 ------------------- .../ignition/gazebo/ignition/gazebo/Export.hh | 19 ------------------- 2 files changed, 38 deletions(-) delete mode 100644 include/ignition/gazebo/ign/gazebo/Export.hh delete mode 100644 include/ignition/gazebo/ignition/gazebo/Export.hh diff --git a/include/ignition/gazebo/ign/gazebo/Export.hh b/include/ignition/gazebo/ign/gazebo/Export.hh deleted file mode 100644 index a851891bca..0000000000 --- a/include/ignition/gazebo/ign/gazebo/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include diff --git a/include/ignition/gazebo/ignition/gazebo/Export.hh b/include/ignition/gazebo/ignition/gazebo/Export.hh deleted file mode 100644 index a851891bca..0000000000 --- a/include/ignition/gazebo/ignition/gazebo/Export.hh +++ /dev/null @@ -1,19 +0,0 @@ -/* - * Copyright (C) 2022 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#include -#include From eec680a6dc50aa4d557d549afc5ad7fbb14e2722 Mon Sep 17 00:00:00 2001 From: jrutgeer Date: Fri, 4 Aug 2023 02:52:26 +0200 Subject: [PATCH 23/31] Avoid nullptr dereference if TouchPlugin is not attached to a model entity. (#2069) * Avoid nullptr dereference of sdfConfig if plugin is not attached to a model. Skip PreUpdate if the configuration was not successful. Signed-off-by: Johan Rutgeerts * Changed documentation to describe more clearly what the plugin actually does. Signed-off-by: Johan Rutgeerts * Fix codecheck error Signed-off-by: Addisu Z. Taddese --------- Signed-off-by: Johan Rutgeerts Signed-off-by: Addisu Z. Taddese Co-authored-by: Addisu Z. Taddese --- src/systems/touch_plugin/TouchPlugin.cc | 9 ++++----- src/systems/touch_plugin/TouchPlugin.hh | 26 ++++++++++++++----------- 2 files changed, 19 insertions(+), 16 deletions(-) diff --git a/src/systems/touch_plugin/TouchPlugin.cc b/src/systems/touch_plugin/TouchPlugin.cc index 85090e560e..a624e75e83 100644 --- a/src/systems/touch_plugin/TouchPlugin.cc +++ b/src/systems/touch_plugin/TouchPlugin.cc @@ -103,7 +103,7 @@ class gz::sim::systems::TouchPluginPrivate public: bool initialized{false}; /// \brief Set during Load to true if the configuration for the plugin is - /// valid and the post update can run + /// valid and the pre and post update can run public: bool validConfig{false}; /// \brief Whether the plugin is enabled. @@ -373,7 +373,7 @@ void TouchPlugin::Configure(const Entity &_entity, void TouchPlugin::PreUpdate(const UpdateInfo &, EntityComponentManager &_ecm) { GZ_PROFILE("TouchPlugin::PreUpdate"); - if (!this->dataPtr->initialized) + if ((!this->dataPtr->initialized) && this->dataPtr->sdfConfig) { // We call Load here instead of Configure because we can't be guaranteed // that all entities have been created when Configure is called @@ -381,9 +381,8 @@ void TouchPlugin::PreUpdate(const UpdateInfo &, EntityComponentManager &_ecm) this->dataPtr->initialized = true; } - // This is not an "else" because "initialized" can be set in the if block - // above - if (this->dataPtr->initialized) + // If Load() was successful, validConfig is set to true + if (this->dataPtr->validConfig) { // Update target entities when new collisions are added std::vector potentialEntities; diff --git a/src/systems/touch_plugin/TouchPlugin.hh b/src/systems/touch_plugin/TouchPlugin.hh index 189bcdbc75..27a4d848aa 100644 --- a/src/systems/touch_plugin/TouchPlugin.hh +++ b/src/systems/touch_plugin/TouchPlugin.hh @@ -32,21 +32,25 @@ namespace systems // Forward declaration class TouchPluginPrivate; - /// \brief Plugin which checks if a model has touched some specific target - /// for a given time continuously and exclusively. After the touch is - /// completed, the plugin is disabled. It can be re-enabled through an - /// Gazebo Transport service. + /// \brief Plugin which publishes a message if the model it is attached + /// to has touched one or more specified targets continuously during a + /// given time. /// - /// It requires that contact sensors be placed in at least one link on the - /// model on which this plugin is attached. + /// After publishing, the plugin is disabled. It can be re-enabled through + /// a Gazebo Transport service call. + /// + /// The plugin requires that a contact sensors is placed in at least one + /// link on the model on which this plugin is attached. /// /// Parameters: /// - /// - `` Scoped name of the desired collision entity that is checked - /// to see if it's touching this model. This can be a substring - /// of the desired collision name so we match more than one - /// collision. For example, using the name of a model will match - /// all its collisions. + /// - `` Name, or substring of a name, that identifies the target + /// collision entity/entities. + /// This value is searched in the scoped name of all collision + /// entities, so it can possibly match more than one collision. + /// For example, using the name of a model will match all of its + /// collisions (scoped name + /// /model_name/link_name/collision_name). /// /// - `