From c7e25be28252a3e308098db205381871757b67f1 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Sun, 29 May 2022 11:03:52 -0700 Subject: [PATCH] ign -> gz: namespaces, .gz directory (#1496) Signed-off-by: methylDragon Signed-off-by: Louise Poubel Co-authored-by: Louise Poubel --- .github/ci/after_make.sh | 2 +- .github/workflows/ci.yml | 2 +- CMakeLists.txt | 10 +- CODE_OF_CONDUCT.md | 2 +- CONTRIBUTING.md | 2 +- Changelog.md | 1980 ++++++++--------- Migration.md | 64 +- NEWS | 2 +- README.md | 56 +- api.md.in | 10 +- doc/architecture_design.md | 7 +- docker/README.md | 26 +- docker/scripts/build_ign.sh | 2 +- docker/scripts/upload_json_benchmark.sh | 4 +- examples/plugin/command_actor/CommandActor.cc | 40 +- examples/plugin/command_actor/CommandActor.hh | 22 +- .../plugin/command_actor/command_actor.sdf | 4 +- .../custom_component/CustomComponentPlugin.cc | 2 +- .../custom_component/CustomComponentPlugin.hh | 20 +- .../custom_sensor_system/CMakeLists.txt | 2 +- .../custom_sensor_system/OdometerSystem.cc | 44 +- .../custom_sensor_system/OdometerSystem.hh | 18 +- .../plugin/custom_sensor_system/README.md | 4 +- .../plugin/custom_sensor_system/odometer.sdf | 8 +- .../gui_system_plugin/GuiSystemPlugin.cc | 16 +- .../gui_system_plugin/GuiSystemPlugin.hh | 12 +- examples/plugin/gui_system_plugin/README.md | 4 +- examples/plugin/hello_world/HelloWorld.cc | 12 +- examples/plugin/hello_world/HelloWorld.hh | 8 +- examples/plugin/rendering_plugins/README.md | 2 +- .../rendering_plugins/RenderingGuiPlugin.cc | 30 +- .../rendering_plugins/RenderingGuiPlugin.hh | 8 +- .../RenderingServerPlugin.cc | 36 +- .../RenderingServerPlugin.hh | 22 +- .../rendering_plugins/rendering_plugins.sdf | 4 +- .../reset_plugin/JointPositionRandomizer.cc | 22 +- examples/plugin/reset_plugin/README.md | 2 +- .../joint_position_randomizer.sdf | 8 +- examples/plugin/system_plugin/SampleSystem.cc | 8 +- examples/plugin/system_plugin/SampleSystem.hh | 28 +- .../plugin/system_plugin/SampleSystem2.cc | 20 +- 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 +- examples/scripts/log_video_recorder/README.md | 2 +- .../log_video_recorder/log_video_recorder.sdf | 6 +- examples/scripts/python_api/README.md | 4 +- examples/scripts/python_api/gravity.sdf | 2 +- examples/scripts/python_api/testFixture.py | 2 +- examples/standalone/comms/publisher.cc | 8 +- examples/standalone/custom_server/README.md | 2 +- .../standalone/custom_server/custom_server.cc | 6 +- examples/standalone/each_performance/each.cc | 4 +- .../entity_creation/entity_creation.cc | 36 +- .../standalone/external_ecm/external_ecm.cc | 16 +- examples/standalone/gtest_setup/command.sdf | 4 +- .../standalone/gtest_setup/command_TEST.cc | 36 +- examples/standalone/gtest_setup/gravity.sdf | 2 +- .../standalone/gtest_setup/gravity_TEST.cc | 24 +- examples/standalone/joy_to_twist/README.md | 6 +- .../standalone/joy_to_twist/joy_to_twist.cc | 42 +- examples/standalone/joystick/CMakeLists.txt | 2 +- examples/standalone/joystick/README.md | 6 +- examples/standalone/joystick/joystick.cc | 14 +- examples/standalone/keyboard/README.md | 2 +- examples/standalone/keyboard/keyboard.cc | 26 +- .../standalone/light_control/light_control.cc | 42 +- .../multi_lrauv_race/multi_lrauv_race.cc | 18 +- .../scene_requester/scene_requester.cc | 6 +- examples/worlds/3k_shapes.sdf | 6 +- examples/worlds/ackermann_steering.sdf | 12 +- examples/worlds/actor.sdf | 8 +- examples/worlds/actor_crowd.sdf | 6 +- examples/worlds/actors_population.sdf.erb | 6 +- examples/worlds/apply_joint_force.sdf | 12 +- examples/worlds/auv_controls.sdf | 24 +- examples/worlds/breadcrumbs.sdf | 18 +- examples/worlds/buoyancy.sdf | 22 +- examples/worlds/buoyancy_engine.sdf | 22 +- examples/worlds/camera_sensor.sdf | 8 +- .../camera_video_record_dbl_pendulum.sdf | 14 +- examples/worlds/collada_world_exporter.sdf | 2 +- examples/worlds/contact_sensor.sdf | 10 +- examples/worlds/conveyor.sdf | 26 +- examples/worlds/debug_shapes.sdf | 6 +- examples/worlds/default.sdf | 2 +- examples/worlds/depth_camera_sensor.sdf | 6 +- examples/worlds/detachable_joint.sdf | 22 +- examples/worlds/diff_drive.sdf | 16 +- examples/worlds/diff_drive_skid.sdf | 12 +- examples/worlds/elevator.sdf | 10 +- examples/worlds/empty.sdf | 26 +- examples/worlds/empty_gui.sdf | 2 +- examples/worlds/follow_actor.sdf | 14 +- examples/worlds/fuel.sdf | 8 +- examples/worlds/fuel_textured_mesh.sdf | 10 +- .../worlds/gpu_lidar_retro_values_sensor.sdf | 6 +- examples/worlds/gpu_lidar_sensor.sdf | 6 +- examples/worlds/graded_buoyancy.sdf | 10 +- examples/worlds/grid.sdf | 8 +- examples/worlds/import_mesh.sdf | 8 +- examples/worlds/joint_controller.sdf | 18 +- examples/worlds/joint_position_controller.sdf | 12 +- .../worlds/joint_trajectory_controller.sdf | 18 +- examples/worlds/kinetic_energy_monitor.sdf | 10 +- examples/worlds/levels.sdf | 18 +- examples/worlds/levels_no_performers.sdf | 24 +- examples/worlds/lift_drag.sdf | 18 +- examples/worlds/lift_drag_battery.sdf | 20 +- examples/worlds/lift_drag_nested.sdf | 16 +- examples/worlds/lights.sdf | 6 +- examples/worlds/linear_battery_demo.sdf | 24 +- examples/worlds/log_record_dbl_pendulum.sdf | 16 +- examples/worlds/log_record_keyboard.sdf | 18 +- examples/worlds/log_record_resources.sdf | 14 +- examples/worlds/log_record_shapes.sdf | 16 +- .../worlds/logical_audio_sensor_plugin.sdf | 18 +- examples/worlds/logical_camera_sensor.sdf | 10 +- examples/worlds/mecanum_drive.sdf | 16 +- examples/worlds/minimal_scene.sdf | 2 +- examples/worlds/model_photo_shoot.sdf | 8 +- examples/worlds/multi_lrauv_race.sdf | 48 +- .../worlds/multicopter_velocity_control.sdf | 44 +- examples/worlds/nested_model.sdf | 6 +- .../worlds/optical_tactile_sensor_plugin.sdf | 16 +- examples/worlds/particle_emitter.sdf | 14 +- examples/worlds/pendulum_links.sdf | 14 +- examples/worlds/perfect_comms.sdf | 14 +- examples/worlds/performer_detector.sdf | 16 +- examples/worlds/plane_propeller_demo.sdf | 28 +- examples/worlds/pose_publisher.sdf | 10 +- examples/worlds/quadcopter.sdf | 20 +- examples/worlds/rf_comms.sdf | 14 +- examples/worlds/rolling_shapes.sdf | 6 +- examples/worlds/segmentation_camera.sdf | 26 +- examples/worlds/sensors.sdf | 18 +- examples/worlds/sensors_demo.sdf | 8 +- examples/worlds/shader_param.sdf | 8 +- examples/worlds/shapes.sdf | 2 +- examples/worlds/shapes_bitmask.sdf | 6 +- examples/worlds/shapes_population.sdf.erb | 6 +- examples/worlds/skid_steer_mecanum.sdf | 12 +- examples/worlds/sky.sdf | 8 +- examples/worlds/spaces.sdf | 6 +- examples/worlds/spherical_coordinates.sdf | 20 +- examples/worlds/thermal_camera.sdf | 12 +- examples/worlds/touch_plugin.sdf | 12 +- examples/worlds/track_drive.sdf | 18 +- examples/worlds/tracked_vehicle_simple.sdf | 74 +- examples/worlds/trajectory_follower.sdf | 18 +- examples/worlds/triggered_publisher.sdf | 40 +- .../worlds/trisphere_cycle_wheel_slip.sdf | 12 +- examples/worlds/tunnel.sdf | 42 +- examples/worlds/velocity_control.sdf | 16 +- examples/worlds/video_record_dbl_pendulum.sdf | 6 +- examples/worlds/visibility.sdf | 8 +- examples/worlds/visualize_contacts.sdf | 8 +- examples/worlds/visualize_lidar.sdf | 8 +- examples/worlds/wide_angle_camera.sdf | 8 +- examples/worlds/wind.sdf | 10 +- examples/worlds/world_joint.sdf | 6 +- include/gz/sim/Conversions.hh | 24 +- include/gz/sim/Entity.hh | 12 +- include/gz/sim/EntityComponentManager.hh | 34 +- include/gz/sim/EventManager.hh | 24 +- include/gz/sim/Events.hh | 24 +- include/gz/sim/Link.hh | 28 +- include/gz/sim/Model.hh | 28 +- include/gz/sim/Primitives.hh | 26 +- include/gz/sim/SdfEntityCreator.hh | 12 +- include/gz/sim/Server.hh | 34 +- include/gz/sim/ServerConfig.hh | 20 +- include/gz/sim/System.hh | 10 +- include/gz/sim/SystemLoader.hh | 16 +- include/gz/sim/SystemPluginPtr.hh | 10 +- include/gz/sim/TestFixture.hh | 22 +- include/gz/sim/Types.hh | 12 +- include/gz/sim/Util.hh | 52 +- include/gz/sim/World.hh | 30 +- include/gz/sim/comms/Broker.hh | 22 +- include/gz/sim/comms/ICommsModel.hh | 22 +- include/gz/sim/comms/MsgManager.hh | 14 +- include/gz/sim/components/Actor.hh | 6 +- include/gz/sim/components/Actuators.hh | 6 +- .../gz/sim/components/AirPressureSensor.hh | 6 +- include/gz/sim/components/Altimeter.hh | 6 +- .../gz/sim/components/AngularAcceleration.hh | 10 +- include/gz/sim/components/AngularVelocity.hh | 10 +- .../gz/sim/components/AngularVelocityCmd.hh | 10 +- include/gz/sim/components/Atmosphere.hh | 6 +- include/gz/sim/components/AxisAlignedBox.hh | 10 +- include/gz/sim/components/BatterySoC.hh | 6 +- include/gz/sim/components/Camera.hh | 6 +- include/gz/sim/components/CanonicalLink.hh | 6 +- include/gz/sim/components/CastShadows.hh | 6 +- include/gz/sim/components/CenterOfVolume.hh | 6 +- include/gz/sim/components/ChildLinkName.hh | 6 +- include/gz/sim/components/Collision.hh | 6 +- include/gz/sim/components/Component.hh | 20 +- include/gz/sim/components/ContactSensor.hh | 6 +- .../gz/sim/components/ContactSensorData.hh | 6 +- include/gz/sim/components/CustomSensor.hh | 6 +- include/gz/sim/components/DepthCamera.hh | 6 +- include/gz/sim/components/DetachableJoint.hh | 6 +- .../sim/components/ExternalWorldWrenchCmd.hh | 8 +- include/gz/sim/components/Factory.hh | 30 +- include/gz/sim/components/ForceTorque.hh | 6 +- include/gz/sim/components/Geometry.hh | 6 +- include/gz/sim/components/GpuLidar.hh | 6 +- include/gz/sim/components/Gravity.hh | 6 +- include/gz/sim/components/HaltMotion.hh | 6 +- include/gz/sim/components/Imu.hh | 6 +- include/gz/sim/components/Inertial.hh | 6 +- include/gz/sim/components/Joint.hh | 6 +- include/gz/sim/components/JointAxis.hh | 6 +- .../gz/sim/components/JointEffortLimitsCmd.hh | 10 +- include/gz/sim/components/JointForce.hh | 6 +- include/gz/sim/components/JointForceCmd.hh | 6 +- include/gz/sim/components/JointPosition.hh | 6 +- .../sim/components/JointPositionLimitsCmd.hh | 10 +- .../gz/sim/components/JointPositionReset.hh | 6 +- .../sim/components/JointTransmittedWrench.hh | 6 +- include/gz/sim/components/JointType.hh | 6 +- include/gz/sim/components/JointVelocity.hh | 6 +- include/gz/sim/components/JointVelocityCmd.hh | 6 +- .../sim/components/JointVelocityLimitsCmd.hh | 10 +- .../gz/sim/components/JointVelocityReset.hh | 6 +- include/gz/sim/components/LaserRetro.hh | 6 +- include/gz/sim/components/Level.hh | 6 +- include/gz/sim/components/LevelBuffer.hh | 6 +- include/gz/sim/components/LevelEntityNames.hh | 6 +- include/gz/sim/components/Lidar.hh | 6 +- include/gz/sim/components/Light.hh | 6 +- include/gz/sim/components/LightCmd.hh | 8 +- include/gz/sim/components/LightType.hh | 6 +- .../gz/sim/components/LinearAcceleration.hh | 10 +- include/gz/sim/components/LinearVelocity.hh | 10 +- .../gz/sim/components/LinearVelocityCmd.hh | 10 +- .../gz/sim/components/LinearVelocitySeed.hh | 10 +- include/gz/sim/components/Link.hh | 6 +- .../sim/components/LogPlaybackStatistics.hh | 8 +- include/gz/sim/components/LogicalAudio.hh | 10 +- include/gz/sim/components/LogicalCamera.hh | 6 +- include/gz/sim/components/MagneticField.hh | 6 +- include/gz/sim/components/Magnetometer.hh | 6 +- include/gz/sim/components/Material.hh | 6 +- include/gz/sim/components/Model.hh | 10 +- include/gz/sim/components/Name.hh | 6 +- include/gz/sim/components/NavSat.hh | 6 +- include/gz/sim/components/ParentEntity.hh | 8 +- include/gz/sim/components/ParentLinkName.hh | 6 +- include/gz/sim/components/ParticleEmitter.hh | 6 +- include/gz/sim/components/Performer.hh | 6 +- .../gz/sim/components/PerformerAffinity.hh | 6 +- include/gz/sim/components/PerformerLevels.hh | 6 +- include/gz/sim/components/Physics.hh | 6 +- include/gz/sim/components/PhysicsCmd.hh | 6 +- .../gz/sim/components/PhysicsEnginePlugin.hh | 6 +- include/gz/sim/components/Pose.hh | 18 +- include/gz/sim/components/PoseCmd.hh | 8 +- include/gz/sim/components/Recreate.hh | 6 +- .../sim/components/RenderEngineGuiPlugin.hh | 6 +- .../components/RenderEngineServerHeadless.hh | 6 +- .../components/RenderEngineServerPlugin.hh | 6 +- include/gz/sim/components/RgbdCamera.hh | 6 +- include/gz/sim/components/Scene.hh | 6 +- .../gz/sim/components/SegmentationCamera.hh | 6 +- include/gz/sim/components/SelfCollide.hh | 6 +- include/gz/sim/components/SemanticLabel.hh | 6 +- include/gz/sim/components/Sensor.hh | 6 +- include/gz/sim/components/Serialization.hh | 28 +- .../gz/sim/components/SlipComplianceCmd.hh | 6 +- include/gz/sim/components/SourceFilePath.hh | 6 +- .../gz/sim/components/SphericalCoordinates.hh | 6 +- include/gz/sim/components/Static.hh | 6 +- include/gz/sim/components/Temperature.hh | 6 +- include/gz/sim/components/TemperatureRange.hh | 6 +- include/gz/sim/components/ThermalCamera.hh | 6 +- include/gz/sim/components/ThreadPitch.hh | 6 +- include/gz/sim/components/Transparency.hh | 6 +- include/gz/sim/components/Visibility.hh | 6 +- include/gz/sim/components/Visual.hh | 8 +- include/gz/sim/components/VisualCmd.hh | 8 +- include/gz/sim/components/Volume.hh | 6 +- include/gz/sim/components/WheelSlipCmd.hh | 8 +- include/gz/sim/components/WideAngleCamera.hh | 6 +- include/gz/sim/components/Wind.hh | 6 +- include/gz/sim/components/WindMode.hh | 6 +- include/gz/sim/components/World.hh | 6 +- include/gz/sim/components/components.hh.in | 4 +- include/gz/sim/config.hh.in | 52 +- include/gz/sim/detail/BaseView.hh | 20 +- include/gz/sim/detail/ComponentStorageBase.hh | 18 +- .../gz/sim/detail/EntityComponentManager.hh | 20 +- include/gz/sim/detail/View.hh | 20 +- include/gz/sim/gui/Gui.hh | 20 +- include/gz/sim/gui/GuiEvents.hh | 38 +- include/gz/sim/gui/GuiSystem.hh | 14 +- include/gz/sim/physics/Events.hh | 18 +- include/gz/sim/playback_server.config | 4 +- include/gz/sim/rendering/Events.hh | 28 +- include/gz/sim/rendering/MarkerManager.hh | 14 +- include/gz/sim/rendering/RenderUtil.hh | 16 +- include/gz/sim/rendering/SceneManager.hh | 14 +- include/gz/sim/server.config | 6 +- include/ignition/gazebo/Conversions.hh | 1 + include/ignition/gazebo/Entity.hh | 1 + .../ignition/gazebo/EntityComponentManager.hh | 1 + include/ignition/gazebo/EventManager.hh | 1 + include/ignition/gazebo/Events.hh | 1 + include/ignition/gazebo/Export.hh | 1 + include/ignition/gazebo/Link.hh | 1 + include/ignition/gazebo/Model.hh | 1 + include/ignition/gazebo/Primitives.hh | 1 + include/ignition/gazebo/SdfEntityCreator.hh | 1 + include/ignition/gazebo/Server.hh | 1 + include/ignition/gazebo/ServerConfig.hh | 1 + include/ignition/gazebo/System.hh | 1 + include/ignition/gazebo/SystemLoader.hh | 1 + include/ignition/gazebo/SystemPluginPtr.hh | 1 + include/ignition/gazebo/TestFixture.hh | 1 + include/ignition/gazebo/Types.hh | 1 + include/ignition/gazebo/Util.hh | 1 + include/ignition/gazebo/World.hh | 1 + .../ackermann-steering-system/Export.hh | 1 + .../gazebo/air-pressure-system/Export.hh | 1 + .../gazebo/altimeter-system/Export.hh | 1 + .../gazebo/apply-joint-force-system/Export.hh | 1 + .../gazebo/breadcrumbs-system/Export.hh | 1 + .../gazebo/buoyancy-engine-system/Export.hh | 1 + .../ignition/gazebo/buoyancy-system/Export.hh | 1 + .../camera-video-recorder-system/Export.hh | 1 + .../collada-world-exporter-system/Export.hh | 1 + .../gazebo/comms-endpoint-system/Export.hh | 1 + include/ignition/gazebo/comms/Broker.hh | 1 + include/ignition/gazebo/comms/ICommsModel.hh | 1 + include/ignition/gazebo/comms/MsgManager.hh | 1 + include/ignition/gazebo/components.hh | 1 + include/ignition/gazebo/components/Actor.hh | 1 + .../ignition/gazebo/components/Actuators.hh | 1 + .../gazebo/components/AirPressureSensor.hh | 1 + .../ignition/gazebo/components/Altimeter.hh | 1 + .../gazebo/components/AngularAcceleration.hh | 1 + .../gazebo/components/AngularVelocity.hh | 1 + .../gazebo/components/AngularVelocityCmd.hh | 1 + .../ignition/gazebo/components/Atmosphere.hh | 1 + .../gazebo/components/AxisAlignedBox.hh | 1 + .../ignition/gazebo/components/BatterySoC.hh | 1 + include/ignition/gazebo/components/Camera.hh | 1 + .../gazebo/components/CanonicalLink.hh | 1 + .../ignition/gazebo/components/CastShadows.hh | 1 + .../gazebo/components/CenterOfVolume.hh | 1 + .../gazebo/components/ChildLinkName.hh | 1 + .../ignition/gazebo/components/Collision.hh | 1 + .../ignition/gazebo/components/Component.hh | 1 + .../gazebo/components/ContactSensor.hh | 1 + .../gazebo/components/ContactSensorData.hh | 1 + .../gazebo/components/CustomSensor.hh | 1 + .../ignition/gazebo/components/DepthCamera.hh | 1 + .../gazebo/components/DetachableJoint.hh | 1 + .../components/ExternalWorldWrenchCmd.hh | 1 + include/ignition/gazebo/components/Factory.hh | 1 + .../ignition/gazebo/components/ForceTorque.hh | 1 + .../ignition/gazebo/components/Geometry.hh | 1 + .../ignition/gazebo/components/GpuLidar.hh | 1 + include/ignition/gazebo/components/Gravity.hh | 1 + .../ignition/gazebo/components/HaltMotion.hh | 1 + include/ignition/gazebo/components/Imu.hh | 1 + .../ignition/gazebo/components/Inertial.hh | 1 + include/ignition/gazebo/components/Joint.hh | 1 + .../ignition/gazebo/components/JointAxis.hh | 1 + .../gazebo/components/JointEffortLimitsCmd.hh | 1 + .../ignition/gazebo/components/JointForce.hh | 1 + .../gazebo/components/JointForceCmd.hh | 1 + .../gazebo/components/JointPosition.hh | 1 + .../components/JointPositionLimitsCmd.hh | 1 + .../gazebo/components/JointPositionReset.hh | 1 + .../components/JointTransmittedWrench.hh | 1 + .../ignition/gazebo/components/JointType.hh | 1 + .../gazebo/components/JointVelocity.hh | 1 + .../gazebo/components/JointVelocityCmd.hh | 1 + .../components/JointVelocityLimitsCmd.hh | 1 + .../gazebo/components/JointVelocityReset.hh | 1 + .../ignition/gazebo/components/LaserRetro.hh | 1 + include/ignition/gazebo/components/Level.hh | 1 + .../ignition/gazebo/components/LevelBuffer.hh | 1 + .../gazebo/components/LevelEntityNames.hh | 1 + include/ignition/gazebo/components/Lidar.hh | 1 + include/ignition/gazebo/components/Light.hh | 1 + .../ignition/gazebo/components/LightCmd.hh | 1 + .../ignition/gazebo/components/LightType.hh | 1 + .../gazebo/components/LinearAcceleration.hh | 1 + .../gazebo/components/LinearVelocity.hh | 1 + .../gazebo/components/LinearVelocityCmd.hh | 1 + .../gazebo/components/LinearVelocitySeed.hh | 1 + include/ignition/gazebo/components/Link.hh | 1 + .../components/LogPlaybackStatistics.hh | 1 + .../gazebo/components/LogicalAudio.hh | 1 + .../gazebo/components/LogicalCamera.hh | 1 + .../gazebo/components/MagneticField.hh | 1 + .../gazebo/components/Magnetometer.hh | 1 + .../ignition/gazebo/components/Material.hh | 1 + include/ignition/gazebo/components/Model.hh | 1 + include/ignition/gazebo/components/Name.hh | 1 + include/ignition/gazebo/components/NavSat.hh | 1 + .../gazebo/components/ParentEntity.hh | 1 + .../gazebo/components/ParentLinkName.hh | 1 + .../gazebo/components/ParticleEmitter.hh | 1 + .../ignition/gazebo/components/Performer.hh | 1 + .../gazebo/components/PerformerAffinity.hh | 1 + .../gazebo/components/PerformerLevels.hh | 1 + include/ignition/gazebo/components/Physics.hh | 1 + .../ignition/gazebo/components/PhysicsCmd.hh | 1 + .../gazebo/components/PhysicsEnginePlugin.hh | 1 + include/ignition/gazebo/components/Pose.hh | 1 + include/ignition/gazebo/components/PoseCmd.hh | 1 + .../ignition/gazebo/components/Recreate.hh | 1 + .../components/RenderEngineGuiPlugin.hh | 1 + .../components/RenderEngineServerHeadless.hh | 1 + .../components/RenderEngineServerPlugin.hh | 1 + .../ignition/gazebo/components/RgbdCamera.hh | 1 + include/ignition/gazebo/components/Scene.hh | 1 + .../gazebo/components/SegmentationCamera.hh | 1 + .../ignition/gazebo/components/SelfCollide.hh | 1 + .../gazebo/components/SemanticLabel.hh | 1 + include/ignition/gazebo/components/Sensor.hh | 1 + .../gazebo/components/Serialization.hh | 1 + .../gazebo/components/SlipComplianceCmd.hh | 1 + .../gazebo/components/SourceFilePath.hh | 1 + .../gazebo/components/SphericalCoordinates.hh | 1 + include/ignition/gazebo/components/Static.hh | 1 + .../ignition/gazebo/components/Temperature.hh | 1 + .../gazebo/components/TemperatureRange.hh | 1 + .../gazebo/components/ThermalCamera.hh | 1 + .../ignition/gazebo/components/ThreadPitch.hh | 1 + .../gazebo/components/Transparency.hh | 1 + .../ignition/gazebo/components/Visibility.hh | 1 + include/ignition/gazebo/components/Visual.hh | 1 + .../ignition/gazebo/components/VisualCmd.hh | 1 + include/ignition/gazebo/components/Volume.hh | 1 + .../gazebo/components/WheelSlipCmd.hh | 1 + .../gazebo/components/WideAngleCamera.hh | 1 + include/ignition/gazebo/components/Wind.hh | 1 + .../ignition/gazebo/components/WindMode.hh | 1 + include/ignition/gazebo/components/World.hh | 1 + include/ignition/gazebo/config.hh | 36 + .../ignition/gazebo/contact-system/Export.hh | 1 + .../gazebo/detachable-joint-system/Export.hh | 1 + .../gazebo/diff-drive-system/Export.hh | 1 + .../ignition/gazebo/elevator-system/Export.hh | 1 + .../gazebo/follow-actor-system/Export.hh | 1 + .../gazebo/forcetorque-system/Export.hh | 1 + include/ignition/gazebo/gui/Export.hh | 1 + include/ignition/gazebo/gui/Gui.hh | 1 + include/ignition/gazebo/gui/GuiEvents.hh | 1 + include/ignition/gazebo/gui/GuiSystem.hh | 1 + .../gazebo/hydrodynamics-system/Export.hh | 1 + include/ignition/gazebo/ign/Export.hh | 1 + include/ignition/gazebo/imu-system/Export.hh | 1 + .../gazebo/joint-controller-system/Export.hh | 1 + .../Export.hh | 1 + .../joint-state-publisher-system/Export.hh | 1 + .../Export.hh | 1 + .../kinetic-energy-monitor-system/Export.hh | 1 + .../ignition/gazebo/label-system/Export.hh | 1 + .../gazebo/lift-drag-system/Export.hh | 1 + .../linearbatteryplugin-system/Export.hh | 1 + include/ignition/gazebo/log-system/Export.hh | 1 + .../log-video-recorder-system/Export.hh | 1 + .../gazebo/logical-camera-system/Export.hh | 1 + .../logicalaudiosensorplugin-system/Export.hh | 1 + .../gazebo/magnetometer-system/Export.hh | 1 + .../gazebo/mecanum-drive-system/Export.hh | 1 + .../gazebo/model-photo-shoot-system/Export.hh | 1 + .../multicopter-control-system/Export.hh | 1 + .../multicopter-motor-model-system/Export.hh | 1 + .../ignition/gazebo/navsat-system/Export.hh | 1 + .../odometry-publisher-system/Export.hh | 1 + .../opticaltactileplugin-system/Export.hh | 1 + .../gazebo/particle-emitter-system/Export.hh | 1 + .../gazebo/particle-emitter2-system/Export.hh | 1 + .../gazebo/perfect-comms-system/Export.hh | 1 + .../performer-detector-system/Export.hh | 1 + .../ignition/gazebo/physics-system/Export.hh | 1 + include/ignition/gazebo/physics/Events.hh | 1 + .../gazebo/pose-publisher-system/Export.hh | 1 + include/ignition/gazebo/rendering/Events.hh | 1 + include/ignition/gazebo/rendering/Export.hh | 1 + .../gazebo/rendering/MarkerManager.hh | 1 + .../ignition/gazebo/rendering/RenderUtil.hh | 1 + .../ignition/gazebo/rendering/SceneManager.hh | 1 + .../ignition/gazebo/rf-comms-system/Export.hh | 1 + .../gazebo/scene-broadcaster-system/Export.hh | 1 + .../ignition/gazebo/sensors-system/Export.hh | 1 + .../gazebo/shader-param-system/Export.hh | 1 + .../thermal-sensor-system-system/Export.hh | 1 + .../ignition/gazebo/thermal-system/Export.hh | 1 + .../ignition/gazebo/thruster-system/Export.hh | 1 + .../gazebo/touchplugin-system/Export.hh | 1 + .../gazebo/track-controller-system/Export.hh | 1 + .../gazebo/tracked-vehicle-system/Export.hh | 1 + .../trajectory-follower-system/Export.hh | 1 + .../triggered-publisher-system/Export.hh | 1 + .../gazebo/user-commands-system/Export.hh | 1 + .../gazebo/velocity-control-system/Export.hh | 1 + .../gazebo/wheel-slip-system/Export.hh | 1 + .../gazebo/wind-effects-system/Export.hh | 1 + python/src/gz/common/Console.cc | 6 +- python/src/gz/common/Console.hh | 6 +- python/src/gz/common/_gz_common_pybind11.cc | 4 +- python/src/gz/sim/EntityComponentManager.cc | 10 +- python/src/gz/sim/EntityComponentManager.hh | 18 +- python/src/gz/sim/EventManager.cc | 12 +- python/src/gz/sim/EventManager.hh | 16 +- python/src/gz/sim/Server.cc | 24 +- python/src/gz/sim/Server.hh | 16 +- python/src/gz/sim/ServerConfig.cc | 14 +- python/src/gz/sim/ServerConfig.hh | 16 +- python/src/gz/sim/TestFixture.cc | 6 +- python/src/gz/sim/TestFixture.hh | 12 +- python/src/gz/sim/UpdateInfo.cc | 22 +- python/src/gz/sim/UpdateInfo.hh | 16 +- python/src/gz/sim/Util.cc | 12 +- python/src/gz/sim/Util.hh | 18 +- python/src/gz/sim/World.cc | 16 +- python/src/gz/sim/World.hh | 18 +- python/src/gz/sim/_gz_sim_pybind11.cc | 18 +- python/test/gravity.sdf | 2 +- src/Barrier.cc | 4 +- src/Barrier.hh | 18 +- src/Barrier_TEST.cc | 14 +- src/BaseView.cc | 4 +- src/BaseView_TEST.cc | 4 +- src/CMakeLists.txt | 6 +- src/ComponentFactory_TEST.cc | 6 +- src/Component_TEST.cc | 12 +- src/Conversions.cc | 252 +-- src/Conversions_TEST.cc | 42 +- src/EntityComponentManager.cc | 74 +- src/EntityComponentManagerDiff.cc | 4 +- src/EntityComponentManagerDiff.hh | 12 +- src/EntityComponentManager_TEST.cc | 20 +- src/EventManager_TEST.cc | 12 +- src/LevelManager.cc | 50 +- src/LevelManager.hh | 14 +- src/Link.cc | 10 +- src/Link_TEST.cc | 32 +- src/Model.cc | 8 +- src/ModelCommandAPI_TEST.cc | 40 +- src/Model_TEST.cc | 104 +- src/Primitives.cc | 30 +- src/Primitives_TEST.cc | 12 +- src/SdfEntityCreator.cc | 30 +- src/SdfEntityCreator_TEST.cc | 104 +- src/SdfGenerator.cc | 12 +- src/SdfGenerator.hh | 34 +- src/SdfGenerator_TEST.cc | 6 +- src/Server.cc | 24 +- src/ServerConfig.cc | 87 +- src/ServerConfig_TEST.cc | 38 +- src/ServerPrivate.cc | 50 +- src/ServerPrivate.hh | 24 +- src/Server_TEST.cc | 150 +- src/SimulationRunner.cc | 104 +- src/SimulationRunner.hh | 34 +- src/SimulationRunner_TEST.cc | 186 +- src/SystemInternal.hh | 16 +- src/SystemLoader.cc | 33 +- src/SystemLoader_TEST.cc | 12 +- src/SystemManager.cc | 6 +- src/SystemManager.hh | 18 +- src/SystemManager_TEST.cc | 2 +- src/System_TEST.cc | 2 +- src/TestFixture.cc | 14 +- src/TestFixture_TEST.cc | 4 +- src/Util.cc | 30 +- src/Util_TEST.cc | 42 +- src/View.cc | 14 +- src/World.cc | 20 +- src/WorldControl.hh | 16 +- src/World_TEST.cc | 32 +- src/cmd/ModelCommandAPI.cc | 4 +- src/cmd/cmdgazebo.rb.in | 24 +- src/cmd/cmdmodel.rb.in | 2 +- src/cmd/ign.cc | 150 +- src/comms/Broker.cc | 50 +- src/comms/Broker_TEST.cc | 6 +- src/comms/ICommsModel.cc | 14 +- src/comms/MsgManager.cc | 26 +- src/comms/MsgManager_TEST.cc | 4 +- src/gui/AboutDialogHandler.cc | 16 +- src/gui/AboutDialogHandler.hh | 10 +- src/gui/Gui.cc | 106 +- src/gui/GuiEvents.cc | 24 +- src/gui/GuiEvents_TEST.cc | 4 +- src/gui/GuiFileHandler.cc | 14 +- src/gui/GuiFileHandler.hh | 10 +- src/gui/GuiRunner.cc | 48 +- src/gui/GuiRunner.hh | 12 +- src/gui/Gui_TEST.cc | 34 +- src/gui/Gui_clean_exit_TEST.cc | 10 +- src/gui/PathManager.cc | 12 +- src/gui/PathManager.hh | 10 +- src/gui/plugins/CMakeLists.txt | 6 +- src/gui/plugins/align_tool/AlignTool.cc | 80 +- src/gui/plugins/align_tool/AlignTool.hh | 10 +- .../banana_for_scale/BananaForScale.cc | 32 +- .../banana_for_scale/BananaForScale.hh | 10 +- .../component_inspector/ComponentInspector.cc | 108 +- .../component_inspector/ComponentInspector.hh | 18 +- src/gui/plugins/component_inspector/Pose3d.cc | 6 +- src/gui/plugins/component_inspector/Pose3d.hh | 8 +- src/gui/plugins/component_inspector/Types.hh | 8 +- .../component_inspector_editor/AirPressure.cc | 16 +- .../component_inspector_editor/AirPressure.hh | 8 +- .../component_inspector_editor/Altimeter.cc | 16 +- .../component_inspector_editor/Altimeter.hh | 8 +- .../ComponentInspectorEditor.cc | 144 +- .../ComponentInspectorEditor.hh | 20 +- .../plugins/component_inspector_editor/Imu.cc | 40 +- .../plugins/component_inspector_editor/Imu.hh | 8 +- .../component_inspector_editor/JointType.cc | 10 +- .../component_inspector_editor/JointType.hh | 8 +- .../component_inspector_editor/Lidar.cc | 16 +- .../component_inspector_editor/Lidar.hh | 8 +- .../Magnetometer.cc | 16 +- .../Magnetometer.hh | 8 +- .../component_inspector_editor/ModelEditor.cc | 32 +- .../component_inspector_editor/ModelEditor.hh | 8 +- .../component_inspector_editor/Pose3d.cc | 8 +- .../component_inspector_editor/Pose3d.hh | 8 +- .../component_inspector_editor/Types.cc | 2 +- .../component_inspector_editor/Types.hh | 8 +- src/gui/plugins/copy_paste/CopyPaste.cc | 38 +- src/gui/plugins/copy_paste/CopyPaste.hh | 18 +- .../EntityContextMenuPlugin.cc | 26 +- .../EntityContextMenuPlugin.hh | 10 +- src/gui/plugins/entity_tree/EntityTree.cc | 46 +- src/gui/plugins/entity_tree/EntityTree.hh | 10 +- .../JointPositionController.cc | 40 +- .../JointPositionController.hh | 16 +- .../JointPositionController_TEST.cc | 38 +- src/gui/plugins/lights/Lights.cc | 18 +- src/gui/plugins/lights/Lights.hh | 10 +- src/gui/plugins/modules/CMakeLists.txt | 4 +- src/gui/plugins/modules/EntityContextMenu.cc | 50 +- src/gui/plugins/modules/EntityContextMenu.hh | 8 +- .../playback_scrubber/PlaybackScrubber.cc | 14 +- .../playback_scrubber/PlaybackScrubber.hh | 10 +- src/gui/plugins/plot_3d/Plot3D.cc | 24 +- src/gui/plugins/plot_3d/Plot3D.hh | 10 +- src/gui/plugins/plot_3d/Plot3D_TEST.cc | 10 +- src/gui/plugins/plotting/Plotting.cc | 40 +- src/gui/plugins/plotting/Plotting.hh | 24 +- .../resource_spawner/ResourceSpawner.cc | 46 +- .../resource_spawner/ResourceSpawner.hh | 10 +- src/gui/plugins/scene3d/Scene3D.cc | 284 +-- src/gui/plugins/scene3d/Scene3D.hh | 16 +- .../plugins/scene_manager/GzSceneManager.cc | 40 +- .../plugins/scene_manager/GzSceneManager.hh | 12 +- .../plugins/select_entities/SelectEntities.cc | 102 +- .../plugins/select_entities/SelectEntities.hh | 10 +- src/gui/plugins/shapes/Shapes.cc | 22 +- src/gui/plugins/shapes/Shapes.hh | 10 +- src/gui/plugins/spawn/Spawn.cc | 84 +- src/gui/plugins/spawn/Spawn.hh | 12 +- .../transform_control/TransformControl.cc | 124 +- .../transform_control/TransformControl.hh | 10 +- .../plugins/video_recorder/VideoRecorder.cc | 62 +- .../plugins/video_recorder/VideoRecorder.hh | 10 +- src/gui/plugins/view_angle/ViewAngle.cc | 36 +- src/gui/plugins/view_angle/ViewAngle.hh | 10 +- .../VisualizationCapabilities.cc | 160 +- .../VisualizationCapabilities.hh | 10 +- .../visualize_contacts/VisualizeContacts.cc | 50 +- .../visualize_contacts/VisualizeContacts.hh | 12 +- .../plugins/visualize_lidar/VisualizeLidar.cc | 54 +- .../plugins/visualize_lidar/VisualizeLidar.hh | 14 +- src/gui/resources/GazeboDrawer.qml | 4 +- src/ign.cc | 106 +- src/ign.hh | 6 +- src/ign_TEST.cc | 6 +- src/msgs/peer_control.proto | 6 +- src/msgs/peer_info.proto | 6 +- src/msgs/performer_affinity.proto | 6 +- src/msgs/simulation_step.proto | 6 +- src/network/NetworkConfig.cc | 10 +- src/network/NetworkConfig.hh | 18 +- src/network/NetworkConfig_TEST.cc | 4 +- src/network/NetworkManager.cc | 14 +- src/network/NetworkManager.hh | 20 +- src/network/NetworkManagerPrimary.cc | 18 +- src/network/NetworkManagerPrimary.hh | 22 +- src/network/NetworkManagerPrivate.hh | 24 +- src/network/NetworkManagerSecondary.cc | 16 +- src/network/NetworkManagerSecondary.hh | 22 +- src/network/NetworkManager_TEST.cc | 8 +- src/network/NetworkRole.hh | 16 +- src/network/PeerInfo.cc | 32 +- src/network/PeerInfo.hh | 22 +- src/network/PeerTracker.cc | 8 +- src/network/PeerTracker.hh | 26 +- src/network/PeerTracker_TEST.cc | 30 +- src/rendering/MarkerManager.cc | 148 +- src/rendering/RenderUtil.cc | 88 +- src/rendering/SceneManager.cc | 138 +- src/systems/CMakeLists.txt | 6 +- .../ackermann_steering/AckermannSteering.cc | 62 +- .../ackermann_steering/AckermannSteering.hh | 16 +- .../ackermann_steering/SpeedLimiter.hh | 10 +- src/systems/air_pressure/AirPressure.cc | 19 +- src/systems/air_pressure/AirPressure.hh | 10 +- src/systems/altimeter/Altimeter.cc | 19 +- src/systems/altimeter/Altimeter.hh | 10 +- .../apply_joint_force/ApplyJointForce.cc | 28 +- .../apply_joint_force/ApplyJointForce.hh | 14 +- .../battery_plugin/LinearBatteryPlugin.cc | 88 +- .../battery_plugin/LinearBatteryPlugin.hh | 16 +- src/systems/breadcrumbs/Breadcrumbs.cc | 47 +- src/systems/breadcrumbs/Breadcrumbs.hh | 16 +- src/systems/buoyancy/Buoyancy.cc | 48 +- src/systems/buoyancy/Buoyancy.hh | 14 +- src/systems/buoyancy_engine/BuoyancyEngine.cc | 58 +- src/systems/buoyancy_engine/BuoyancyEngine.hh | 34 +- .../CameraVideoRecorder.cc | 42 +- .../CameraVideoRecorder.hh | 10 +- .../ColladaWorldExporter.cc | 30 +- .../ColladaWorldExporter.hh | 10 +- src/systems/comms_endpoint/CommsEndpoint.cc | 36 +- src/systems/comms_endpoint/CommsEndpoint.hh | 16 +- src/systems/contact/Contact.cc | 17 +- src/systems/contact/Contact.hh | 14 +- .../detachable_joint/DetachableJoint.cc | 32 +- .../detachable_joint/DetachableJoint.hh | 14 +- src/systems/diff_drive/DiffDrive.cc | 57 +- src/systems/diff_drive/DiffDrive.hh | 22 +- src/systems/elevator/Elevator.cc | 27 +- src/systems/elevator/Elevator.hh | 18 +- src/systems/elevator/ElevatorCommonPrivate.hh | 16 +- src/systems/elevator/ElevatorStateMachine.hh | 16 +- .../elevator/state_machine/ActionsImpl.hh | 10 +- .../state_machine/ElevatorStateMachineImpl.hh | 12 +- .../elevator/state_machine/EventsImpl.hh | 10 +- .../elevator/state_machine/GuardsImpl.hh | 10 +- .../elevator/state_machine/StatesImpl.hh | 18 +- src/systems/elevator/utils/DoorTimer.cc | 10 +- src/systems/elevator/utils/DoorTimer.hh | 16 +- src/systems/elevator/utils/JointMonitor.cc | 10 +- src/systems/elevator/utils/JointMonitor.hh | 16 +- src/systems/follow_actor/FollowActor.cc | 23 +- src/systems/follow_actor/FollowActor.hh | 10 +- src/systems/force_torque/ForceTorque.cc | 27 +- src/systems/force_torque/ForceTorque.hh | 12 +- src/systems/hydrodynamics/Hydrodynamics.cc | 71 +- src/systems/hydrodynamics/Hydrodynamics.hh | 32 +- src/systems/imu/Imu.cc | 31 +- src/systems/imu/Imu.hh | 12 +- .../joint_controller/JointController.cc | 56 +- .../joint_controller/JointController.hh | 14 +- .../JointPositionController.cc | 56 +- .../JointPositionController.hh | 18 +- .../JointStatePublisher.cc | 28 +- .../JointStatePublisher.hh | 14 +- .../JointTrajectoryController.cc | 95 +- .../JointTrajectoryController.hh | 24 +- .../KineticEnergyMonitor.cc | 22 +- .../KineticEnergyMonitor.hh | 12 +- src/systems/label/Label.cc | 19 +- src/systems/label/Label.hh | 12 +- src/systems/lift_drag/LiftDrag.cc | 95 +- src/systems/lift_drag/LiftDrag.hh | 10 +- src/systems/log/LogPlayback.cc | 61 +- src/systems/log/LogPlayback.hh | 10 +- src/systems/log/LogRecord.cc | 68 +- src/systems/log/LogRecord.hh | 10 +- .../log_video_recorder/LogVideoRecorder.cc | 52 +- .../log_video_recorder/LogVideoRecorder.hh | 10 +- .../LogicalAudio.cc | 14 +- .../LogicalAudio.hh | 26 +- .../LogicalAudioSensorPlugin.cc | 76 +- .../LogicalAudioSensorPlugin.hh | 18 +- .../LogicalAudio_TEST.cc | 2 +- src/systems/logical_camera/LogicalCamera.cc | 19 +- src/systems/logical_camera/LogicalCamera.hh | 10 +- src/systems/magnetometer/Magnetometer.cc | 26 +- src/systems/magnetometer/Magnetometer.hh | 10 +- src/systems/mecanum_drive/MecanumDrive.cc | 50 +- src/systems/mecanum_drive/MecanumDrive.hh | 22 +- .../model_photo_shoot/ModelPhotoShoot.cc | 86 +- .../model_photo_shoot/ModelPhotoShoot.hh | 20 +- src/systems/multicopter_control/Common.cc | 30 +- src/systems/multicopter_control/Common.hh | 14 +- .../LeeVelocityController.cc | 10 +- .../LeeVelocityController.hh | 14 +- .../MulticopterVelocityControl.cc | 53 +- .../MulticopterVelocityControl.hh | 16 +- src/systems/multicopter_control/Parameters.hh | 14 +- .../MulticopterMotorModel.cc | 58 +- .../MulticopterMotorModel.hh | 14 +- src/systems/navsat/NavSat.cc | 21 +- src/systems/navsat/NavSat.hh | 12 +- .../odometry_publisher/OdometryPublisher.cc | 68 +- .../odometry_publisher/OdometryPublisher.hh | 16 +- .../OpticalTactilePlugin.cc | 140 +- .../OpticalTactilePlugin.hh | 18 +- .../optical_tactile_plugin/Visualization.cc | 146 +- .../optical_tactile_plugin/Visualization.hh | 52 +- .../particle_emitter/ParticleEmitter.cc | 38 +- .../particle_emitter/ParticleEmitter.hh | 14 +- .../particle_emitter2/ParticleEmitter2.cc | 38 +- .../particle_emitter2/ParticleEmitter2.hh | 26 +- src/systems/perfect_comms/PerfectComms.cc | 16 +- src/systems/perfect_comms/PerfectComms.hh | 12 +- .../performer_detector/PerformerDetector.cc | 28 +- .../performer_detector/PerformerDetector.hh | 22 +- .../physics/CanonicalLinkModelTracker.hh | 8 +- src/systems/physics/EntityFeatureMap.hh | 10 +- src/systems/physics/EntityFeatureMap_TEST.cc | 22 +- src/systems/physics/Physics.cc | 343 +-- src/systems/physics/Physics.hh | 12 +- src/systems/pose_publisher/PosePublisher.cc | 32 +- src/systems/pose_publisher/PosePublisher.hh | 18 +- src/systems/rf_comms/RFComms.cc | 36 +- src/systems/rf_comms/RFComms.hh | 14 +- .../scene_broadcaster/SceneBroadcaster.cc | 70 +- .../scene_broadcaster/SceneBroadcaster.hh | 12 +- src/systems/sensors/Sensors.cc | 39 +- src/systems/sensors/Sensors.hh | 10 +- src/systems/shader_param/ShaderParam.cc | 30 +- src/systems/shader_param/ShaderParam.hh | 16 +- src/systems/thermal/Thermal.cc | 21 +- src/systems/thermal/Thermal.hh | 12 +- src/systems/thermal/ThermalSensor.cc | 16 +- src/systems/thermal/ThermalSensor.hh | 12 +- src/systems/thruster/Thruster.cc | 67 +- src/systems/thruster/Thruster.hh | 32 +- src/systems/touch_plugin/TouchPlugin.cc | 33 +- src/systems/touch_plugin/TouchPlugin.hh | 14 +- .../track_controller/TrackController.cc | 100 +- .../track_controller/TrackController.hh | 14 +- src/systems/tracked_vehicle/TrackedVehicle.cc | 94 +- src/systems/tracked_vehicle/TrackedVehicle.hh | 22 +- .../trajectory_follower/TrajectoryFollower.cc | 86 +- .../trajectory_follower/TrajectoryFollower.hh | 20 +- .../triggered_publisher/TriggeredPublisher.cc | 60 +- .../triggered_publisher/TriggeredPublisher.hh | 46 +- src/systems/user_commands/UserCommands.cc | 132 +- src/systems/user_commands/UserCommands.hh | 28 +- .../velocity_control/VelocityControl.cc | 56 +- .../velocity_control/VelocityControl.hh | 14 +- src/systems/wheel_slip/WheelSlip.cc | 30 +- src/systems/wheel_slip/WheelSlip.hh | 16 +- src/systems/wind_effects/WindEffects.cc | 35 +- src/systems/wind_effects/WindEffects.hh | 10 +- test/benchmark/CMakeLists.txt | 2 +- test/benchmark/each.cc | 22 +- test/benchmark/ecm_serialize.cc | 30 +- test/helpers/EnvTestFixture.hh | 12 +- test/helpers/Relay.hh | 12 +- test/helpers/UniqueTestDirectoryEnv.hh | 16 +- test/integration/ModelPhotoShootTest.hh | 78 +- test/integration/ackermann_steering_system.cc | 40 +- test/integration/air_pressure_system.cc | 30 +- test/integration/altimeter_system.cc | 42 +- test/integration/apply_joint_force_system.cc | 28 +- test/integration/battery_plugin.cc | 62 +- test/integration/breadcrumbs.cc | 64 +- test/integration/buoyancy.cc | 70 +- test/integration/buoyancy_engine.cc | 62 +- test/integration/camera_sensor_background.cc | 14 +- .../integration/camera_video_record_system.cc | 22 +- test/integration/collada_world_exporter.cc | 34 +- test/integration/components.cc | 130 +- test/integration/contact_system.cc | 20 +- test/integration/deprecated_TEST.cc | 34 + test/integration/depth_camera.cc | 22 +- test/integration/detachable_joint.cc | 46 +- test/integration/diff_drive_system.cc | 44 +- test/integration/distortion_camera.cc | 18 +- test/integration/each_new_removed.cc | 44 +- test/integration/elevator_system.cc | 14 +- test/integration/entity_erase.cc | 14 +- test/integration/events.cc | 16 +- test/integration/examples_build.cc | 32 +- test/integration/follow_actor_system.cc | 36 +- test/integration/force_torque_system.cc | 22 +- test/integration/fuel_cached_server.cc | 10 +- test/integration/gpu_lidar.cc | 20 +- test/integration/halt_motion.cc | 38 +- test/integration/imu_system.cc | 50 +- test/integration/joint_controller_system.cc | 42 +- .../joint_position_controller_system.cc | 42 +- .../joint_state_publisher_system.cc | 16 +- .../joint_trajectory_controller_system.cc | 62 +- .../kinetic_energy_monitor_system.cc | 22 +- test/integration/level_manager.cc | 62 +- .../level_manager_runtime_performers.cc | 68 +- test/integration/lift_drag_system.cc | 60 +- test/integration/link.cc | 52 +- test/integration/log_system.cc | 117 +- .../logical_audio_sensor_plugin.cc | 40 +- test/integration/logical_camera_system.cc | 56 +- test/integration/magnetometer_system.cc | 46 +- test/integration/model.cc | 36 +- .../model_photo_shoot_default_joints.cc | 2 +- .../model_photo_shoot_random_joints.cc | 2 +- test/integration/multicopter.cc | 60 +- test/integration/multiple_servers.cc | 20 +- test/integration/navsat_system.cc | 40 +- test/integration/nested_model_physics.cc | 38 +- test/integration/network_handshake.cc | 34 +- test/integration/odometry_publisher.cc | 54 +- test/integration/optical_tactile_plugin.cc | 24 +- test/integration/particle_emitter.cc | 34 +- test/integration/perfect_comms.cc | 24 +- test/integration/performer_detector.cc | 28 +- test/integration/physics_system.cc | 392 ++-- test/integration/play_pause.cc | 24 +- test/integration/pose_publisher_system.cc | 46 +- test/integration/recreate_entities.cc | 72 +- test/integration/reset.cc | 60 +- test/integration/rf_comms.cc | 26 +- test/integration/rgbd_camera.cc | 22 +- test/integration/save_world.cc | 68 +- test/integration/scene_broadcaster_system.cc | 182 +- test/integration/sdf_frame_semantics.cc | 100 +- test/integration/sdf_include.cc | 18 +- test/integration/sensors_system.cc | 88 +- test/integration/sensors_system_battery.cc | 40 +- test/integration/shader_param_system.cc | 16 +- test/integration/spherical_coordinates.cc | 56 +- test/integration/thermal_sensor_system.cc | 42 +- test/integration/thermal_system.cc | 48 +- test/integration/thruster.cc | 40 +- test/integration/touch_plugin.cc | 22 +- test/integration/tracked_vehicle_system.cc | 70 +- test/integration/triggered_publisher.cc | 30 +- test/integration/user_commands.cc | 122 +- test/integration/velocity_control_system.cc | 38 +- test/integration/wheel_slip.cc | 108 +- test/integration/wide_angle_camera.cc | 18 +- test/integration/wind_effects.cc | 44 +- test/integration/world.cc | 48 +- test/integration/world_control_state.cc | 34 +- test/media/rolling_shapes_log/README.md | 3 + test/media/rolling_shapes_log/state.tlog | Bin 2105344 -> 2105344 bytes test/performance/each.cc | 14 +- test/performance/level_manager.cc | 30 +- test/performance/sdf_runner.cc | 42 +- test/plugins/EventTriggerSystem.cc | 10 +- test/plugins/EventTriggerSystem.hh | 24 +- test/plugins/MockSystem.cc | 14 +- test/plugins/MockSystem.hh | 44 +- test/plugins/Null.cc | 12 +- test/plugins/Null.hh | 16 +- test/plugins/TestModelSystem.cc | 8 +- test/plugins/TestModelSystem.hh | 32 +- test/plugins/TestSensorSystem.cc | 8 +- test/plugins/TestSensorSystem.hh | 28 +- test/plugins/TestSystem.cc | 10 +- test/plugins/TestSystem.hh | 14 +- test/plugins/TestVisualSystem.cc | 8 +- test/plugins/TestVisualSystem.hh | 28 +- test/plugins/TestWorldSystem.cc | 10 +- test/plugins/TestWorldSystem.hh | 24 +- test/test_config.hh.in | 20 +- 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 | 4 +- test/worlds/altimeter.sdf | 6 +- test/worlds/altimeter_with_pose.sdf | 8 +- test/worlds/apply_joint_force.sdf | 4 +- test/worlds/battery.sdf | 8 +- 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/buoyancy_engine.sdf | 8 +- .../buoyancy_graded_restoring_moments.sdf | 4 +- .../buoyancy_uniform_restoring_moments.sdf | 4 +- test/worlds/camera_distortion.sdf | 6 +- 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/center_of_volume_graded.sdf | 8 +- test/worlds/collada_world_exporter.sdf | 2 +- test/worlds/collada_world_exporter_lights.sdf | 2 +- .../worlds/collada_world_exporter_submesh.sdf | 4 +- test/worlds/contact.sdf | 4 +- test/worlds/contact_with_entity_names.sdf | 4 +- test/worlds/contact_without_entity_names.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_nested.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/follow_actor.sdf | 4 +- test/worlds/force_torque.sdf | 6 +- test/worlds/friction.sdf | 8 +- test/worlds/gpu_lidar_sensor.sdf | 4 +- test/worlds/graded_buoyancy.sdf | 10 +- test/worlds/imu.sdf | 4 +- test/worlds/imu_heading_deg.sdf | 4 +- test/worlds/imu_named_frame.sdf | 4 +- test/worlds/imu_no_orientation.sdf | 4 +- test/worlds/imu_rotating_demo.sdf | 6 +- .../include_connected_nested_models.sdf | 4 +- test/worlds/include_nested_models.sdf | 4 +- test/worlds/joint_controller.sdf | 8 +- test/worlds/joint_controller_invalid.sdf | 2 +- test/worlds/joint_position_controller.sdf | 6 +- .../joint_position_controller_velocity.sdf | 6 +- test/worlds/joint_sensor.sdf | 4 +- test/worlds/joint_trajectory_controller.sdf | 8 +- 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/lift_drag_nested_model.sdf | 6 +- test/worlds/lights.sdf | 4 +- test/worlds/lights_render.sdf | 6 +- 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 | 6 +- test/worlds/mesh.sdf | 4 +- test/worlds/model_nested_include.sdf | 4 +- .../model_photo_shoot_random_joints.sdf | 8 +- test/worlds/model_plugin_only.sdf | 2 +- test/worlds/models/nested_models/model.sdf | 2 +- test/worlds/multiple_worlds.sdf | 10 +- test/worlds/navsat.sdf | 4 +- test/worlds/nested_model.sdf | 6 +- test/worlds/nested_model_canonical_link.sdf | 4 +- test/worlds/non_rendering_sensors.sdf | 4 +- test/worlds/nondefault_canonical.sdf | 4 +- test/worlds/odometry_noise.sdf | 4 +- test/worlds/odometry_offset.sdf | 4 +- test/worlds/odometry_publisher.sdf | 4 +- test/worlds/odometry_publisher_3d.sdf | 14 +- test/worlds/odometry_publisher_custom.sdf | 4 +- test/worlds/office.sdf | 6 +- test/worlds/only_canonical_link_moves.sdf | 4 +- test/worlds/optical_tactile_plugin.sdf | 8 +- test/worlds/particle_emitter.sdf | 2 +- test/worlds/performer_detector.sdf | 12 +- test/worlds/performers.sdf | 2 +- test/worlds/physics_options.sdf | 2 +- test/worlds/plugins.sdf | 8 +- test/worlds/pose_publisher.sdf | 12 +- test/worlds/quadcopter.sdf | 12 +- test/worlds/quadcopter_velocity_control.sdf | 14 +- test/worlds/reset.sdf | 6 +- 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 | 6 +- test/worlds/save_world.sdf | 6 +- test/worlds/sea_storm_effects.sdf | 6 +- test/worlds/sensor.sdf | 4 +- test/worlds/sensors_system_battery.sdf | 8 +- test/worlds/server_invalid.config | 2 +- test/worlds/server_valid.config | 6 +- test/worlds/server_valid2.config | 4 +- test/worlds/shapes_scene_broadcaster_only.sdf | 2 +- test/worlds/spherical_coordinates.sdf | 4 +- test/worlds/static_diff_drive_vehicle.sdf | 6 +- test/worlds/thermal.sdf | 18 +- test/worlds/thermal_invalid.sdf | 14 +- test/worlds/thruster_ang_vel_cmd.sdf | 6 +- test/worlds/thruster_ccw_ang_vel_cmd.sdf | 6 +- test/worlds/thruster_ccw_force_cmd.sdf | 6 +- test/worlds/thruster_pid.sdf | 6 +- test/worlds/thruster_vel_cmd.sdf | 6 +- 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 | 108 +- test/worlds/trisphere_cycle_wheel_slip.sdf | 10 +- test/worlds/velocity_control.sdf | 16 +- test/worlds/wide_angle_camera_sensor.sdf | 6 +- test/worlds/wind_effects.sdf | 6 +- tutorials.md.in | 16 +- tutorials/battery.md | 10 +- tutorials/blender_sdf_exporter.md | 2 +- tutorials/collada_world_exporter.md | 4 +- tutorials/create_system_plugins.md | 12 +- tutorials/detachable_joints.md | 2 +- tutorials/distributed_simulation.md | 2 +- tutorials/entity_creation.md | 20 +- tutorials/erb_template.md | 6 +- tutorials/gui_config.md | 26 +- tutorials/headless_rendering.md | 6 +- tutorials/install.md | 18 +- tutorials/levels.md | 32 +- tutorials/light_config.md | 4 +- tutorials/log.md | 16 +- tutorials/logical_audio_sensor.md | 16 +- tutorials/mesh_to_fuel.md | 18 +- tutorials/migrating_ardupilot_plugin.md | 178 +- tutorials/migration_link_api.md | 94 +- tutorials/migration_model_api.md | 78 +- tutorials/migration_plugins.md | 58 +- tutorials/migration_sdf.md | 28 +- tutorials/migration_world_api.md | 68 +- tutorials/model_command.md | 4 +- tutorials/model_photo_shoot.md | 12 +- tutorials/particle_tutorial.md | 18 +- tutorials/physics.md | 28 +- tutorials/point_cloud_to_mesh.md | 22 +- tutorials/python_interfaces.md | 10 +- tutorials/rendering_plugins.md | 44 +- tutorials/resources.md | 64 +- tutorials/server_config.md | 28 +- tutorials/spherical_coordinates.md | 20 +- tutorials/terminology.md | 16 +- tutorials/test_fixture.md | 8 +- tutorials/triggered_publisher.md | 42 +- tutorials/underwater_vehicles.md | 28 +- tutorials/video_recorder.md | 22 +- 1142 files changed, 11999 insertions(+), 11466 deletions(-) create mode 100644 test/integration/deprecated_TEST.cc diff --git a/.github/ci/after_make.sh b/.github/ci/after_make.sh index 8e619ed869..d7d0da54ef 100644 --- a/.github/ci/after_make.sh +++ b/.github/ci/after_make.sh @@ -8,7 +8,7 @@ make install export LD_LIBRARY_PATH=${LD_LIBRARY_PATH}:/usr/local/lib # For ign-tools -export IGN_CONFIG_PATH=/usr/local/share/ignition +export GZ_CONFIG_PATH=/usr/local/share/ignition # For rendering / window tests Xvfb :1 -screen 0 1280x1024x24 & diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 130c5dfc58..66518cb228 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -26,5 +26,5 @@ jobs: id: ci uses: ignition-tooling/action-ignition-ci@jammy with: - # per bug https://github.com/ignitionrobotics/ign-gazebo/issues/1409 + # per bug https://github.com/gazebosim/gz-sim/issues/1409 cmake-args: '-DBUILD_DOCS=OFF' diff --git a/CMakeLists.txt b/CMakeLists.txt index 2dfdcd576e..93357a1d0c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -23,7 +23,7 @@ set (CMAKE_CXX_STANDARD 17) # Set project-specific options #============================================================================ -option(ENABLE_PROFILER "Enable Ignition Profiler" FALSE) +option(ENABLE_PROFILER "Enable Gazebo Profiler" FALSE) if(ENABLE_PROFILER) add_definitions("-DIGN_PROFILER_ENABLE=1") @@ -201,10 +201,10 @@ else() endif() endif() # Plugin install dirs -set(IGNITION_GAZEBO_PLUGIN_INSTALL_DIR +set(GZ_SIM_PLUGIN_INSTALL_DIR ${CMAKE_INSTALL_PREFIX}/${IGN_LIB_INSTALL_DIR}/ign-${IGN_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins ) -set(IGNITION_GAZEBO_GUI_PLUGIN_INSTALL_DIR +set(GZ_SIM_GUI_PLUGIN_INSTALL_DIR ${CMAKE_INSTALL_PREFIX}/${IGN_LIB_INSTALL_DIR}/ign-${IGN_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins/gui ) @@ -233,7 +233,7 @@ configure_file(${CMAKE_SOURCE_DIR}/tools/desktop/ignition-gazebo.svg.in ${CMAKE_ # disable doxygen on macOS due to issues with doxygen 1.9.0 # there is an unreleased fix; revert this when 1.9.1 is released -# https://github.com/ignitionrobotics/ign-gazebo/issues/520 +# https://github.com/gazebosim/gz-sim/issues/520 if (NOT APPLE) ign_create_docs( API_MAINPAGE_MD "${CMAKE_BINARY_DIR}/api.md" @@ -256,7 +256,7 @@ if(TARGET doc) endif() # TICKTOCK MASTER HEADER (to bypass IGN_DESIGNATION) -# TODO(CH3): Remove on tock +# TODO(CH3): Deprecated. Remove on tock configure_file( ${CMAKE_CURRENT_BINARY_DIR}/include/gz/${IGN_DESIGNATION}.hh ${CMAKE_CURRENT_BINARY_DIR}/include/gz/sim.hh diff --git a/CODE_OF_CONDUCT.md b/CODE_OF_CONDUCT.md index 820e43fdbb..65eec816ef 100644 --- a/CODE_OF_CONDUCT.md +++ b/CODE_OF_CONDUCT.md @@ -56,7 +56,7 @@ further defined and clarified by project maintainers. ## Enforcement Instances of abusive, harassing, or otherwise unacceptable behavior may be -reported by contacting the project team at [https://ignitionrobotics.org/support](https://ignitionrobotics.org/support). All +reported by contacting the project team at [https://gazebosim.org/support](https://gazebosim.org/support). All complaints will be reviewed and investigated and will result in a response that is deemed necessary and appropriate to the circumstances. The project team is obligated to maintain confidentiality with regard to the reporter of an incident. diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index 147239ce5f..a1c121ea4d 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -1 +1 @@ -See the [Ignition Robotics contributing guide](https://ignitionrobotics.org/docs/all/contributing). +See the [Gazebo contributing guide](https://gazebosim.org/docs/all/contributing). diff --git a/Changelog.md b/Changelog.md index 31221f0292..02ebba9568 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,1883 +1,1883 @@ -## Ignition Gazebo 7.x +## Gazebo Sim 7.x -### Ignition Gazebo 7.X.X (20XX-XX-XX) +### Gazebo Sim 7.X.X (20XX-XX-XX) -## Ignition Gazebo 6.x +## Gazebo Sim 6.x -### Ignition Gazebo 6.9.0 (2022-04-14) +### Gazebo Sim 6.9.0 (2022-04-14) 1. Add new `RFComms` system - * [Pull request #1428](https://github.com/ignitionrobotics/ign-gazebo/pull/1428) + * [Pull request #1428](https://github.com/gazebosim/gz-sim/pull/1428) 1. Add comms infrastructure - * [Pull request #1416](https://github.com/ignitionrobotics/ign-gazebo/pull/1416) + * [Pull request #1416](https://github.com/gazebosim/gz-sim/pull/1416) 1. Fix CMake version examples and bump plugin version - * [Pull request #1442](https://github.com/ignitionrobotics/ign-gazebo/pull/1442) + * [Pull request #1442](https://github.com/gazebosim/gz-sim/pull/1442) 1. Make sure pose publisher creates valid pose topics - * [Pull request #1433](https://github.com/ignitionrobotics/ign-gazebo/pull/1433) + * [Pull request #1433](https://github.com/gazebosim/gz-sim/pull/1433) 1. Add Ubuntu Jammy CI - * [Pull request #1418](https://github.com/ignitionrobotics/ign-gazebo/pull/1418) + * [Pull request #1418](https://github.com/gazebosim/gz-sim/pull/1418) 1. Removed `screenToPlane` method and use `rendering::screenToPlane` - * [Pull request #1432](https://github.com/ignitionrobotics/ign-gazebo/pull/1432) + * [Pull request #1432](https://github.com/gazebosim/gz-sim/pull/1432) 1. Supply world frame orientation and heading to IMU sensor (#1427) - * [Pull request #1427](https://github.com/ignitionrobotics/ign-gazebo/pull/1427) + * [Pull request #1427](https://github.com/gazebosim/gz-sim/pull/1427) 1. Add desktop entry and SVG logo - * [Pull request #1411](https://github.com/ignitionrobotics/ign-gazebo/pull/1411) - * [Pull request #1430](https://github.com/ignitionrobotics/ign-gazebo/pull/1430) + * [Pull request #1411](https://github.com/gazebosim/gz-sim/pull/1411) + * [Pull request #1430](https://github.com/gazebosim/gz-sim/pull/1430) 1. Fix segfault at exit - * [Pull request #1317](https://github.com/ignitionrobotics/ign-gazebo/pull/1317) + * [Pull request #1317](https://github.com/gazebosim/gz-sim/pull/1317) 1. Add Gaussian noise to Odometry Publisher - * [Pull request #1393](https://github.com/ignitionrobotics/ign-gazebo/pull/1393) + * [Pull request #1393](https://github.com/gazebosim/gz-sim/pull/1393) -### Ignition Gazebo 6.8.0 (2022-04-04) +### Gazebo Sim 6.8.0 (2022-04-04) 1. ServerConfig accepts an sdf::Root DOM object - * [Pull request #1333](https://github.com/ignitionrobotics/ign-gazebo/pull/1333) + * [Pull request #1333](https://github.com/gazebosim/gz-sim/pull/1333) 1. Disable sensors in sensors system when battery is drained - * [Pull request #1385](https://github.com/ignitionrobotics/ign-gazebo/pull/1385) + * [Pull request #1385](https://github.com/gazebosim/gz-sim/pull/1385) 1. Referring to Fuel assets within a heightmap - * [Pull request #1419](https://github.com/ignitionrobotics/ign-gazebo/pull/1419) + * [Pull request #1419](https://github.com/gazebosim/gz-sim/pull/1419) 1. Add the Model Photo Shoot system, port of Modelpropshop plugin from Gazebo classic - * [Pull request #1331](https://github.com/ignitionrobotics/ign-gazebo/pull/1331) + * [Pull request #1331](https://github.com/gazebosim/gz-sim/pull/1331) 1. Distortion camera integration test - * [Pull request #1374](https://github.com/ignitionrobotics/ign-gazebo/pull/1374) + * [Pull request #1374](https://github.com/gazebosim/gz-sim/pull/1374) 1. Add wheel slip user command - * [Pull request #1241](https://github.com/ignitionrobotics/ign-gazebo/pull/1241) + * [Pull request #1241](https://github.com/gazebosim/gz-sim/pull/1241) 1. SceneBroadcaster: only send changed state information for change events - * [Pull request #1392](https://github.com/ignitionrobotics/ign-gazebo/pull/1392) + * [Pull request #1392](https://github.com/gazebosim/gz-sim/pull/1392) 1. Fortress: Install Ogre 2.2, simplify docker - * [Pull request #1395](https://github.com/ignitionrobotics/ign-gazebo/pull/1395) + * [Pull request #1395](https://github.com/gazebosim/gz-sim/pull/1395) 1. Disable tests that are expected to fail on Windows - * [Pull request #1408](https://github.com/ignitionrobotics/ign-gazebo/pull/1408) + * [Pull request #1408](https://github.com/gazebosim/gz-sim/pull/1408) 1. Added user command to set multiple entities - * [Pull request #1394](https://github.com/ignitionrobotics/ign-gazebo/pull/1394) + * [Pull request #1394](https://github.com/gazebosim/gz-sim/pull/1394) 1. Fix JointStatePublisher topic name for nested models - * [Pull request #1405](https://github.com/ignitionrobotics/ign-gazebo/pull/1405) + * [Pull request #1405](https://github.com/gazebosim/gz-sim/pull/1405) 1. add initial_position param to joint controller system - * [Pull request #1406](https://github.com/ignitionrobotics/ign-gazebo/pull/1406) + * [Pull request #1406](https://github.com/gazebosim/gz-sim/pull/1406) 1. Component inspector: refactor Pose3d C++ code into a separate class - * [Pull request #1400](https://github.com/ignitionrobotics/ign-gazebo/pull/1400) + * [Pull request #1400](https://github.com/gazebosim/gz-sim/pull/1400) 1. Prevent hanging when world has only non-world plugins - * [Pull request #1383](https://github.com/ignitionrobotics/ign-gazebo/pull/1383) + * [Pull request #1383](https://github.com/gazebosim/gz-sim/pull/1383) 1. Toggle Light visuals - * [Pull request #1387](https://github.com/ignitionrobotics/ign-gazebo/pull/1387) + * [Pull request #1387](https://github.com/gazebosim/gz-sim/pull/1387) 1. Disable PeerTracker.PeerTrackerStale on macOS - * [Pull request #1398](https://github.com/ignitionrobotics/ign-gazebo/pull/1398) + * [Pull request #1398](https://github.com/gazebosim/gz-sim/pull/1398) 1. Disable ModelCommandAPI_TEST.RgbdCameraSensor on macOS - * [Pull request #1397](https://github.com/ignitionrobotics/ign-gazebo/pull/1397) + * [Pull request #1397](https://github.com/gazebosim/gz-sim/pull/1397) 1. Don't mark entities with a ComponentState::NoChange component as modified - * [Pull request #1391](https://github.com/ignitionrobotics/ign-gazebo/pull/1391) + * [Pull request #1391](https://github.com/gazebosim/gz-sim/pull/1391) 1. Add gazebo Entity id to rendering sensor's user data - * [Pull request #1381](https://github.com/ignitionrobotics/ign-gazebo/pull/1381) + * [Pull request #1381](https://github.com/gazebosim/gz-sim/pull/1381) 1. Allow to turn on/off lights - * [Pull request #1343](https://github.com/ignitionrobotics/ign-gazebo/pull/1343) + * [Pull request #1343](https://github.com/gazebosim/gz-sim/pull/1343) 1. Added headless rendering tutorial - * [Pull request #1386](https://github.com/ignitionrobotics/ign-gazebo/pull/1386) + * [Pull request #1386](https://github.com/gazebosim/gz-sim/pull/1386) 1. Add xyz and rpy offset to published odometry pose - * [Pull request #1341](https://github.com/ignitionrobotics/ign-gazebo/pull/1341) + * [Pull request #1341](https://github.com/gazebosim/gz-sim/pull/1341) 1. Fix visualization python tutorial - * [Pull request #1377](https://github.com/ignitionrobotics/ign-gazebo/pull/1377) + * [Pull request #1377](https://github.com/gazebosim/gz-sim/pull/1377) 1. Populate GUI plugins that are empty - * [Pull request #1375](https://github.com/ignitionrobotics/ign-gazebo/pull/1375) + * [Pull request #1375](https://github.com/gazebosim/gz-sim/pull/1375) -### Ignition Gazebo 6.7.0 (2022-02-24) +### Gazebo Sim 6.7.0 (2022-02-24) -1. Added Python interfaces to some Ignition Gazebo methods - * [Pull request #1219](https://github.com/ignitionrobotics/ign-gazebo/pull/1219) +1. Added Python interfaces to some Gazebo Sim methods + * [Pull request #1219](https://github.com/gazebosim/gz-sim/pull/1219) 1. Use pose multiplication instead of addition - * [Pull request #1369](https://github.com/ignitionrobotics/ign-gazebo/pull/1369) + * [Pull request #1369](https://github.com/gazebosim/gz-sim/pull/1369) 1. Disables Failing Buoyancy Tests on Win32 - * [Pull request #1368](https://github.com/ignitionrobotics/ign-gazebo/pull/1368) + * [Pull request #1368](https://github.com/gazebosim/gz-sim/pull/1368) 1. Extend ShaderParam system to support loading different shader languages - * [Pull request #1335](https://github.com/ignitionrobotics/ign-gazebo/pull/1335) + * [Pull request #1335](https://github.com/gazebosim/gz-sim/pull/1335) 1. Populate names of colliding entities in contact points message - * [Pull request #1351](https://github.com/ignitionrobotics/ign-gazebo/pull/1351) + * [Pull request #1351](https://github.com/gazebosim/gz-sim/pull/1351) 1. Refactor System functionality into SystemManager - * [Pull request #1340](https://github.com/ignitionrobotics/ign-gazebo/pull/1340) + * [Pull request #1340](https://github.com/gazebosim/gz-sim/pull/1340) 1. GzSceneManager: Prevent crash boom when inserted from menu - * [Pull request #1371](https://github.com/ignitionrobotics/ign-gazebo/pull/1371) + * [Pull request #1371](https://github.com/gazebosim/gz-sim/pull/1371) -### Ignition Gazebo 6.6.0 (2022-02-24) +### Gazebo Sim 6.6.0 (2022-02-24) 1. Fix accessing empty JointPosition component in lift drag plugin - * [Pull request #1366](https://github.com/ignitionrobotics/ign-gazebo/pull/1366) + * [Pull request #1366](https://github.com/gazebosim/gz-sim/pull/1366) 1. Add parameter to TrajectoryFollower stop rotation when bearing is reached - * [Pull request #1349](https://github.com/ignitionrobotics/ign-gazebo/pull/1349) + * [Pull request #1349](https://github.com/gazebosim/gz-sim/pull/1349) 1. Support disabling pose publisher from publishing top level model pose - * [Pull request #1342](https://github.com/ignitionrobotics/ign-gazebo/pull/1342) + * [Pull request #1342](https://github.com/gazebosim/gz-sim/pull/1342) 1. Added more sensor properties to scene/info topic - * [Pull request #1344](https://github.com/ignitionrobotics/ign-gazebo/pull/1344) + * [Pull request #1344](https://github.com/gazebosim/gz-sim/pull/1344) 1. Adding ability to pause/resume the trajectory follower behavior. - * [Pull request #1347](https://github.com/ignitionrobotics/ign-gazebo/pull/1347) + * [Pull request #1347](https://github.com/gazebosim/gz-sim/pull/1347) 1. Logs a warning if a mode is not clearly sepecified. - * [Pull request #1307](https://github.com/ignitionrobotics/ign-gazebo/pull/1307) + * [Pull request #1307](https://github.com/gazebosim/gz-sim/pull/1307) 1. JointStatePublisher publish parent, child and axis data - * [Pull request #1345](https://github.com/ignitionrobotics/ign-gazebo/pull/1345) + * [Pull request #1345](https://github.com/gazebosim/gz-sim/pull/1345) 1. Fixed light gui component inspector - * [Pull request #1337](https://github.com/ignitionrobotics/ign-gazebo/pull/1337) + * [Pull request #1337](https://github.com/gazebosim/gz-sim/pull/1337) 1. Fix UNIT_SdfGenerator_TEST - * [Pull request #1319](https://github.com/ignitionrobotics/ign-gazebo/pull/1319) + * [Pull request #1319](https://github.com/gazebosim/gz-sim/pull/1319) 1. Add elevator system - * [Pull request #535](https://github.com/ignitionrobotics/ign-gazebo/pull/535) + * [Pull request #535](https://github.com/gazebosim/gz-sim/pull/535) 1. Removed unused variables in shapes plugin - * [Pull request #1321](https://github.com/ignitionrobotics/ign-gazebo/pull/1321) + * [Pull request #1321](https://github.com/gazebosim/gz-sim/pull/1321) -### Ignition Gazebo 6.5.0 (2022-02-15) +### Gazebo Sim 6.5.0 (2022-02-15) 1. New trajectory follower system - * [Pull request #1332](https://github.com/ignitionrobotics/ign-gazebo/pull/1332) + * [Pull request #1332](https://github.com/gazebosim/gz-sim/pull/1332) 1. Extend ShaderParam system to support textures - * [Pull request #1310](https://github.com/ignitionrobotics/ign-gazebo/pull/1310) + * [Pull request #1310](https://github.com/gazebosim/gz-sim/pull/1310) 1. Adds a `Link::SetLinearVelocity()` method - * [Pull request #1323](https://github.com/ignitionrobotics/ign-gazebo/pull/1323) + * [Pull request #1323](https://github.com/gazebosim/gz-sim/pull/1323) 1. Fix weird indentation in `Link.hh` - * [Pull request #1324](https://github.com/ignitionrobotics/ign-gazebo/pull/1324) + * [Pull request #1324](https://github.com/gazebosim/gz-sim/pull/1324) 1. Limit thruster system's input thrust cmd - * [Pull request #1318](https://github.com/ignitionrobotics/ign-gazebo/pull/1318) + * [Pull request #1318](https://github.com/gazebosim/gz-sim/pull/1318) 1. Load and run visual plugin (system) on GUI side - * [Pull request #1275](https://github.com/ignitionrobotics/ign-gazebo/pull/1275) + * [Pull request #1275](https://github.com/gazebosim/gz-sim/pull/1275) 1. Log an error if JointPositionController cannot find the joint. (citadel retarget) - * [Pull request #1314](https://github.com/ignitionrobotics/ign-gazebo/pull/1314) + * [Pull request #1314](https://github.com/gazebosim/gz-sim/pull/1314) 1. Update source install instructions - * [Pull request #1311](https://github.com/ignitionrobotics/ign-gazebo/pull/1311) + * [Pull request #1311](https://github.com/gazebosim/gz-sim/pull/1311) 1. Document the `` option for JointPositionController. - * [Pull request #1309](https://github.com/ignitionrobotics/ign-gazebo/pull/1309) + * [Pull request #1309](https://github.com/gazebosim/gz-sim/pull/1309) 1. Fix typo in EntityComponentManager - * [Pull request #1304](https://github.com/ignitionrobotics/ign-gazebo/pull/1304) + * [Pull request #1304](https://github.com/gazebosim/gz-sim/pull/1304) 1. Buoyancy: fix center of volume's reference frame - * [Pull request #1302](https://github.com/ignitionrobotics/ign-gazebo/pull/1302) + * [Pull request #1302](https://github.com/gazebosim/gz-sim/pull/1302) 1. Fix graded buoyancy problems - * [Pull request #1297](https://github.com/ignitionrobotics/ign-gazebo/pull/1297) + * [Pull request #1297](https://github.com/gazebosim/gz-sim/pull/1297) 1. Add surface to buoyancy engine. (retarget fortress) - * [Pull request #1298](https://github.com/ignitionrobotics/ign-gazebo/pull/1298) + * [Pull request #1298](https://github.com/gazebosim/gz-sim/pull/1298) 1. Remove EachNew calls from sensor PreUpdates - * [Pull request #1281](https://github.com/ignitionrobotics/ign-gazebo/pull/1281) + * [Pull request #1281](https://github.com/gazebosim/gz-sim/pull/1281) 1. Prevent GzScene3D 💥 if another scene is already loaded - * [Pull request #1294](https://github.com/ignitionrobotics/ign-gazebo/pull/1294) + * [Pull request #1294](https://github.com/gazebosim/gz-sim/pull/1294) 1. Fix various typos on API documentation - * [Pull request #1291](https://github.com/ignitionrobotics/ign-gazebo/pull/1291) + * [Pull request #1291](https://github.com/gazebosim/gz-sim/pull/1291) 1. Optional orientation when spawning entity using spherical coordinates - * [Pull request #1263](https://github.com/ignitionrobotics/ign-gazebo/pull/1263) + * [Pull request #1263](https://github.com/gazebosim/gz-sim/pull/1263) 1. Cleanup update call for non-rendering sensors - * [Pull request #1282](https://github.com/ignitionrobotics/ign-gazebo/pull/1282) + * [Pull request #1282](https://github.com/gazebosim/gz-sim/pull/1282) 1. Documentation Error - * [Pull request #1285](https://github.com/ignitionrobotics/ign-gazebo/pull/1285) + * [Pull request #1285](https://github.com/gazebosim/gz-sim/pull/1285) 1. Min and max parameters for velocity, acceleration, and jerk apply to linear and angular separately. - * [Pull request #1229](https://github.com/ignitionrobotics/ign-gazebo/pull/1229) + * [Pull request #1229](https://github.com/gazebosim/gz-sim/pull/1229) 1. Add project() call to examples - * [Pull request #1274](https://github.com/ignitionrobotics/ign-gazebo/pull/1274) + * [Pull request #1274](https://github.com/gazebosim/gz-sim/pull/1274) 1. Implement /server_control::stop - * [Pull request #1240](https://github.com/ignitionrobotics/ign-gazebo/pull/1240) + * [Pull request #1240](https://github.com/gazebosim/gz-sim/pull/1240) -### Ignition Gazebo 6.4.0 (2021-01-13) +### Gazebo Sim 6.4.0 (2021-01-13) 1. Disable more tests on Windows - * [Pull request #1286](https://github.com/ignitionrobotics/ign-gazebo/pull/1286) + * [Pull request #1286](https://github.com/gazebosim/gz-sim/pull/1286) 1. Adding angular acceleration to the Link class - * [Pull request #1288](https://github.com/ignitionrobotics/ign-gazebo/pull/1288) + * [Pull request #1288](https://github.com/gazebosim/gz-sim/pull/1288) 1. Add world force - * [Pull request #1279](https://github.com/ignitionrobotics/ign-gazebo/pull/1279) + * [Pull request #1279](https://github.com/gazebosim/gz-sim/pull/1279) 1. Add NavSat sensor (GPS) - * [Pull request #1248](https://github.com/ignitionrobotics/ign-gazebo/pull/1248) + * [Pull request #1248](https://github.com/gazebosim/gz-sim/pull/1248) 1. Light Commands via topic - * [Pull request #1222](https://github.com/ignitionrobotics/ign-gazebo/pull/1222) + * [Pull request #1222](https://github.com/gazebosim/gz-sim/pull/1222) 1. Support battery draining start via topics - * [Pull request #1255](https://github.com/ignitionrobotics/ign-gazebo/pull/1255) + * [Pull request #1255](https://github.com/gazebosim/gz-sim/pull/1255) 1. Add visibility to ModelEditorAddEntity to fix Windows - * [Pull request #1246](https://github.com/ignitionrobotics/ign-gazebo/pull/1246) + * [Pull request #1246](https://github.com/gazebosim/gz-sim/pull/1246) 1. Make tests run as fast as possible - * [Pull request #1194](https://github.com/ignitionrobotics/ign-gazebo/pull/1194) + * [Pull request #1194](https://github.com/gazebosim/gz-sim/pull/1194) 1. Fix visualize lidar - * [Pull request #1224](https://github.com/ignitionrobotics/ign-gazebo/pull/1224) + * [Pull request #1224](https://github.com/gazebosim/gz-sim/pull/1224) 1. Disable user commands light test on macOS - * [Pull request #1204](https://github.com/ignitionrobotics/ign-gazebo/pull/1204) + * [Pull request #1204](https://github.com/gazebosim/gz-sim/pull/1204) 1. Skip failing Windows tests - * [Pull request #1205](https://github.com/ignitionrobotics/ign-gazebo/pull/1205) + * [Pull request #1205](https://github.com/gazebosim/gz-sim/pull/1205) -### Ignition Gazebo 6.3.0 (2021-12-10) +### Gazebo Sim 6.3.0 (2021-12-10) 1. View entity frames from the GUI - * [Pull request #1105](https://github.com/ignitionrobotics/ign-gazebo/pull/1105) + * [Pull request #1105](https://github.com/gazebosim/gz-sim/pull/1105) 1. Model editor - * [Pull request #1231](https://github.com/ignitionrobotics/ign-gazebo/pull/1231) + * [Pull request #1231](https://github.com/gazebosim/gz-sim/pull/1231) 1. Send state message when components are removed - * [Pull request #1235](https://github.com/ignitionrobotics/ign-gazebo/pull/1235) + * [Pull request #1235](https://github.com/gazebosim/gz-sim/pull/1235) 1. Docker fixes for Fortress - * [Pull request #1238](https://github.com/ignitionrobotics/ign-gazebo/pull/1238) + * [Pull request #1238](https://github.com/gazebosim/gz-sim/pull/1238) 1. Added sensor plugin to be able to visualize camera in `plane_propeller_demo.sdf` - * [Pull request #1226](https://github.com/ignitionrobotics/ign-gazebo/pull/1226) + * [Pull request #1226](https://github.com/gazebosim/gz-sim/pull/1226) 1. Update SdfGenerator to save link and sensor data to file - * [Pull request #1201](https://github.com/ignitionrobotics/ign-gazebo/pull/1201) + * [Pull request #1201](https://github.com/gazebosim/gz-sim/pull/1201) 1. Fix buoyancy not being applied for one iteration - * [Pull request #1211](https://github.com/ignitionrobotics/ign-gazebo/pull/1211) + * [Pull request #1211](https://github.com/gazebosim/gz-sim/pull/1211) 1. Increase maximum values in ViewAngle widget and increase its size - * [Pull request #1221](https://github.com/ignitionrobotics/ign-gazebo/pull/1221) - * [Pull request #1239](https://github.com/ignitionrobotics/ign-gazebo/pull/1239) + * [Pull request #1221](https://github.com/gazebosim/gz-sim/pull/1221) + * [Pull request #1239](https://github.com/gazebosim/gz-sim/pull/1239) 1. Fix the force-torque sensor update rate - * [Pull request #1159](https://github.com/ignitionrobotics/ign-gazebo/pull/1159) + * [Pull request #1159](https://github.com/gazebosim/gz-sim/pull/1159) -### Ignition Gazebo 6.2.0 (2021-11-16) +### Gazebo Sim 6.2.0 (2021-11-16) 1. Configurable joint state publisher's topic - * [Pull request #1076](https://github.com/ignitionrobotics/ign-gazebo/pull/1076) + * [Pull request #1076](https://github.com/gazebosim/gz-sim/pull/1076) 1. Thruster plugin: add tests and velocity control - * [Pull request #1190](https://github.com/ignitionrobotics/ign-gazebo/pull/1190) + * [Pull request #1190](https://github.com/gazebosim/gz-sim/pull/1190) 1. Prevent creation of spurious `` elements when saving worlds - * [Pull request #1192](https://github.com/ignitionrobotics/ign-gazebo/pull/1192) + * [Pull request #1192](https://github.com/gazebosim/gz-sim/pull/1192) 1. Add `sdfString` to `ServerConfig`'s copy constructor. - * [Pull request #1185](https://github.com/ignitionrobotics/ign-gazebo/pull/1185) + * [Pull request #1185](https://github.com/gazebosim/gz-sim/pull/1185) 1. Added support for tracked vehicles - * [Pull request #869](https://github.com/ignitionrobotics/ign-gazebo/pull/869) + * [Pull request #869](https://github.com/gazebosim/gz-sim/pull/869) 1. Add components to dynamically set joint limits - * [Pull request #847](https://github.com/ignitionrobotics/ign-gazebo/pull/847) + * [Pull request #847](https://github.com/gazebosim/gz-sim/pull/847) 1. Remove bounding box when entities are removed - * [Pull request #1053](https://github.com/ignitionrobotics/ign-gazebo/pull/1053) - * [Pull request #1213](https://github.com/ignitionrobotics/ign-gazebo/pull/1213) + * [Pull request #1053](https://github.com/gazebosim/gz-sim/pull/1053) + * [Pull request #1213](https://github.com/gazebosim/gz-sim/pull/1213) 1. Fix updating component from state - * [Pull request #1181](https://github.com/ignitionrobotics/ign-gazebo/pull/1181) + * [Pull request #1181](https://github.com/gazebosim/gz-sim/pull/1181) 1. Extend odom publisher to allow 3D - * [Pull request #1180](https://github.com/ignitionrobotics/ign-gazebo/pull/1180) + * [Pull request #1180](https://github.com/gazebosim/gz-sim/pull/1180) 1. Support copy/paste - * [Pull request #1013](https://github.com/ignitionrobotics/ign-gazebo/pull/1013) + * [Pull request #1013](https://github.com/gazebosim/gz-sim/pull/1013) 1. Tweaks install instructions - * [Pull request #1078](https://github.com/ignitionrobotics/ign-gazebo/pull/1078) + * [Pull request #1078](https://github.com/gazebosim/gz-sim/pull/1078) 1. Publish 10 world stats msgs/sec instead of 5 - * [Pull request #1163](https://github.com/ignitionrobotics/ign-gazebo/pull/1163) + * [Pull request #1163](https://github.com/gazebosim/gz-sim/pull/1163) 1. Add functionality to add entities via the entity tree - * [Pull request #1101](https://github.com/ignitionrobotics/ign-gazebo/pull/1101) + * [Pull request #1101](https://github.com/gazebosim/gz-sim/pull/1101) 1. Get updated GUI ECM info when a user presses 'play' - * [Pull request #1109](https://github.com/ignitionrobotics/ign-gazebo/pull/1109) + * [Pull request #1109](https://github.com/gazebosim/gz-sim/pull/1109) 1. Create expanding type header to reduce code duplication - * [Pull request #1169](https://github.com/ignitionrobotics/ign-gazebo/pull/1169) + * [Pull request #1169](https://github.com/gazebosim/gz-sim/pull/1169) 1. `minimal_scene.sdf` example: add `camera_clip` params - * [Pull request #1166](https://github.com/ignitionrobotics/ign-gazebo/pull/1166) + * [Pull request #1166](https://github.com/gazebosim/gz-sim/pull/1166) 1. Sensor systems work if loaded after sensors - * [Pull request #1104](https://github.com/ignitionrobotics/ign-gazebo/pull/1104) + * [Pull request #1104](https://github.com/gazebosim/gz-sim/pull/1104) 1. Support printing sensors using `ign model` - * [Pull request #1157](https://github.com/ignitionrobotics/ign-gazebo/pull/1157) + * [Pull request #1157](https://github.com/gazebosim/gz-sim/pull/1157) 1. Set camera clipping plane distances from the GUI - * [Pull request #1162](https://github.com/ignitionrobotics/ign-gazebo/pull/1162) + * [Pull request #1162](https://github.com/gazebosim/gz-sim/pull/1162) 1. Fix generation of systems library symlinks in build directory - * [Pull request #1160](https://github.com/ignitionrobotics/ign-gazebo/pull/1160) + * [Pull request #1160](https://github.com/gazebosim/gz-sim/pull/1160) 1. Add a default value for `isHeadlessRendering`. - * [Pull request #1151](https://github.com/ignitionrobotics/ign-gazebo/pull/1151) + * [Pull request #1151](https://github.com/gazebosim/gz-sim/pull/1151) 1. Component inspector 1. Edit material colors - * [Pull request #1123](https://github.com/ignitionrobotics/ign-gazebo/pull/1123) - * [Pull request #1186](https://github.com/ignitionrobotics/ign-gazebo/pull/1186) + * [Pull request #1123](https://github.com/gazebosim/gz-sim/pull/1123) + * [Pull request #1186](https://github.com/gazebosim/gz-sim/pull/1186) 1. Fix integers and floats - * [Pull request #1143](https://github.com/ignitionrobotics/ign-gazebo/pull/1143) + * [Pull request #1143](https://github.com/gazebosim/gz-sim/pull/1143) 1. Prevent a segfault when updating - * [Pull request #1167](https://github.com/ignitionrobotics/ign-gazebo/pull/1167) + * [Pull request #1167](https://github.com/gazebosim/gz-sim/pull/1167) 1. Use `uint64_t` for Entity IDs - * [Pull request #1144](https://github.com/ignitionrobotics/ign-gazebo/pull/1144) + * [Pull request #1144](https://github.com/gazebosim/gz-sim/pull/1144) 1. Support setting the background color for sensors - * [Pull request #1147](https://github.com/ignitionrobotics/ign-gazebo/pull/1147) + * [Pull request #1147](https://github.com/gazebosim/gz-sim/pull/1147) 1. Select top level entity not visual - * [Pull request #1150](https://github.com/ignitionrobotics/ign-gazebo/pull/1150) + * [Pull request #1150](https://github.com/gazebosim/gz-sim/pull/1150) 1. Update create entity offset on GUI side - * [Pull request #1145](https://github.com/ignitionrobotics/ign-gazebo/pull/1145) + * [Pull request #1145](https://github.com/gazebosim/gz-sim/pull/1145) 1. Update Select Entities GUI plugin to use Entity type - * [Pull request #1146](https://github.com/ignitionrobotics/ign-gazebo/pull/1146) + * [Pull request #1146](https://github.com/gazebosim/gz-sim/pull/1146) 1. Notify other GUI plugins of added/removed entities via GUI events - * [Pull request #1138](https://github.com/ignitionrobotics/ign-gazebo/pull/1138) - * [Pull request #1213](https://github.com/ignitionrobotics/ign-gazebo/pull/1213) + * [Pull request #1138](https://github.com/gazebosim/gz-sim/pull/1138) + * [Pull request #1213](https://github.com/gazebosim/gz-sim/pull/1213) -### Ignition Gazebo 6.1.0 (2021-10-25) +### Gazebo Sim 6.1.0 (2021-10-25) 1. Updates to camera video record from subt - * [Pull request #1117](https://github.com/ignitionrobotics/ign-gazebo/pull/1117) + * [Pull request #1117](https://github.com/gazebosim/gz-sim/pull/1117) 1. Use the actor tension parameter - * [Pull request #1091](https://github.com/ignitionrobotics/ign-gazebo/pull/1091) + * [Pull request #1091](https://github.com/gazebosim/gz-sim/pull/1091) 1. Better protect this->dataPtr->initialized with renderMutex. - * [Pull request #1119](https://github.com/ignitionrobotics/ign-gazebo/pull/1119) + * [Pull request #1119](https://github.com/gazebosim/gz-sim/pull/1119) 1. Use QTimer to update plugins in the Qt thread - * [Pull request #1095](https://github.com/ignitionrobotics/ign-gazebo/pull/1095) + * [Pull request #1095](https://github.com/gazebosim/gz-sim/pull/1095) 1. Adjust pose decimals based on element width - * [Pull request #1089](https://github.com/ignitionrobotics/ign-gazebo/pull/1089) + * [Pull request #1089](https://github.com/gazebosim/gz-sim/pull/1089) 1. JointPositionController: Improve misleading error message - * [Pull request #1098](https://github.com/ignitionrobotics/ign-gazebo/pull/1098) + * [Pull request #1098](https://github.com/gazebosim/gz-sim/pull/1098) 1. Fixed IMU system plugin - * [Pull request #1043](https://github.com/ignitionrobotics/ign-gazebo/pull/1043) + * [Pull request #1043](https://github.com/gazebosim/gz-sim/pull/1043) 1. Prevent crash and print error - * [Pull request #1099](https://github.com/ignitionrobotics/ign-gazebo/pull/1099) + * [Pull request #1099](https://github.com/gazebosim/gz-sim/pull/1099) 1. Create GUI config folder before copying config - * [Pull request #1092](https://github.com/ignitionrobotics/ign-gazebo/pull/1092) + * [Pull request #1092](https://github.com/gazebosim/gz-sim/pull/1092) 1. Add support for configuring point size in Visualize Lidar GUI plugin - * [Pull request #1021](https://github.com/ignitionrobotics/ign-gazebo/pull/1021) + * [Pull request #1021](https://github.com/gazebosim/gz-sim/pull/1021) 1. Set a cloned joint's parent/child link names to the cloned parent/child link names - * [Pull request #1075](https://github.com/ignitionrobotics/ign-gazebo/pull/1075) + * [Pull request #1075](https://github.com/gazebosim/gz-sim/pull/1075) 1. Performance: use std::unordered_map where possible in SceneManager - * [Pull request #1083](https://github.com/ignitionrobotics/ign-gazebo/pull/1083) + * [Pull request #1083](https://github.com/gazebosim/gz-sim/pull/1083) 1. Fix transform controls - * [Pull request #1081](https://github.com/ignitionrobotics/ign-gazebo/pull/1081) + * [Pull request #1081](https://github.com/gazebosim/gz-sim/pull/1081) 1. Fix View Angle's home button - * [Pull request #1082](https://github.com/ignitionrobotics/ign-gazebo/pull/1082) + * [Pull request #1082](https://github.com/gazebosim/gz-sim/pull/1082) 1. Fix light control standalone example - * [Pull request #1077](https://github.com/ignitionrobotics/ign-gazebo/pull/1077) + * [Pull request #1077](https://github.com/gazebosim/gz-sim/pull/1077) 1. Parse new param for enabling / disabling IMU orientation output - * [Pull request #899](https://github.com/ignitionrobotics/ign-gazebo/pull/899) + * [Pull request #899](https://github.com/gazebosim/gz-sim/pull/899) -### Ignition Gazebo 6.0.0 (2021-10-01) +### Gazebo Sim 6.0.0 (2021-10-01) 1. Deprecated GzScene3D in favor of MinimalScene - * [Pull request #1065](https://github.com/ignitionrobotics/ign-gazebo/pull/1065) - * [Pull request #1051](https://github.com/ignitionrobotics/ign-gazebo/pull/1051) - * [Pull request #1014](https://github.com/ignitionrobotics/ign-gazebo/pull/1014) - * [Pull request #1034](https://github.com/ignitionrobotics/ign-gazebo/pull/1034) - * [Pull request #900](https://github.com/ignitionrobotics/ign-gazebo/pull/900) - * [Pull request #988](https://github.com/ignitionrobotics/ign-gazebo/pull/988) - * [Pull request #1016](https://github.com/ignitionrobotics/ign-gazebo/pull/1016) - * [Pull request #983](https://github.com/ignitionrobotics/ign-gazebo/pull/983) - * [Pull request #854](https://github.com/ignitionrobotics/ign-gazebo/pull/854) - * [Pull request #813](https://github.com/ignitionrobotics/ign-gazebo/pull/813) - * [Pull request #905](https://github.com/ignitionrobotics/ign-gazebo/pull/905) + * [Pull request #1065](https://github.com/gazebosim/gz-sim/pull/1065) + * [Pull request #1051](https://github.com/gazebosim/gz-sim/pull/1051) + * [Pull request #1014](https://github.com/gazebosim/gz-sim/pull/1014) + * [Pull request #1034](https://github.com/gazebosim/gz-sim/pull/1034) + * [Pull request #900](https://github.com/gazebosim/gz-sim/pull/900) + * [Pull request #988](https://github.com/gazebosim/gz-sim/pull/988) + * [Pull request #1016](https://github.com/gazebosim/gz-sim/pull/1016) + * [Pull request #983](https://github.com/gazebosim/gz-sim/pull/983) + * [Pull request #854](https://github.com/gazebosim/gz-sim/pull/854) + * [Pull request #813](https://github.com/gazebosim/gz-sim/pull/813) + * [Pull request #905](https://github.com/gazebosim/gz-sim/pull/905) 1. Fix GuiRunner initial state and entity spawn timing issue - * [Pull request #1073](https://github.com/ignitionrobotics/ign-gazebo/pull/1073) + * [Pull request #1073](https://github.com/gazebosim/gz-sim/pull/1073) 1. Buoyancy plugin upgrade - * [Pull request #818](https://github.com/ignitionrobotics/ign-gazebo/pull/818) - * [Pull request #1067](https://github.com/ignitionrobotics/ign-gazebo/pull/1067) - * [Pull request #1064](https://github.com/ignitionrobotics/ign-gazebo/pull/1064) + * [Pull request #818](https://github.com/gazebosim/gz-sim/pull/818) + * [Pull request #1067](https://github.com/gazebosim/gz-sim/pull/1067) + * [Pull request #1064](https://github.com/gazebosim/gz-sim/pull/1064) 1. Fix non desired window opening alongside ignition GUI - * [Pull request #1063](https://github.com/ignitionrobotics/ign-gazebo/pull/1063) + * [Pull request #1063](https://github.com/gazebosim/gz-sim/pull/1063) 1. Documentation - * [Pull request #1074](https://github.com/ignitionrobotics/ign-gazebo/pull/1074) - * [Pull request #996](https://github.com/ignitionrobotics/ign-gazebo/pull/996) + * [Pull request #1074](https://github.com/gazebosim/gz-sim/pull/1074) + * [Pull request #996](https://github.com/gazebosim/gz-sim/pull/996) 1. Update to latest SDFormat changes - * [Pull request #1069](https://github.com/ignitionrobotics/ign-gazebo/pull/1069) - * [Pull request #1023](https://github.com/ignitionrobotics/ign-gazebo/pull/1023) + * [Pull request #1069](https://github.com/gazebosim/gz-sim/pull/1069) + * [Pull request #1023](https://github.com/gazebosim/gz-sim/pull/1023) 1. Suppress missing canonical link error messages for static models - * [Pull request #1068](https://github.com/ignitionrobotics/ign-gazebo/pull/1068) + * [Pull request #1068](https://github.com/gazebosim/gz-sim/pull/1068) 1. Heightmap fixes - * [Pull request #1055](https://github.com/ignitionrobotics/ign-gazebo/pull/1055) - * [Pull request #1054](https://github.com/ignitionrobotics/ign-gazebo/pull/1054) + * [Pull request #1055](https://github.com/gazebosim/gz-sim/pull/1055) + * [Pull request #1054](https://github.com/gazebosim/gz-sim/pull/1054) 1. Place config files in a versioned directory - * [Pull request #1050](https://github.com/ignitionrobotics/ign-gazebo/pull/1050) - * [Pull request #1070](https://github.com/ignitionrobotics/ign-gazebo/pull/1070) + * [Pull request #1050](https://github.com/gazebosim/gz-sim/pull/1050) + * [Pull request #1070](https://github.com/gazebosim/gz-sim/pull/1070) 1. Fix GUI crash when accessing bad rendering UserData - * [Pull request #1052](https://github.com/ignitionrobotics/ign-gazebo/pull/1052) + * [Pull request #1052](https://github.com/gazebosim/gz-sim/pull/1052) 1. Fix performance issue with contact data and AABB updates - * [Pull request #1048](https://github.com/ignitionrobotics/ign-gazebo/pull/1048) + * [Pull request #1048](https://github.com/gazebosim/gz-sim/pull/1048) 1. Enable new policy to fix protobuf compilation errors - * [Pull request #1046](https://github.com/ignitionrobotics/ign-gazebo/pull/1046) + * [Pull request #1046](https://github.com/gazebosim/gz-sim/pull/1046) 1. Support locked entities, and headless video recording using sim time - * [Pull request #862](https://github.com/ignitionrobotics/ign-gazebo/pull/862) + * [Pull request #862](https://github.com/gazebosim/gz-sim/pull/862) 1. Label Component & System, segmentation camera support - * [Pull request #853](https://github.com/ignitionrobotics/ign-gazebo/pull/853) - * [Pull request #1047](https://github.com/ignitionrobotics/ign-gazebo/pull/1047) + * [Pull request #853](https://github.com/gazebosim/gz-sim/pull/853) + * [Pull request #1047](https://github.com/gazebosim/gz-sim/pull/1047) 1. Joint Force-Torque Systems Plugin - * [Pull request #977](https://github.com/ignitionrobotics/ign-gazebo/pull/977) + * [Pull request #977](https://github.com/gazebosim/gz-sim/pull/977) 1. Add support for cloning entities - * [Pull request #959](https://github.com/ignitionrobotics/ign-gazebo/pull/959) + * [Pull request #959](https://github.com/gazebosim/gz-sim/pull/959) 1. 🌐 Spherical coordinates - * [Pull request #1008](https://github.com/ignitionrobotics/ign-gazebo/pull/1008) + * [Pull request #1008](https://github.com/gazebosim/gz-sim/pull/1008) 1. Populate JointConstraintWrench from physics - * [Pull request #989](https://github.com/ignitionrobotics/ign-gazebo/pull/989) + * [Pull request #989](https://github.com/gazebosim/gz-sim/pull/989) 1. Buoyancy engine - * [Pull request #1009](https://github.com/ignitionrobotics/ign-gazebo/pull/1009) + * [Pull request #1009](https://github.com/gazebosim/gz-sim/pull/1009) 1. Infrastructure - * [Pull request #1033](https://github.com/ignitionrobotics/ign-gazebo/pull/1033) - * [Pull request #1029](https://github.com/ignitionrobotics/ign-gazebo/pull/1029) - * [Pull request #991](https://github.com/ignitionrobotics/ign-gazebo/pull/991) - * [Pull request #809](https://github.com/ignitionrobotics/ign-gazebo/pull/809) + * [Pull request #1033](https://github.com/gazebosim/gz-sim/pull/1033) + * [Pull request #1029](https://github.com/gazebosim/gz-sim/pull/1029) + * [Pull request #991](https://github.com/gazebosim/gz-sim/pull/991) + * [Pull request #809](https://github.com/gazebosim/gz-sim/pull/809) 1. Update on resize instead of pre-render / render - * [Pull request #1028](https://github.com/ignitionrobotics/ign-gazebo/pull/1028) + * [Pull request #1028](https://github.com/gazebosim/gz-sim/pull/1028) 1. Add a flag to force headless rendering mode - * [Pull request #701](https://github.com/ignitionrobotics/ign-gazebo/pull/701) + * [Pull request #701](https://github.com/gazebosim/gz-sim/pull/701) 1. Remove unused ignition gui header - * [Pull request #1026](https://github.com/ignitionrobotics/ign-gazebo/pull/1026) + * [Pull request #1026](https://github.com/gazebosim/gz-sim/pull/1026) 1. Adds velocity control to JointPositionController. - * [Pull request #1003](https://github.com/ignitionrobotics/ign-gazebo/pull/1003) + * [Pull request #1003](https://github.com/gazebosim/gz-sim/pull/1003) 1. Collada world exporter now exporting lights - * [Pull request #912](https://github.com/ignitionrobotics/ign-gazebo/pull/912) + * [Pull request #912](https://github.com/gazebosim/gz-sim/pull/912) 1. Workaround for setting visual cast shadows without material - * [Pull request #1015](https://github.com/ignitionrobotics/ign-gazebo/pull/1015) + * [Pull request #1015](https://github.com/gazebosim/gz-sim/pull/1015) 1. Fix selection buffer crash on resize - * [Pull request #969](https://github.com/ignitionrobotics/ign-gazebo/pull/969) + * [Pull request #969](https://github.com/gazebosim/gz-sim/pull/969) 1. Remove extra xml version line in pendulum_links example world - * [Pull request #1002](https://github.com/ignitionrobotics/ign-gazebo/pull/1002) + * [Pull request #1002](https://github.com/gazebosim/gz-sim/pull/1002) 1. Enable sensor metrics on example worlds - * [Pull request #982](https://github.com/ignitionrobotics/ign-gazebo/pull/982) + * [Pull request #982](https://github.com/gazebosim/gz-sim/pull/982) 1. Add ESC to unselect entities in select entities plugin - * [Pull request #995](https://github.com/ignitionrobotics/ign-gazebo/pull/995) + * [Pull request #995](https://github.com/gazebosim/gz-sim/pull/995) 1. Visualize joints - * [Pull request #961](https://github.com/ignitionrobotics/ign-gazebo/pull/961) + * [Pull request #961](https://github.com/gazebosim/gz-sim/pull/961) 1. Deprecate particle emitter, and use scatter ratio in new particle mes… - * [Pull request #986](https://github.com/ignitionrobotics/ign-gazebo/pull/986) + * [Pull request #986](https://github.com/gazebosim/gz-sim/pull/986) 1. Removed unused variable in Shapes plugin - * [Pull request #984](https://github.com/ignitionrobotics/ign-gazebo/pull/984) + * [Pull request #984](https://github.com/gazebosim/gz-sim/pull/984) 1. Use root.Model() - * [Pull request #980](https://github.com/ignitionrobotics/ign-gazebo/pull/980) + * [Pull request #980](https://github.com/gazebosim/gz-sim/pull/980) 1. Add ModelSDF serializer - * [Pull request #851](https://github.com/ignitionrobotics/ign-gazebo/pull/851) + * [Pull request #851](https://github.com/gazebosim/gz-sim/pull/851) 1. Entity tree: prevent creation of repeated entity items - * [Pull request #974](https://github.com/ignitionrobotics/ign-gazebo/pull/974) + * [Pull request #974](https://github.com/gazebosim/gz-sim/pull/974) 1. Use statically-typed views for better performance - * [Pull request #856](https://github.com/ignitionrobotics/ign-gazebo/pull/856) - * [Pull request #1001](https://github.com/ignitionrobotics/ign-gazebo/pull/1001) + * [Pull request #856](https://github.com/gazebosim/gz-sim/pull/856) + * [Pull request #1001](https://github.com/gazebosim/gz-sim/pull/1001) 1. Upgrade ign-sensors and support custom sensors - * [Pull request #617](https://github.com/ignitionrobotics/ign-gazebo/pull/617) + * [Pull request #617](https://github.com/gazebosim/gz-sim/pull/617) 1. Fix entity creation console msg - * [Pull request #972](https://github.com/ignitionrobotics/ign-gazebo/pull/972) + * [Pull request #972](https://github.com/gazebosim/gz-sim/pull/972) 1. Fix crash in the follow_actor example - * [Pull request #958](https://github.com/ignitionrobotics/ign-gazebo/pull/958) + * [Pull request #958](https://github.com/gazebosim/gz-sim/pull/958) 1. Removed pose topic from log system - * [Pull request #839](https://github.com/ignitionrobotics/ign-gazebo/pull/839) + * [Pull request #839](https://github.com/gazebosim/gz-sim/pull/839) 1. Be more specific when looking for physics plugins - * [Pull request #965](https://github.com/ignitionrobotics/ign-gazebo/pull/965) + * [Pull request #965](https://github.com/gazebosim/gz-sim/pull/965) 1. Complaint if Joint doesn't exists before adding joint controller - * [Pull request #786](https://github.com/ignitionrobotics/ign-gazebo/pull/786) + * [Pull request #786](https://github.com/gazebosim/gz-sim/pull/786) 1. [DiffDrive] add enable/disable - * [Pull request #772](https://github.com/ignitionrobotics/ign-gazebo/pull/772) + * [Pull request #772](https://github.com/gazebosim/gz-sim/pull/772) 1. Fix component inspector shutdown crash - * [Pull request #724](https://github.com/ignitionrobotics/ign-gazebo/pull/724) + * [Pull request #724](https://github.com/gazebosim/gz-sim/pull/724) 1. Setting the intiial velocity for a model or joint - * [Pull request #693](https://github.com/ignitionrobotics/ign-gazebo/pull/693) + * [Pull request #693](https://github.com/gazebosim/gz-sim/pull/693) 1. Examples and tutorial on using rendering API from plugins - * [Pull request #596](https://github.com/ignitionrobotics/ign-gazebo/pull/596) + * [Pull request #596](https://github.com/gazebosim/gz-sim/pull/596) -1. Add missing IGNITION_GAZEBO_VISIBLE macros - * [Pull request #563](https://github.com/ignitionrobotics/ign-gazebo/pull/563) +1. Add missing GZ_GAZEBO_VISIBLE macros + * [Pull request #563](https://github.com/gazebosim/gz-sim/pull/563) 1. Fix visibility macro names when used by a different component (Windows) - * [Pull request #564](https://github.com/ignitionrobotics/ign-gazebo/pull/564) + * [Pull request #564](https://github.com/gazebosim/gz-sim/pull/564) 1. No install apt recommends and clear cache - * [Pull request #423](https://github.com/ignitionrobotics/ign-gazebo/pull/423) + * [Pull request #423](https://github.com/gazebosim/gz-sim/pull/423) 1. Support adding systems that don't come from a plugin - * [Pull request #936](https://github.com/ignitionrobotics/ign-gazebo/pull/936) + * [Pull request #936](https://github.com/gazebosim/gz-sim/pull/936) 1. Fix tests that use multiple root level models or lights - * [Pull request #931](https://github.com/ignitionrobotics/ign-gazebo/pull/931) + * [Pull request #931](https://github.com/gazebosim/gz-sim/pull/931) -1. Make Gazebo aware of SetCameraPassCountPerGpuFlush - * [Pull request #921](https://github.com/ignitionrobotics/ign-gazebo/pull/921) +1. Make Gazebo Sim aware of SetCameraPassCountPerGpuFlush + * [Pull request #921](https://github.com/gazebosim/gz-sim/pull/921) 1. Visualize center of mass - * [Pull request #903](https://github.com/ignitionrobotics/ign-gazebo/pull/903) + * [Pull request #903](https://github.com/gazebosim/gz-sim/pull/903) 1. Transparent mode - * [Pull request #878](https://github.com/ignitionrobotics/ign-gazebo/pull/878) + * [Pull request #878](https://github.com/gazebosim/gz-sim/pull/878) 1. Visualize inertia - * [Pull request #861](https://github.com/ignitionrobotics/ign-gazebo/pull/861) + * [Pull request #861](https://github.com/gazebosim/gz-sim/pull/861) 1. Remove deprecations: tock 🕑 - * [Pull request #875](https://github.com/ignitionrobotics/ign-gazebo/pull/875) + * [Pull request #875](https://github.com/gazebosim/gz-sim/pull/875) 1. Removed and moved tape measure and grid config to ign-gui - * [Pull request #870](https://github.com/ignitionrobotics/ign-gazebo/pull/870) + * [Pull request #870](https://github.com/gazebosim/gz-sim/pull/870) 1. Update wireframe visualization to support nested models - * [Pull request #832](https://github.com/ignitionrobotics/ign-gazebo/pull/832) + * [Pull request #832](https://github.com/gazebosim/gz-sim/pull/832) 1. Multi-LRAUV Swimming Race Example - * [Pull request #841](https://github.com/ignitionrobotics/ign-gazebo/pull/841) + * [Pull request #841](https://github.com/gazebosim/gz-sim/pull/841) 1. Add view control gui plugin and support orthographic view - * [Pull request #815](https://github.com/ignitionrobotics/ign-gazebo/pull/815) + * [Pull request #815](https://github.com/gazebosim/gz-sim/pull/815) 1. Wireframe mode - * [Pull request #816](https://github.com/ignitionrobotics/ign-gazebo/pull/816) + * [Pull request #816](https://github.com/gazebosim/gz-sim/pull/816) 1. Explain why detail::View symbols are visible - * [Pull request #788](https://github.com/ignitionrobotics/ign-gazebo/pull/788) + * [Pull request #788](https://github.com/gazebosim/gz-sim/pull/788) 1. Bump dependencies in fortress - * [Pull request #764](https://github.com/ignitionrobotics/ign-gazebo/pull/764) + * [Pull request #764](https://github.com/gazebosim/gz-sim/pull/764) -## Ignition Gazebo 5.x +## Gazebo Sim 5.x -### Ignition Gazebo 5.4.0 (2022-03-31) +### Gazebo Sim 5.4.0 (2022-03-31) 1. Add the Model Photo Shoot system, port of Modelpropshop plugin from Gazebo classic - * [Pull request #1331](https://github.com/ignitionrobotics/ign-gazebo/pull/1331) + * [Pull request #1331](https://github.com/gazebosim/gz-sim/pull/1331) 1. Add wheel slip user command - * [Pull request #1241](https://github.com/ignitionrobotics/ign-gazebo/pull/1241) + * [Pull request #1241](https://github.com/gazebosim/gz-sim/pull/1241) 1. Added user command to set multiple entity poses - * [Pull request #1394](https://github.com/ignitionrobotics/ign-gazebo/pull/1394) + * [Pull request #1394](https://github.com/gazebosim/gz-sim/pull/1394) 1. Component inspector: refactor Pose3d C++ code into a separate class - * [Pull request #1400](https://github.com/ignitionrobotics/ign-gazebo/pull/1400) + * [Pull request #1400](https://github.com/gazebosim/gz-sim/pull/1400) 1. Toggle Light visuals - * [Pull request #1387](https://github.com/ignitionrobotics/ign-gazebo/pull/1387) + * [Pull request #1387](https://github.com/gazebosim/gz-sim/pull/1387) 1. Allow to turn on/off lights - * [Pull request #1343](https://github.com/ignitionrobotics/ign-gazebo/pull/1343) + * [Pull request #1343](https://github.com/gazebosim/gz-sim/pull/1343) 1. Added more sensor properties to scene/info topic - * [Pull request #1344](https://github.com/ignitionrobotics/ign-gazebo/pull/1344) + * [Pull request #1344](https://github.com/gazebosim/gz-sim/pull/1344) 1. JointStatePublisher publish parent, child and axis data - * [Pull request #1345](https://github.com/ignitionrobotics/ign-gazebo/pull/1345) + * [Pull request #1345](https://github.com/gazebosim/gz-sim/pull/1345) 1. Fixed light GUI component inspector - * [Pull request #1337](https://github.com/ignitionrobotics/ign-gazebo/pull/1337) + * [Pull request #1337](https://github.com/gazebosim/gz-sim/pull/1337) 1. Fix `UNIT_SdfGenerator_TEST` - * [Pull request #1319](https://github.com/ignitionrobotics/ign-gazebo/pull/1319) + * [Pull request #1319](https://github.com/gazebosim/gz-sim/pull/1319) 1. Add elevator system - * [Pull request #535](https://github.com/ignitionrobotics/ign-gazebo/pull/535) + * [Pull request #535](https://github.com/gazebosim/gz-sim/pull/535) 1. Removed unused variables in shapes plugin - * [Pull request #1321](https://github.com/ignitionrobotics/ign-gazebo/pull/1321) + * [Pull request #1321](https://github.com/gazebosim/gz-sim/pull/1321) 1. Log an error if JointPositionController cannot find the joint. (citadel retarget) - * [Pull request #1314](https://github.com/ignitionrobotics/ign-gazebo/pull/1314) + * [Pull request #1314](https://github.com/gazebosim/gz-sim/pull/1314) 1. Buoyancy: fix center of volume's reference frame - * [Pull request #1302](https://github.com/ignitionrobotics/ign-gazebo/pull/1302) + * [Pull request #1302](https://github.com/gazebosim/gz-sim/pull/1302) 1. Remove EachNew calls from sensor PreUpdates - * [Pull request #1281](https://github.com/ignitionrobotics/ign-gazebo/pull/1281) + * [Pull request #1281](https://github.com/gazebosim/gz-sim/pull/1281) 1. Prevent GzScene3D 💥 if another scene is already loaded - * [Pull request #1294](https://github.com/ignitionrobotics/ign-gazebo/pull/1294) + * [Pull request #1294](https://github.com/gazebosim/gz-sim/pull/1294) 1. Cleanup update call for non-rendering sensors - * [Pull request #1282](https://github.com/ignitionrobotics/ign-gazebo/pull/1282) + * [Pull request #1282](https://github.com/gazebosim/gz-sim/pull/1282) 1. Documentation Error - * [Pull request #1285](https://github.com/ignitionrobotics/ign-gazebo/pull/1285) + * [Pull request #1285](https://github.com/gazebosim/gz-sim/pull/1285) 1. Min and max parameters for velocity, acceleration, and jerk apply to linear and angular separately. - * [Pull request #1229](https://github.com/ignitionrobotics/ign-gazebo/pull/1229) + * [Pull request #1229](https://github.com/gazebosim/gz-sim/pull/1229) 1. Add project() call to examples - * [Pull request #1274](https://github.com/ignitionrobotics/ign-gazebo/pull/1274) + * [Pull request #1274](https://github.com/gazebosim/gz-sim/pull/1274) 1. Implement `/server_control::stop` - * [Pull request #1240](https://github.com/ignitionrobotics/ign-gazebo/pull/1240) + * [Pull request #1240](https://github.com/gazebosim/gz-sim/pull/1240) 1. 👩‍🌾 Make depth camera tests more robust (#897) - * [Pull request #897) (#1257](https://github.com/ignitionrobotics/ign-gazebo/pull/897) (#1257) + * [Pull request #897) (#1257](https://github.com/gazebosim/gz-sim/pull/897) (#1257) 1. Support battery draining start via topics - * [Pull request #1255](https://github.com/ignitionrobotics/ign-gazebo/pull/1255) + * [Pull request #1255](https://github.com/gazebosim/gz-sim/pull/1255) 1. Make tests run as fast as possible - * [Pull request #1194](https://github.com/ignitionrobotics/ign-gazebo/pull/1194) - * [Pull request #1250](https://github.com/ignitionrobotics/ign-gazebo/pull/1250) + * [Pull request #1194](https://github.com/gazebosim/gz-sim/pull/1194) + * [Pull request #1250](https://github.com/gazebosim/gz-sim/pull/1250) 1. Fix visualize lidar - * [Pull request #1224](https://github.com/ignitionrobotics/ign-gazebo/pull/1224) + * [Pull request #1224](https://github.com/gazebosim/gz-sim/pull/1224) 1. Skip failing Windows tests - * [Pull request #1205](https://github.com/ignitionrobotics/ign-gazebo/pull/1205) - * [Pull request #1204](https://github.com/ignitionrobotics/ign-gazebo/pull/1204) - * [Pull request #1259](https://github.com/ignitionrobotics/ign-gazebo/pull/1259) - * [Pull request #1408](https://github.com/ignitionrobotics/ign-gazebo/pull/1408) + * [Pull request #1205](https://github.com/gazebosim/gz-sim/pull/1205) + * [Pull request #1204](https://github.com/gazebosim/gz-sim/pull/1204) + * [Pull request #1259](https://github.com/gazebosim/gz-sim/pull/1259) + * [Pull request #1408](https://github.com/gazebosim/gz-sim/pull/1408) 1. Configurable joint state publisher's topic - * [Pull request #1076](https://github.com/ignitionrobotics/ign-gazebo/pull/1076) + * [Pull request #1076](https://github.com/gazebosim/gz-sim/pull/1076) 1. Thruster plugin: add tests and velocity control - * [Pull request #1190](https://github.com/ignitionrobotics/ign-gazebo/pull/1190) + * [Pull request #1190](https://github.com/gazebosim/gz-sim/pull/1190) 1. Limit thruster system's input thrust cmd - * [Pull request #1318](https://github.com/ignitionrobotics/ign-gazebo/pull/1318) + * [Pull request #1318](https://github.com/gazebosim/gz-sim/pull/1318) -### Ignition Gazebo 5.3.0 (2021-11-12) +### Gazebo Sim 5.3.0 (2021-11-12) 1. Prevent creation of spurious elements when saving worlds - * [Pull request #1192](https://github.com/ignitionrobotics/ign-gazebo/pull/1192) + * [Pull request #1192](https://github.com/gazebosim/gz-sim/pull/1192) 1. Added support for tracked vehicles - * [Pull request #869](https://github.com/ignitionrobotics/ign-gazebo/pull/869) + * [Pull request #869](https://github.com/gazebosim/gz-sim/pull/869) 1. Add components to dynamically set joint limits - * [Pull request #847](https://github.com/ignitionrobotics/ign-gazebo/pull/847) + * [Pull request #847](https://github.com/gazebosim/gz-sim/pull/847) 1. Fix updating component from state - * [Pull request #1181](https://github.com/ignitionrobotics/ign-gazebo/pull/1181) + * [Pull request #1181](https://github.com/gazebosim/gz-sim/pull/1181) 1. Extend odom publisher to allow 3D - * [Pull request #1180](https://github.com/ignitionrobotics/ign-gazebo/pull/1180) + * [Pull request #1180](https://github.com/gazebosim/gz-sim/pull/1180) 1. Fix updating a component's data via SerializedState msg - * [Pull request #1131](https://github.com/ignitionrobotics/ign-gazebo/pull/1131) + * [Pull request #1131](https://github.com/gazebosim/gz-sim/pull/1131) 1. Sensor systems work if loaded after sensors - * [Pull request #1104](https://github.com/ignitionrobotics/ign-gazebo/pull/1104) + * [Pull request #1104](https://github.com/gazebosim/gz-sim/pull/1104) 1. Fix generation of systems library symlinks in build directory - * [Pull request #1160](https://github.com/ignitionrobotics/ign-gazebo/pull/1160) + * [Pull request #1160](https://github.com/gazebosim/gz-sim/pull/1160) 1. Edit material colors in component inspector - * [Pull request #1123](https://github.com/ignitionrobotics/ign-gazebo/pull/1123) + * [Pull request #1123](https://github.com/gazebosim/gz-sim/pull/1123) 1. Support setting the background color for sensors - * [Pull request #1147](https://github.com/ignitionrobotics/ign-gazebo/pull/1147) + * [Pull request #1147](https://github.com/gazebosim/gz-sim/pull/1147) 1. Use `uint64_t` for ComponentInspector Entity IDs - * [Pull request #1144](https://github.com/ignitionrobotics/ign-gazebo/pull/1144) + * [Pull request #1144](https://github.com/gazebosim/gz-sim/pull/1144) 1. Fix integers and floats on component inspector - * [Pull request #1143](https://github.com/ignitionrobotics/ign-gazebo/pull/1143) + * [Pull request #1143](https://github.com/gazebosim/gz-sim/pull/1143) -### Ignition Gazebo 5.2.0 (2021-10-22) +### Gazebo Sim 5.2.0 (2021-10-22) 1. Fix performance level test flakiness - * [Pull request #1129](https://github.com/ignitionrobotics/ign-gazebo/pull/1129) + * [Pull request #1129](https://github.com/gazebosim/gz-sim/pull/1129) 1. Updates to camera video record from subt - * [Pull request #1117](https://github.com/ignitionrobotics/ign-gazebo/pull/1117) + * [Pull request #1117](https://github.com/gazebosim/gz-sim/pull/1117) 1. Better protect this->dataPtr->initialized with renderMutex. - * [Pull request #1119](https://github.com/ignitionrobotics/ign-gazebo/pull/1119) + * [Pull request #1119](https://github.com/gazebosim/gz-sim/pull/1119) 1. Use QTimer to update plugins in the Qt thread - * [Pull request #1095](https://github.com/ignitionrobotics/ign-gazebo/pull/1095) + * [Pull request #1095](https://github.com/gazebosim/gz-sim/pull/1095) 1. Adjust pose decimals based on element width - * [Pull request #1089](https://github.com/ignitionrobotics/ign-gazebo/pull/1089) + * [Pull request #1089](https://github.com/gazebosim/gz-sim/pull/1089) 1. JointPositionController: Improve misleading error message - * [Pull request #1098](https://github.com/ignitionrobotics/ign-gazebo/pull/1098) + * [Pull request #1098](https://github.com/gazebosim/gz-sim/pull/1098) 1. Fixed IMU system plugin - * [Pull request #1043](https://github.com/ignitionrobotics/ign-gazebo/pull/1043) + * [Pull request #1043](https://github.com/gazebosim/gz-sim/pull/1043) 1. Cache top level and static to speed up physics system (Backport #656) - * [Pull request #993](https://github.com/ignitionrobotics/ign-gazebo/pull/993) + * [Pull request #993](https://github.com/gazebosim/gz-sim/pull/993) 1. Prevent crash and print error - * [Pull request #1099](https://github.com/ignitionrobotics/ign-gazebo/pull/1099) + * [Pull request #1099](https://github.com/gazebosim/gz-sim/pull/1099) 1. Performance: use std::unordered_map where possible in SceneManager - * [Pull request #1083](https://github.com/ignitionrobotics/ign-gazebo/pull/1083) + * [Pull request #1083](https://github.com/gazebosim/gz-sim/pull/1083) 1. Fix light control standalone example - * [Pull request #1077](https://github.com/ignitionrobotics/ign-gazebo/pull/1077) + * [Pull request #1077](https://github.com/gazebosim/gz-sim/pull/1077) 1. Parse new param for enabling / disabling IMU orientation output - * [Pull request #899](https://github.com/ignitionrobotics/ign-gazebo/pull/899) + * [Pull request #899](https://github.com/gazebosim/gz-sim/pull/899) 1. Enable new policy to fix protobuf compilation errors - * [Pull request #1059](https://github.com/ignitionrobotics/ign-gazebo/pull/1059) + * [Pull request #1059](https://github.com/gazebosim/gz-sim/pull/1059) 1. Fix performance issue with contact data and AABB updates - * [Pull request #1048](https://github.com/ignitionrobotics/ign-gazebo/pull/1048) + * [Pull request #1048](https://github.com/gazebosim/gz-sim/pull/1048) 1. Support locked entities, and headless video recording using sim time - * [Pull request #862](https://github.com/ignitionrobotics/ign-gazebo/pull/862) + * [Pull request #862](https://github.com/gazebosim/gz-sim/pull/862) 1. Update ign-gazebo4 changelog - * [Pull request #1031](https://github.com/ignitionrobotics/ign-gazebo/pull/1031) + * [Pull request #1031](https://github.com/gazebosim/gz-sim/pull/1031) 1. bump version and update changelog - * [Pull request #1029](https://github.com/ignitionrobotics/ign-gazebo/pull/1029) + * [Pull request #1029](https://github.com/gazebosim/gz-sim/pull/1029) 1. Remove unused ignition gui header - * [Pull request #1026](https://github.com/ignitionrobotics/ign-gazebo/pull/1026) + * [Pull request #1026](https://github.com/gazebosim/gz-sim/pull/1026) 1. Collada world exporter now exporting lights - * [Pull request #912](https://github.com/ignitionrobotics/ign-gazebo/pull/912) + * [Pull request #912](https://github.com/gazebosim/gz-sim/pull/912) 1. Fixed GUI's ComponentInspector light parameter - * [Pull request #1018](https://github.com/ignitionrobotics/ign-gazebo/pull/1018) + * [Pull request #1018](https://github.com/gazebosim/gz-sim/pull/1018) 1. Workaround for setting visual cast shadows without material - * [Pull request #1015](https://github.com/ignitionrobotics/ign-gazebo/pull/1015) + * [Pull request #1015](https://github.com/gazebosim/gz-sim/pull/1015) 1. Fix selection buffer crash on resize - * [Pull request #969](https://github.com/ignitionrobotics/ign-gazebo/pull/969) + * [Pull request #969](https://github.com/gazebosim/gz-sim/pull/969) 1. Update DART deps to local - * [Pull request #1005](https://github.com/ignitionrobotics/ign-gazebo/pull/1005) + * [Pull request #1005](https://github.com/gazebosim/gz-sim/pull/1005) 1. Remove extra xml version line in pendulum_links example world - * [Pull request #1002](https://github.com/ignitionrobotics/ign-gazebo/pull/1002) + * [Pull request #1002](https://github.com/gazebosim/gz-sim/pull/1002) 1. Enable sensor metrics on example worlds - * [Pull request #982](https://github.com/ignitionrobotics/ign-gazebo/pull/982) + * [Pull request #982](https://github.com/gazebosim/gz-sim/pull/982) 1. Make thermal sensor test more robust - * [Pull request #994](https://github.com/ignitionrobotics/ign-gazebo/pull/994) + * [Pull request #994](https://github.com/gazebosim/gz-sim/pull/994) 1. Improved doxygen - * [Pull request #996](https://github.com/ignitionrobotics/ign-gazebo/pull/996) + * [Pull request #996](https://github.com/gazebosim/gz-sim/pull/996) 1. Remove bitbucket-pipelines.yml - * [Pull request #991](https://github.com/ignitionrobotics/ign-gazebo/pull/991) + * [Pull request #991](https://github.com/gazebosim/gz-sim/pull/991) 1. Removed unused variable in Shapes plugin - * [Pull request #984](https://github.com/ignitionrobotics/ign-gazebo/pull/984) + * [Pull request #984](https://github.com/gazebosim/gz-sim/pull/984) 1. Entity tree: prevent creation of repeated entity items - * [Pull request #974](https://github.com/ignitionrobotics/ign-gazebo/pull/974) + * [Pull request #974](https://github.com/gazebosim/gz-sim/pull/974) 1. Updates when forward-porting to v4 - * [Pull request #973](https://github.com/ignitionrobotics/ign-gazebo/pull/973) + * [Pull request #973](https://github.com/gazebosim/gz-sim/pull/973) 1. Don't use $HOME on most tests (InternalFixture) - * [Pull request #971](https://github.com/ignitionrobotics/ign-gazebo/pull/971) + * [Pull request #971](https://github.com/gazebosim/gz-sim/pull/971) 1. Fix entity creation console msg - * [Pull request #972](https://github.com/ignitionrobotics/ign-gazebo/pull/972) + * [Pull request #972](https://github.com/gazebosim/gz-sim/pull/972) 1. Fix crash in the follow_actor example - * [Pull request #958](https://github.com/ignitionrobotics/ign-gazebo/pull/958) + * [Pull request #958](https://github.com/gazebosim/gz-sim/pull/958) 1. Be more specific when looking for physics plugins - * [Pull request #965](https://github.com/ignitionrobotics/ign-gazebo/pull/965) + * [Pull request #965](https://github.com/gazebosim/gz-sim/pull/965) 1. Drag and drop meshes into scene - * [Pull request #939](https://github.com/ignitionrobotics/ign-gazebo/pull/939) + * [Pull request #939](https://github.com/gazebosim/gz-sim/pull/939) 1. Allow referencing links in nested models in LiftDrag - * [Pull request #955](https://github.com/ignitionrobotics/ign-gazebo/pull/955) + * [Pull request #955](https://github.com/gazebosim/gz-sim/pull/955) 1. Complaint if Joint doesn't exists before adding joint controller - * [Pull request #786](https://github.com/ignitionrobotics/ign-gazebo/pull/786) + * [Pull request #786](https://github.com/gazebosim/gz-sim/pull/786) 1. Set protobuf_MODULE_COMPATIBLE before any find_package call - * [Pull request #957](https://github.com/ignitionrobotics/ign-gazebo/pull/957) + * [Pull request #957](https://github.com/gazebosim/gz-sim/pull/957) 1. DiffDrive add enable/disable - * [Pull request #772](https://github.com/ignitionrobotics/ign-gazebo/pull/772) + * [Pull request #772](https://github.com/gazebosim/gz-sim/pull/772) 1. Fix component inspector shutdown crash - * [Pull request #724](https://github.com/ignitionrobotics/ign-gazebo/pull/724) + * [Pull request #724](https://github.com/gazebosim/gz-sim/pull/724) 1. Add UserCommands Plugin. - * [Pull request #719](https://github.com/ignitionrobotics/ign-gazebo/pull/719) + * [Pull request #719](https://github.com/gazebosim/gz-sim/pull/719) 1. Expose a test fixture helper class - * [Pull request #926](https://github.com/ignitionrobotics/ign-gazebo/pull/926) + * [Pull request #926](https://github.com/gazebosim/gz-sim/pull/926) 1. Fix logic to disable server default plugins loading - * [Pull request #953](https://github.com/ignitionrobotics/ign-gazebo/pull/953) + * [Pull request #953](https://github.com/gazebosim/gz-sim/pull/953) 1. Porting Dome to Edifice: Windows, deprecations - * [Pull request #948](https://github.com/ignitionrobotics/ign-gazebo/pull/948) + * [Pull request #948](https://github.com/gazebosim/gz-sim/pull/948) 1. removed unneeded plugin update - * [Pull request #944](https://github.com/ignitionrobotics/ign-gazebo/pull/944) + * [Pull request #944](https://github.com/gazebosim/gz-sim/pull/944) 1. Functions to enable velocity and acceleration checks on Link - * [Pull request #935](https://github.com/ignitionrobotics/ign-gazebo/pull/935) + * [Pull request #935](https://github.com/gazebosim/gz-sim/pull/935) 1. Support adding systems that don't come from a plugin - * [Pull request #936](https://github.com/ignitionrobotics/ign-gazebo/pull/936) + * [Pull request #936](https://github.com/gazebosim/gz-sim/pull/936) 1. 3D plot GUI plugin - * [Pull request #917](https://github.com/ignitionrobotics/ign-gazebo/pull/917) + * [Pull request #917](https://github.com/gazebosim/gz-sim/pull/917) 1. 4 to 5 - * [Pull request #938](https://github.com/ignitionrobotics/ign-gazebo/pull/938) + * [Pull request #938](https://github.com/gazebosim/gz-sim/pull/938) 1. Fix joint controller without joint vel data - * [Pull request #937](https://github.com/ignitionrobotics/ign-gazebo/pull/937) + * [Pull request #937](https://github.com/gazebosim/gz-sim/pull/937) 1. 3 to 4 - * [Pull request #933](https://github.com/ignitionrobotics/ign-gazebo/pull/933) + * [Pull request #933](https://github.com/gazebosim/gz-sim/pull/933) 1. Model info CLI `ign model` - * [Pull request #893](https://github.com/ignitionrobotics/ign-gazebo/pull/893) + * [Pull request #893](https://github.com/gazebosim/gz-sim/pull/893) 1. Support Bullet on Edifice - * [Pull request #919](https://github.com/ignitionrobotics/ign-gazebo/pull/919) + * [Pull request #919](https://github.com/gazebosim/gz-sim/pull/919) 1. Don't create components for entities that don't exist - * [Pull request #927](https://github.com/ignitionrobotics/ign-gazebo/pull/927) + * [Pull request #927](https://github.com/gazebosim/gz-sim/pull/927) 1. Fix blender sdf export script and remove .material file from collada light export test - * [Pull request #923](https://github.com/ignitionrobotics/ign-gazebo/pull/923) + * [Pull request #923](https://github.com/gazebosim/gz-sim/pull/923) 1. Heightmap physics (with DART) - * [Pull request #661](https://github.com/ignitionrobotics/ign-gazebo/pull/661) + * [Pull request #661](https://github.com/gazebosim/gz-sim/pull/661) 1. Adds Mesh Tutorial - * [Pull request #915](https://github.com/ignitionrobotics/ign-gazebo/pull/915) + * [Pull request #915](https://github.com/gazebosim/gz-sim/pull/915) 1. 4 to 5 - * [Pull request #918](https://github.com/ignitionrobotics/ign-gazebo/pull/918) + * [Pull request #918](https://github.com/gazebosim/gz-sim/pull/918) 1. Fix updating GUI plugin on load - * [Pull request #904](https://github.com/ignitionrobotics/ign-gazebo/pull/904) + * [Pull request #904](https://github.com/gazebosim/gz-sim/pull/904) 1. 3 to 4 - * [Pull request #916](https://github.com/ignitionrobotics/ign-gazebo/pull/916) + * [Pull request #916](https://github.com/gazebosim/gz-sim/pull/916) 1. Physics system: update link poses if the canonical link pose has been updated - * [Pull request #876](https://github.com/ignitionrobotics/ign-gazebo/pull/876) + * [Pull request #876](https://github.com/gazebosim/gz-sim/pull/876) 1. Add blender sdf export tutorial - * [Pull request #895](https://github.com/ignitionrobotics/ign-gazebo/pull/895) + * [Pull request #895](https://github.com/gazebosim/gz-sim/pull/895) 1. Banana for Scale - * [Pull request #734](https://github.com/ignitionrobotics/ign-gazebo/pull/734) + * [Pull request #734](https://github.com/gazebosim/gz-sim/pull/734) 1. Fix textures not exporting after loading a world that uses obj models - * [Pull request #874](https://github.com/ignitionrobotics/ign-gazebo/pull/874) + * [Pull request #874](https://github.com/gazebosim/gz-sim/pull/874) 1. Fix documentation for the Sensor component - * [Pull request #898](https://github.com/ignitionrobotics/ign-gazebo/pull/898) + * [Pull request #898](https://github.com/gazebosim/gz-sim/pull/898) 1. Make depth camera tests more robust - * [Pull request #897](https://github.com/ignitionrobotics/ign-gazebo/pull/897) + * [Pull request #897](https://github.com/gazebosim/gz-sim/pull/897) 1. Use UINT64_MAX for kComponentTpyeIDInvalid instead of relying on underflow - * [Pull request #889](https://github.com/ignitionrobotics/ign-gazebo/pull/889) + * [Pull request #889](https://github.com/gazebosim/gz-sim/pull/889) 1. Fix mouse view control target position - * [Pull request #879](https://github.com/ignitionrobotics/ign-gazebo/pull/879) + * [Pull request #879](https://github.com/gazebosim/gz-sim/pull/879) -### Ignition Gazebo 5.1.0 (2021-06-29) +### Gazebo Sim 5.1.0 (2021-06-29) 1. Depend on SDF 11.2.1, rendering 5.1 and GUI 5.1. Fix Windows. - * [Pull request #877](https://github.com/ignitionrobotics/ign-gazebo/pull/877) + * [Pull request #877](https://github.com/gazebosim/gz-sim/pull/877) 1. Set gui camera pose - * [Pull request #863](https://github.com/ignitionrobotics/ign-gazebo/pull/863) + * [Pull request #863](https://github.com/gazebosim/gz-sim/pull/863) 1. Refactor RenderUtil::Update with helper functions - * [Pull request #858](https://github.com/ignitionrobotics/ign-gazebo/pull/858) + * [Pull request #858](https://github.com/gazebosim/gz-sim/pull/858) 1. Enables confirmation dialog when closing Gazebo. - * [Pull request #850](https://github.com/ignitionrobotics/ign-gazebo/pull/850) + * [Pull request #850](https://github.com/gazebosim/gz-sim/pull/850) 1. Using math::SpeedLimiter on the diff_drive controller. - * [Pull request #833](https://github.com/ignitionrobotics/ign-gazebo/pull/833) + * [Pull request #833](https://github.com/gazebosim/gz-sim/pull/833) 1. New example: get an ECM snapshot from an external program - * [Pull request #859](https://github.com/ignitionrobotics/ign-gazebo/pull/859) + * [Pull request #859](https://github.com/gazebosim/gz-sim/pull/859) 1. Fix WindEffects Plugin bug, not configuring new links - * [Pull request #844](https://github.com/ignitionrobotics/ign-gazebo/pull/844) + * [Pull request #844](https://github.com/gazebosim/gz-sim/pull/844) 1. Set collision detector and solver from SDF - * [Pull request #684](https://github.com/ignitionrobotics/ign-gazebo/pull/684) + * [Pull request #684](https://github.com/gazebosim/gz-sim/pull/684) 1. Add Particle Emitter tutorial - * [Pull request #860](https://github.com/ignitionrobotics/ign-gazebo/pull/860) + * [Pull request #860](https://github.com/gazebosim/gz-sim/pull/860) 1. Fix potentially flaky integration component test case - * [Pull request #848](https://github.com/ignitionrobotics/ign-gazebo/pull/848) + * [Pull request #848](https://github.com/gazebosim/gz-sim/pull/848) 1. Added follow camera offset service - * [Pull request #855](https://github.com/ignitionrobotics/ign-gazebo/pull/855) + * [Pull request #855](https://github.com/gazebosim/gz-sim/pull/855) 1. Remove unneeded camera follow offset checks - * [Pull request #857](https://github.com/ignitionrobotics/ign-gazebo/pull/857) + * [Pull request #857](https://github.com/gazebosim/gz-sim/pull/857) 1. Using math::SpeedLimiter on the ackermann_steering controller. - * [Pull request #837](https://github.com/ignitionrobotics/ign-gazebo/pull/837) + * [Pull request #837](https://github.com/gazebosim/gz-sim/pull/837) 1. Cleanup and alphabetize plugin headers - * [Pull request #838](https://github.com/ignitionrobotics/ign-gazebo/pull/838) + * [Pull request #838](https://github.com/gazebosim/gz-sim/pull/838) 1. Fix race condition when rendering the UI - * [Pull request #774](https://github.com/ignitionrobotics/ign-gazebo/pull/774) + * [Pull request #774](https://github.com/gazebosim/gz-sim/pull/774) 1. Removed duplicated code with rendering::sceneFromFirstRenderEngine - * [Pull request #819](https://github.com/ignitionrobotics/ign-gazebo/pull/819) + * [Pull request #819](https://github.com/gazebosim/gz-sim/pull/819) 1. Remove unused headers in video_recoder plugin - * [Pull request #834](https://github.com/ignitionrobotics/ign-gazebo/pull/834) + * [Pull request #834](https://github.com/gazebosim/gz-sim/pull/834) 1. Use moveToHelper from ign-rendering - * [Pull request #825](https://github.com/ignitionrobotics/ign-gazebo/pull/825) + * [Pull request #825](https://github.com/gazebosim/gz-sim/pull/825) 1. Make halt motion act like a brake - * [Pull request #830](https://github.com/ignitionrobotics/ign-gazebo/pull/830) + * [Pull request #830](https://github.com/gazebosim/gz-sim/pull/830) 1. Update collision visualization to support nested models - * [Pull request #823](https://github.com/ignitionrobotics/ign-gazebo/pull/823) + * [Pull request #823](https://github.com/gazebosim/gz-sim/pull/823) 1. Adds support for ocean currents - * [Pull request #800](https://github.com/ignitionrobotics/ign-gazebo/pull/800) + * [Pull request #800](https://github.com/gazebosim/gz-sim/pull/800) 1. Add conversion for particle scatter ratio field - * [Pull request #791](https://github.com/ignitionrobotics/ign-gazebo/pull/791) + * [Pull request #791](https://github.com/gazebosim/gz-sim/pull/791) 1. Adding HaltMotion to physics plugin - * [Pull request #728](https://github.com/ignitionrobotics/ign-gazebo/pull/728) + * [Pull request #728](https://github.com/gazebosim/gz-sim/pull/728) 1. ColladaExporter, export submesh selected - * [Pull request #802](https://github.com/ignitionrobotics/ign-gazebo/pull/802) + * [Pull request #802](https://github.com/gazebosim/gz-sim/pull/802) 1. Remove tools/code_check and update codecov - * [Pull request #814](https://github.com/ignitionrobotics/ign-gazebo/pull/814) + * [Pull request #814](https://github.com/gazebosim/gz-sim/pull/814) 1. Trigger delay - * [Pull request #817](https://github.com/ignitionrobotics/ign-gazebo/pull/817) + * [Pull request #817](https://github.com/gazebosim/gz-sim/pull/817) 1. Map canonical links to their models - * [Pull request #736](https://github.com/ignitionrobotics/ign-gazebo/pull/736) + * [Pull request #736](https://github.com/gazebosim/gz-sim/pull/736) 1. Fix included nested model expansion in SDF generation - * [Pull request #768](https://github.com/ignitionrobotics/ign-gazebo/pull/768) + * [Pull request #768](https://github.com/gazebosim/gz-sim/pull/768) 1. Util: Use public API from libsdformat for detecting non-file source - * [Pull request #794](https://github.com/ignitionrobotics/ign-gazebo/pull/794) + * [Pull request #794](https://github.com/gazebosim/gz-sim/pull/794) 1. Contacts visualization - * [Pull request #234](https://github.com/ignitionrobotics/ign-gazebo/pull/234) + * [Pull request #234](https://github.com/gazebosim/gz-sim/pull/234) 1. Bump to ign-msgs 7.1 / sdformat 11.1, Windows fixes - * [Pull request #758](https://github.com/ignitionrobotics/ign-gazebo/pull/758) + * [Pull request #758](https://github.com/gazebosim/gz-sim/pull/758) 1. Add functionalities for optical tactile plugin - * [Pull request #431](https://github.com/ignitionrobotics/ign-gazebo/pull/431) + * [Pull request #431](https://github.com/gazebosim/gz-sim/pull/431) 1. Fix documentation for EntityComponentManager::EachNew - * [Pull request #795](https://github.com/ignitionrobotics/ign-gazebo/pull/795) + * [Pull request #795](https://github.com/gazebosim/gz-sim/pull/795) 1. Bump ign-physics version to 3.2 - * [Pull request #792](https://github.com/ignitionrobotics/ign-gazebo/pull/792) + * [Pull request #792](https://github.com/gazebosim/gz-sim/pull/792) 1. Prevent crash on Plotting plugin with mutex - * [Pull request #747](https://github.com/ignitionrobotics/ign-gazebo/pull/747) + * [Pull request #747](https://github.com/gazebosim/gz-sim/pull/747) 1. 👩‍🌾 Fix Windows build and some warnings - * [Pull request #782](https://github.com/ignitionrobotics/ign-gazebo/pull/782) + * [Pull request #782](https://github.com/gazebosim/gz-sim/pull/782) 1. Fix ColladaExporter submesh index bug - * [Pull request #763](https://github.com/ignitionrobotics/ign-gazebo/pull/763) + * [Pull request #763](https://github.com/gazebosim/gz-sim/pull/763) 1. Fix macOS build: components::Name in benchmark - * [Pull request #784](https://github.com/ignitionrobotics/ign-gazebo/pull/784) + * [Pull request #784](https://github.com/gazebosim/gz-sim/pull/784) 1. Feature/hydrodynamics - * [Pull request #749](https://github.com/ignitionrobotics/ign-gazebo/pull/749) + * [Pull request #749](https://github.com/gazebosim/gz-sim/pull/749) 1. Don't store duplicate ComponentTypeId in ECM - * [Pull request #751](https://github.com/ignitionrobotics/ign-gazebo/pull/751) + * [Pull request #751](https://github.com/gazebosim/gz-sim/pull/751) 1. [TPE] Support setting individual link velocity - * [Pull request #427](https://github.com/ignitionrobotics/ign-gazebo/pull/427) + * [Pull request #427](https://github.com/gazebosim/gz-sim/pull/427) 1. 👩‍🌾 Enable Focal CI - * [Pull request #646](https://github.com/ignitionrobotics/ign-gazebo/pull/646) + * [Pull request #646](https://github.com/gazebosim/gz-sim/pull/646) 1. Patch particle emitter2 service - * [Pull request #777](https://github.com/ignitionrobotics/ign-gazebo/pull/777) + * [Pull request #777](https://github.com/gazebosim/gz-sim/pull/777) 1. Add odometry publisher system - * [Pull request #547](https://github.com/ignitionrobotics/ign-gazebo/pull/547) + * [Pull request #547](https://github.com/gazebosim/gz-sim/pull/547) 1. [DiffDrive] add enable/disable - * [Pull request #772](https://github.com/ignitionrobotics/ign-gazebo/pull/772) + * [Pull request #772](https://github.com/gazebosim/gz-sim/pull/772) 1. Update benchmark comparison instructions - * [Pull request #766](https://github.com/ignitionrobotics/ign-gazebo/pull/766) + * [Pull request #766](https://github.com/gazebosim/gz-sim/pull/766) 1. Fix 'invalid animation update data' msg for actors - * [Pull request #754](https://github.com/ignitionrobotics/ign-gazebo/pull/754) + * [Pull request #754](https://github.com/gazebosim/gz-sim/pull/754) 1. Fixed particle emitter forward playback - * [Pull request #745](https://github.com/ignitionrobotics/ign-gazebo/pull/745) + * [Pull request #745](https://github.com/gazebosim/gz-sim/pull/745) 1. ECM's ChangedState gets message with modified components - * [Pull request #742](https://github.com/ignitionrobotics/ign-gazebo/pull/742) + * [Pull request #742](https://github.com/gazebosim/gz-sim/pull/742) 1. Fixed collision visual bounding boxes - * [Pull request #746](https://github.com/ignitionrobotics/ign-gazebo/pull/746) + * [Pull request #746](https://github.com/gazebosim/gz-sim/pull/746) 1. Fix compute_rtfs arguments - * [Pull request #737](https://github.com/ignitionrobotics/ign-gazebo/pull/737) + * [Pull request #737](https://github.com/gazebosim/gz-sim/pull/737) 1. Validate step size and RTF parameters - * [Pull request #740](https://github.com/ignitionrobotics/ign-gazebo/pull/740) + * [Pull request #740](https://github.com/gazebosim/gz-sim/pull/740) 1. Fix component inspector shutdown crash - * [Pull request #724](https://github.com/ignitionrobotics/ign-gazebo/pull/724) + * [Pull request #724](https://github.com/gazebosim/gz-sim/pull/724) 1. Use Protobuf_IMPORT_DIRS instead of PROTOBUF_IMPORT_DIRS for compatibility with Protobuf CMake config - * [Pull request #715](https://github.com/ignitionrobotics/ign-gazebo/pull/715) + * [Pull request #715](https://github.com/gazebosim/gz-sim/pull/715) 1. Do not pass -Wno-unused-parameter to MSVC compiler - * [Pull request #716](https://github.com/ignitionrobotics/ign-gazebo/pull/716) + * [Pull request #716](https://github.com/gazebosim/gz-sim/pull/716) 1. Iterate through changed links only in UpdateSim - * [Pull request #678](https://github.com/ignitionrobotics/ign-gazebo/pull/678) + * [Pull request #678](https://github.com/gazebosim/gz-sim/pull/678) 1. Update PlaybackScrubber description - * [Pull request #733](https://github.com/ignitionrobotics/ign-gazebo/pull/733) + * [Pull request #733](https://github.com/gazebosim/gz-sim/pull/733) 1. Support configuring particle scatter ratio in particle emitter system - * [Pull request #674](https://github.com/ignitionrobotics/ign-gazebo/pull/674) + * [Pull request #674](https://github.com/gazebosim/gz-sim/pull/674) 1. Fix diffuse and ambient values for ackermann example - * [Pull request #707](https://github.com/ignitionrobotics/ign-gazebo/pull/707) + * [Pull request #707](https://github.com/gazebosim/gz-sim/pull/707) 1. Scenebroadcaster sensors - * [Pull request #698](https://github.com/ignitionrobotics/ign-gazebo/pull/698) + * [Pull request #698](https://github.com/gazebosim/gz-sim/pull/698) 1. Add test for thermal object temperatures below 0 kelvin - * [Pull request #621](https://github.com/ignitionrobotics/ign-gazebo/pull/621) + * [Pull request #621](https://github.com/gazebosim/gz-sim/pull/621) 1. [BULLET] Making GetContactsFromLastStepFeature optional in Collision Features - * [Pull request #690](https://github.com/ignitionrobotics/ign-gazebo/pull/690) + * [Pull request #690](https://github.com/gazebosim/gz-sim/pull/690) 1. Make it so joint state publisher is quieter - * [Pull request #696](https://github.com/ignitionrobotics/ign-gazebo/pull/696) + * [Pull request #696](https://github.com/gazebosim/gz-sim/pull/696) -### Ignition Gazebo 5.0.0 (2021-03-30) +### Gazebo Sim 5.0.0 (2021-03-30) 1. Added Ellipsoid and Capsule geometries - * [Pull request #581](https://github.com/ignitionrobotics/ign-gazebo/pull/581) + * [Pull request #581](https://github.com/gazebosim/gz-sim/pull/581) 1. Support individual canonical links for nested models - * [Pull request #685](https://github.com/ignitionrobotics/ign-gazebo/pull/685) + * [Pull request #685](https://github.com/gazebosim/gz-sim/pull/685) 1. Mecanum wheels demo - * [Pull request #683](https://github.com/ignitionrobotics/ign-gazebo/pull/683) + * [Pull request #683](https://github.com/gazebosim/gz-sim/pull/683) 1. Fixed collision visual bounding boxes - * [Pull request #702](https://github.com/ignitionrobotics/ign-gazebo/pull/702) + * [Pull request #702](https://github.com/gazebosim/gz-sim/pull/702) 1. Fixed material colors for ackermann sdfs - * [Pull request #703](https://github.com/ignitionrobotics/ign-gazebo/pull/703) + * [Pull request #703](https://github.com/gazebosim/gz-sim/pull/703) 1. Setting the intiial velocity for a model or joint - * [Pull request #693](https://github.com/ignitionrobotics/ign-gazebo/pull/693) + * [Pull request #693](https://github.com/gazebosim/gz-sim/pull/693) 1. Remove static for maps from Factory.hh - * [Pull request #635](https://github.com/ignitionrobotics/ign-gazebo/pull/635) + * [Pull request #635](https://github.com/gazebosim/gz-sim/pull/635) 1. Depend on cli component of ignition-utils1 - * [Pull request #671](https://github.com/ignitionrobotics/ign-gazebo/pull/671) + * [Pull request #671](https://github.com/gazebosim/gz-sim/pull/671) 1. Support SDFormat 1.8 Composition - * [Pull request #542](https://github.com/ignitionrobotics/ign-gazebo/pull/542) + * [Pull request #542](https://github.com/gazebosim/gz-sim/pull/542) 1. Deprecate TmpIface: it's leftover from prototyping - * [Pull request #654](https://github.com/ignitionrobotics/ign-gazebo/pull/654) + * [Pull request #654](https://github.com/gazebosim/gz-sim/pull/654) 1. Bump in edifice: ign-common4 - * [Pull request #577](https://github.com/ignitionrobotics/ign-gazebo/pull/577) + * [Pull request #577](https://github.com/gazebosim/gz-sim/pull/577) 1. Plugin to spawn lights - * [Pull request #587](https://github.com/ignitionrobotics/ign-gazebo/pull/587) + * [Pull request #587](https://github.com/gazebosim/gz-sim/pull/587) 1. Added light intensity - * [Pull request #612](https://github.com/ignitionrobotics/ign-gazebo/pull/612) - * [Pull request #670](https://github.com/ignitionrobotics/ign-gazebo/pull/670) + * [Pull request #612](https://github.com/gazebosim/gz-sim/pull/612) + * [Pull request #670](https://github.com/gazebosim/gz-sim/pull/670) 1. Examples and tutorial on using rendering API from plugins - * [Pull request #596](https://github.com/ignitionrobotics/ign-gazebo/pull/596) + * [Pull request #596](https://github.com/gazebosim/gz-sim/pull/596) 1. Prepare GuiRunner to be made private - * [Pull request #567](https://github.com/ignitionrobotics/ign-gazebo/pull/567) + * [Pull request #567](https://github.com/gazebosim/gz-sim/pull/567) -1. Deprecate some gazebo::gui events in favor of ign-gui events - * [Pull request #595](https://github.com/ignitionrobotics/ign-gazebo/pull/595) +1. Deprecate some sim::gui events in favor of ign-gui events + * [Pull request #595](https://github.com/gazebosim/gz-sim/pull/595) 1. Heightmap (rendering only) - * [Pull request #487](https://github.com/ignitionrobotics/ign-gazebo/pull/487) + * [Pull request #487](https://github.com/gazebosim/gz-sim/pull/487) 1. Add image suffix to thermal camera topic name - * [Pull request #606](https://github.com/ignitionrobotics/ign-gazebo/pull/606) + * [Pull request #606](https://github.com/gazebosim/gz-sim/pull/606) 1. Fix build with latest sdformat11 branch - * [Pull request #607](https://github.com/ignitionrobotics/ign-gazebo/pull/607) + * [Pull request #607](https://github.com/gazebosim/gz-sim/pull/607) 1. Added run to time feature - * [Pull request #478](https://github.com/ignitionrobotics/ign-gazebo/pull/478) + * [Pull request #478](https://github.com/gazebosim/gz-sim/pull/478) 1. Depend on ignition-utils1 - * [Pull request #591](https://github.com/ignitionrobotics/ign-gazebo/pull/591) + * [Pull request #591](https://github.com/gazebosim/gz-sim/pull/591) 1. Use double sided field in material msg - * [Pull request #599](https://github.com/ignitionrobotics/ign-gazebo/pull/599) + * [Pull request #599](https://github.com/gazebosim/gz-sim/pull/599) 1. Add lightmap demo - * [Pull request #471](https://github.com/ignitionrobotics/ign-gazebo/pull/471) + * [Pull request #471](https://github.com/gazebosim/gz-sim/pull/471) 1. Added renderOrder to convert functions - * [Pull request #514](https://github.com/ignitionrobotics/ign-gazebo/pull/514) + * [Pull request #514](https://github.com/gazebosim/gz-sim/pull/514) 1. Compilation fixes for Windows - * [Pull request #501](https://github.com/ignitionrobotics/ign-gazebo/pull/501) - * [Pull request #585](https://github.com/ignitionrobotics/ign-gazebo/pull/585) - * [Pull request #565](https://github.com/ignitionrobotics/ign-gazebo/pull/565) - * [Pull request #616](https://github.com/ignitionrobotics/ign-gazebo/pull/616) - * [Pull request #622](https://github.com/ignitionrobotics/ign-gazebo/pull/622) + * [Pull request #501](https://github.com/gazebosim/gz-sim/pull/501) + * [Pull request #585](https://github.com/gazebosim/gz-sim/pull/585) + * [Pull request #565](https://github.com/gazebosim/gz-sim/pull/565) + * [Pull request #616](https://github.com/gazebosim/gz-sim/pull/616) + * [Pull request #622](https://github.com/gazebosim/gz-sim/pull/622) 1. Documentation fixes - * [Pull request #727](https://github.com/ignitionrobotics/ign-gazebo/pull/727) - * [Pull request #710](https://github.com/ignitionrobotics/ign-gazebo/pull/710) + * [Pull request #727](https://github.com/gazebosim/gz-sim/pull/727) + * [Pull request #710](https://github.com/gazebosim/gz-sim/pull/710) 1. Replace deprecated function FreeGroup::CanonicalLink with FreeGroup::RootLink - * [Pull request #723](https://github.com/ignitionrobotics/ign-gazebo/pull/723) + * [Pull request #723](https://github.com/gazebosim/gz-sim/pull/723) 1. Respect spotlight direction - * [Pull request #718](https://github.com/ignitionrobotics/ign-gazebo/pull/718) + * [Pull request #718](https://github.com/gazebosim/gz-sim/pull/718) 1. Add UserCommands plugin to fuel.sdf - * [Pull request #719](https://github.com/ignitionrobotics/ign-gazebo/pull/719) + * [Pull request #719](https://github.com/gazebosim/gz-sim/pull/719) 1. Change SelectedEntities to return a const ref - * [Pull request #571](https://github.com/ignitionrobotics/ign-gazebo/pull/571) + * [Pull request #571](https://github.com/gazebosim/gz-sim/pull/571) 1. Use common::setenv for portability to Windows - * [Pull request #561](https://github.com/ignitionrobotics/ign-gazebo/pull/561) + * [Pull request #561](https://github.com/gazebosim/gz-sim/pull/561) -1. Add missing IGNITION_GAZEBO_VISIBLE macros - * [Pull request #563](https://github.com/ignitionrobotics/ign-gazebo/pull/563) +1. Add missing GZ_GAZEBO_VISIBLE macros + * [Pull request #563](https://github.com/gazebosim/gz-sim/pull/563) 1. Fix deprecation warnings - * [Pull request #572](https://github.com/ignitionrobotics/ign-gazebo/pull/572) + * [Pull request #572](https://github.com/gazebosim/gz-sim/pull/572) 1. Fix visibility macro names when used by a different component (Windows) - * [Pull request #564](https://github.com/ignitionrobotics/ign-gazebo/pull/564) + * [Pull request #564](https://github.com/gazebosim/gz-sim/pull/564) 1. Bump edifice sdformat11 and ign-physics4 - * [Pull request #549](https://github.com/ignitionrobotics/ign-gazebo/pull/549) + * [Pull request #549](https://github.com/gazebosim/gz-sim/pull/549) 1. Use ComponentState::PeriodicChange in UpdateState to avoid forcing full scene update - * [Pull request #486](https://github.com/ignitionrobotics/ign-gazebo/pull/486) + * [Pull request #486](https://github.com/gazebosim/gz-sim/pull/486) 1. Bump in edifice: ign-msgs7 - * [Pull request #546](https://github.com/ignitionrobotics/ign-gazebo/pull/546) + * [Pull request #546](https://github.com/gazebosim/gz-sim/pull/546) 1. Add support for sky - * [Pull request #445](https://github.com/ignitionrobotics/ign-gazebo/pull/445) + * [Pull request #445](https://github.com/gazebosim/gz-sim/pull/445) 1. Infrastructure - * [Pull request #423](https://github.com/ignitionrobotics/ign-gazebo/pull/423) + * [Pull request #423](https://github.com/gazebosim/gz-sim/pull/423) 1. Bump in edifice: ign-rendering5 - * [Pull request #430](https://github.com/ignitionrobotics/ign-gazebo/pull/430) + * [Pull request #430](https://github.com/gazebosim/gz-sim/pull/430) 1. Add 25percent darker view angle icons - * [Pull request #426](https://github.com/ignitionrobotics/ign-gazebo/pull/426) + * [Pull request #426](https://github.com/gazebosim/gz-sim/pull/426) -## Ignition Gazebo 4.x +## Gazebo Sim 4.x -### Ignition Gazebo 4.14.0 (2021-12-20) +### Gazebo Sim 4.14.0 (2021-12-20) 1. Support battery draining start via topics - * [Pull request #1255](https://github.com/ignitionrobotics/ign-gazebo/pull/1255) + * [Pull request #1255](https://github.com/gazebosim/gz-sim/pull/1255) 1. Make tests run as fast as possible - * [Pull request #1194](https://github.com/ignitionrobotics/ign-gazebo/pull/1194) - * [Pull request #1250](https://github.com/ignitionrobotics/ign-gazebo/pull/1250) + * [Pull request #1194](https://github.com/gazebosim/gz-sim/pull/1194) + * [Pull request #1250](https://github.com/gazebosim/gz-sim/pull/1250) 1. Fix visualize lidar - * [Pull request #1224](https://github.com/ignitionrobotics/ign-gazebo/pull/1224) + * [Pull request #1224](https://github.com/gazebosim/gz-sim/pull/1224) 1. Disable user commands light test on macOS - * [Pull request #1204](https://github.com/ignitionrobotics/ign-gazebo/pull/1204) + * [Pull request #1204](https://github.com/gazebosim/gz-sim/pull/1204) -### Ignition Gazebo 4.13.0 (2021-11-15) +### Gazebo Sim 4.13.0 (2021-11-15) 1. Prevent creation of spurious `` elements when saving worlds - * [Pull request #1192](https://github.com/ignitionrobotics/ign-gazebo/pull/1192) + * [Pull request #1192](https://github.com/gazebosim/gz-sim/pull/1192) 1. Add support for tracked vehicles - * [Pull request #869](https://github.com/ignitionrobotics/ign-gazebo/pull/869) + * [Pull request #869](https://github.com/gazebosim/gz-sim/pull/869) 1. Add components to dynamically set joint limits - * [Pull request #847](https://github.com/ignitionrobotics/ign-gazebo/pull/847) + * [Pull request #847](https://github.com/gazebosim/gz-sim/pull/847) 1. Fix updating component from state - * [Pull request #1181](https://github.com/ignitionrobotics/ign-gazebo/pull/1181) + * [Pull request #1181](https://github.com/gazebosim/gz-sim/pull/1181) 1. Fix updating a component's data via SerializedState msg - * [Pull request #1149](https://github.com/ignitionrobotics/ign-gazebo/pull/1149) + * [Pull request #1149](https://github.com/gazebosim/gz-sim/pull/1149) 1. Sensor systems work if loaded after sensors - * [Pull request #1104](https://github.com/ignitionrobotics/ign-gazebo/pull/1104) + * [Pull request #1104](https://github.com/gazebosim/gz-sim/pull/1104) 1. Fix generation of systems library symlinks in build directory - * [Pull request #1160](https://github.com/ignitionrobotics/ign-gazebo/pull/1160) + * [Pull request #1160](https://github.com/gazebosim/gz-sim/pull/1160) 1. Edit material colors in component inspector - * [Pull request #1123](https://github.com/ignitionrobotics/ign-gazebo/pull/1123) + * [Pull request #1123](https://github.com/gazebosim/gz-sim/pull/1123) 1. Support setting the background color for sensors - * [Pull request #1147](https://github.com/ignitionrobotics/ign-gazebo/pull/1147) + * [Pull request #1147](https://github.com/gazebosim/gz-sim/pull/1147) 1. Use uint64_t for ComponentInspector Entity IDs - * [Pull request #1144](https://github.com/ignitionrobotics/ign-gazebo/pull/1144) + * [Pull request #1144](https://github.com/gazebosim/gz-sim/pull/1144) 1. Fix integers and floats on component inspector - * [Pull request #1143](https://github.com/ignitionrobotics/ign-gazebo/pull/1143) + * [Pull request #1143](https://github.com/gazebosim/gz-sim/pull/1143) -### Ignition Gazebo 4.12.0 (2021-10-22) +### Gazebo Sim 4.12.0 (2021-10-22) 1. Fix performance issue with contact data and AABB updates. - * [Pull Request 1048](https://github.com/ignitionrobotics/ign-gazebo/pull/1048) + * [Pull Request 1048](https://github.com/gazebosim/gz-sim/pull/1048) 1. Enable new CMake policy to fix protobuf compilation - * [Pull Request 1059](https://github.com/ignitionrobotics/ign-gazebo/pull/1059) + * [Pull Request 1059](https://github.com/gazebosim/gz-sim/pull/1059) 1. Parse new param for enabling / disabling IMU orientation output. - * [Pull Request 899](https://github.com/ignitionrobotics/ign-gazebo/pull/899) + * [Pull Request 899](https://github.com/gazebosim/gz-sim/pull/899) 1. Fix light control standalone example. - * [Pull Request 1077](https://github.com/ignitionrobotics/ign-gazebo/pull/1077) + * [Pull Request 1077](https://github.com/gazebosim/gz-sim/pull/1077) 1. Performance: use std::unordered_map where possible in SceneManager. - * [Pull Request 1083](https://github.com/ignitionrobotics/ign-gazebo/pull/1083) + * [Pull Request 1083](https://github.com/gazebosim/gz-sim/pull/1083) 1. Prevent crash when using workflow PBR material. - * [Pull Request 1099](https://github.com/ignitionrobotics/ign-gazebo/pull/1099) + * [Pull Request 1099](https://github.com/gazebosim/gz-sim/pull/1099) 1. JointPositionController: Improve misleading error message. - * [Pull Request 1098](https://github.com/ignitionrobotics/ign-gazebo/pull/1098) + * [Pull Request 1098](https://github.com/gazebosim/gz-sim/pull/1098) 1. Adjust pose decimals based on element width. - * [Pull Request 1089](https://github.com/ignitionrobotics/ign-gazebo/pull/1089) + * [Pull Request 1089](https://github.com/gazebosim/gz-sim/pull/1089) 1. Better protect this->dataPtr->initialized with renderMutex. - * [Pull Request 1119](https://github.com/ignitionrobotics/ign-gazebo/pull/1089) + * [Pull Request 1119](https://github.com/gazebosim/gz-sim/pull/1089) 1. Updates to camera video record from subt. - * [Pull Request 1117](https://github.com/ignitionrobotics/ign-gazebo/pull/1117) + * [Pull Request 1117](https://github.com/gazebosim/gz-sim/pull/1117) 1. Fix performance level test flakiness. - * [Pull Request 1129](https://github.com/ignitionrobotics/ign-gazebo/pull/1129) + * [Pull Request 1129](https://github.com/gazebosim/gz-sim/pull/1129) -### Ignition Gazebo 4.11.0 (2021-09-23) +### Gazebo Sim 4.11.0 (2021-09-23) 1. Support locked entities, and headless video recording using sim time. - * [Pull Request 862](https://github.com/ignitionrobotics/ign-gazebo/pull/862) + * [Pull Request 862](https://github.com/gazebosim/gz-sim/pull/862) -### Ignition Gazebo 4.10.0 (2021-09-15) +### Gazebo Sim 4.10.0 (2021-09-15) 1. Fixed GUI's ComponentInspector light parameter - * [Pull Request 1018](https://github.com/ignitionrobotics/ign-gazebo/pull/1018) + * [Pull Request 1018](https://github.com/gazebosim/gz-sim/pull/1018) 1. Fix msg in entity_creation example - * [Pull Request 972](https://github.com/ignitionrobotics/ign-gazebo/pull/972) + * [Pull Request 972](https://github.com/gazebosim/gz-sim/pull/972) 1. Fix selection buffer crash on resize - * [Pull Request 969](https://github.com/ignitionrobotics/ign-gazebo/pull/969) + * [Pull Request 969](https://github.com/gazebosim/gz-sim/pull/969) 1. Fix crash in the follow_actor example - * [Pull Request 958](https://github.com/ignitionrobotics/ign-gazebo/pull/958) + * [Pull Request 958](https://github.com/gazebosim/gz-sim/pull/958) 1. Fix joint controller with empty joint velocity data - * [Pull Request 937](https://github.com/ignitionrobotics/ign-gazebo/pull/937) + * [Pull Request 937](https://github.com/gazebosim/gz-sim/pull/937) 1. Scale mode - Part2 - * [Pull Request 881](https://github.com/ignitionrobotics/ign-gazebo/pull/881) + * [Pull Request 881](https://github.com/gazebosim/gz-sim/pull/881) 1. Physics system: update link poses if the canonical link pose has been updated - * [Pull Request 876](https://github.com/ignitionrobotics/ign-gazebo/pull/876) + * [Pull Request 876](https://github.com/gazebosim/gz-sim/pull/876) 1. Add Particle Emitter tutorial - * [Pull Request 860](https://github.com/ignitionrobotics/ign-gazebo/pull/860) + * [Pull Request 860](https://github.com/gazebosim/gz-sim/pull/860) 1. Refactor RenderUtil::Update with helper functions - * [Pull Request 858](https://github.com/ignitionrobotics/ign-gazebo/pull/858) + * [Pull Request 858](https://github.com/gazebosim/gz-sim/pull/858) 1. Remove unneeded camera follow offset checks - * [Pull Request 857](https://github.com/ignitionrobotics/ign-gazebo/pull/857) + * [Pull Request 857](https://github.com/gazebosim/gz-sim/pull/857) 1. Added service to set camera's follow offset - * [Pull Request 855](https://github.com/ignitionrobotics/ign-gazebo/pull/855) + * [Pull Request 855](https://github.com/gazebosim/gz-sim/pull/855) 1. Using math::SpeedLimiter on the ackermann_steering controller. - * [Pull Request 837](https://github.com/ignitionrobotics/ign-gazebo/pull/837) + * [Pull Request 837](https://github.com/gazebosim/gz-sim/pull/837) 1. All changes merged forward from ign-gazebo3 - * [Pull Request 866](https://github.com/ignitionrobotics/ign-gazebo/pull/866) - * [Pull Request 916](https://github.com/ignitionrobotics/ign-gazebo/pull/916) - * [Pull Request 933](https://github.com/ignitionrobotics/ign-gazebo/pull/933) - * [Pull Request 946](https://github.com/ignitionrobotics/ign-gazebo/pull/946) - * [Pull Request 973](https://github.com/ignitionrobotics/ign-gazebo/pull/973) - * [Pull Request 1017](https://github.com/ignitionrobotics/ign-gazebo/pull/1017) + * [Pull Request 866](https://github.com/gazebosim/gz-sim/pull/866) + * [Pull Request 916](https://github.com/gazebosim/gz-sim/pull/916) + * [Pull Request 933](https://github.com/gazebosim/gz-sim/pull/933) + * [Pull Request 946](https://github.com/gazebosim/gz-sim/pull/946) + * [Pull Request 973](https://github.com/gazebosim/gz-sim/pull/973) + * [Pull Request 1017](https://github.com/gazebosim/gz-sim/pull/1017) -### Ignition Gazebo 4.9.1 (2021-05-24) +### Gazebo Sim 4.9.1 (2021-05-24) 1. Make halt motion act like a brake. - * [Pull Request 830](https://github.com/ignitionrobotics/ign-gazebo/pull/830) + * [Pull Request 830](https://github.com/gazebosim/gz-sim/pull/830) -### Ignition Gazebo 4.9.0 (2021-05-20) +### Gazebo Sim 4.9.0 (2021-05-20) 1. Enable Focal CI. - * [Pull Request 646](https://github.com/ignitionrobotics/ign-gazebo/pull/646) + * [Pull Request 646](https://github.com/gazebosim/gz-sim/pull/646) 1. [TPE] Support setting individual link velocity. - * [Pull Request 427](https://github.com/ignitionrobotics/ign-gazebo/pull/427) + * [Pull Request 427](https://github.com/gazebosim/gz-sim/pull/427) 1. Don't store duplicate ComponentTypeId in ECM. - * [Pull Request 751](https://github.com/ignitionrobotics/ign-gazebo/pull/751) + * [Pull Request 751](https://github.com/gazebosim/gz-sim/pull/751) 1. Fix macOS build: components::Name in benchmark. - * [Pull Request 784](https://github.com/ignitionrobotics/ign-gazebo/pull/784) + * [Pull Request 784](https://github.com/gazebosim/gz-sim/pull/784) 1. Fix documentation for EntityComponentManager::EachNew. - * [Pull Request 795](https://github.com/ignitionrobotics/ign-gazebo/pull/795) + * [Pull Request 795](https://github.com/gazebosim/gz-sim/pull/795) 1. Add functionalities for optical tactile plugin. - * [Pull Request 431](https://github.com/ignitionrobotics/ign-gazebo/pull/431) + * [Pull Request 431](https://github.com/gazebosim/gz-sim/pull/431) 1. Visualize ContactSensorData. - * [Pull Request 234](https://github.com/ignitionrobotics/ign-gazebo/pull/234) + * [Pull Request 234](https://github.com/gazebosim/gz-sim/pull/234) 1. Backport PR #763. - * [Pull Request 804](https://github.com/ignitionrobotics/ign-gazebo/pull/804) + * [Pull Request 804](https://github.com/gazebosim/gz-sim/pull/804) 1. Backport PR #536. - * [Pull Request 812](https://github.com/ignitionrobotics/ign-gazebo/pull/812) + * [Pull Request 812](https://github.com/gazebosim/gz-sim/pull/812) 1. Add an optional delay to the TriggeredPublisher system. - * [Pull Request 817](https://github.com/ignitionrobotics/ign-gazebo/pull/817) + * [Pull Request 817](https://github.com/gazebosim/gz-sim/pull/817) 1. Remove tools/code_check and update codecov. - * [Pull Request 814](https://github.com/ignitionrobotics/ign-gazebo/pull/814) + * [Pull Request 814](https://github.com/gazebosim/gz-sim/pull/814) 1. add conversion for particle scatter ratio field. - * [Pull Request 791](https://github.com/ignitionrobotics/ign-gazebo/pull/791) + * [Pull Request 791](https://github.com/gazebosim/gz-sim/pull/791) -### Ignition Gazebo 4.8.0 (2021-04-22) +### Gazebo Sim 4.8.0 (2021-04-22) 1. Add odometry publisher system. - * [Pull Request 547](https://github.com/ignitionrobotics/ign-gazebo/pull/547) + * [Pull Request 547](https://github.com/gazebosim/gz-sim/pull/547) 1. Patch particle emitter2 service. - * [Pull Request 777](https://github.com/ignitionrobotics/ign-gazebo/pull/777) + * [Pull Request 777](https://github.com/gazebosim/gz-sim/pull/777) -### Ignition Gazebo 4.7.0 (2021-04-09) +### Gazebo Sim 4.7.0 (2021-04-09) 1. Particle emitter based on SDF. - * [Pull Request 730](https://github.com/ignitionrobotics/ign-gazebo/pull/730) + * [Pull Request 730](https://github.com/gazebosim/gz-sim/pull/730) 1. Fix log playback for particle emitters. - * [Pull Request 745](https://github.com/ignitionrobotics/ign-gazebo/pull/745) + * [Pull Request 745](https://github.com/gazebosim/gz-sim/pull/745) 1. ECM's ChangedState gets message with modified components. - * [Pull Request 742](https://github.com/ignitionrobotics/ign-gazebo/pull/742) + * [Pull Request 742](https://github.com/gazebosim/gz-sim/pull/742) 1. Fixed collision visual bounding boxes. - * [Pull Request 746](https://github.com/ignitionrobotics/ign-gazebo/pull/746) + * [Pull Request 746](https://github.com/gazebosim/gz-sim/pull/746) 1. Fix compute_rtfs arguments. - * [Pull Request 737](https://github.com/ignitionrobotics/ign-gazebo/pull/737) + * [Pull Request 737](https://github.com/gazebosim/gz-sim/pull/737) 1. Validate step size and RTF parameters. - * [Pull Request 740](https://github.com/ignitionrobotics/ign-gazebo/pull/740) + * [Pull Request 740](https://github.com/gazebosim/gz-sim/pull/740) 1. Use Protobuf_IMPORT_DIRS instead of PROTOBUF_IMPORT_DIRS for compatibility with Protobuf CMake config. - * [Pull Request 715](https://github.com/ignitionrobotics/ign-gazebo/pull/715) + * [Pull Request 715](https://github.com/gazebosim/gz-sim/pull/715) 1. Do not pass -Wno-unused-parameter to MSVC compiler. - * [Pull Request 716](https://github.com/ignitionrobotics/ign-gazebo/pull/716) + * [Pull Request 716](https://github.com/gazebosim/gz-sim/pull/716) 1. Support configuring particle scatter ratio in particle emitter system. - * [Pull Request 674](https://github.com/ignitionrobotics/ign-gazebo/pull/674) + * [Pull Request 674](https://github.com/gazebosim/gz-sim/pull/674) 1. Fix diffuse and ambient values for ackermann example. - * [Pull Request 707](https://github.com/ignitionrobotics/ign-gazebo/pull/707) + * [Pull Request 707](https://github.com/gazebosim/gz-sim/pull/707) 1. Scenebroadcaster sensors. - * [Pull Request 698](https://github.com/ignitionrobotics/ign-gazebo/pull/698) + * [Pull Request 698](https://github.com/gazebosim/gz-sim/pull/698) 1. Add thermal camera test for object temperature below 0. - * [Pull Request 621](https://github.com/ignitionrobotics/ign-gazebo/pull/621) + * [Pull Request 621](https://github.com/gazebosim/gz-sim/pull/621) 1. [BULLET] Making GetContactsFromLastStepFeature optional in Collision Features - * [Pull Request 690](https://github.com/ignitionrobotics/ign-gazebo/pull/690) + * [Pull Request 690](https://github.com/gazebosim/gz-sim/pull/690) 1. Fix joint controller GUI test. - * [Pull Request 697](https://github.com/ignitionrobotics/ign-gazebo/pull/697) + * [Pull Request 697](https://github.com/gazebosim/gz-sim/pull/697) 1. Quiet warnings from Joint State Publisher. - * [Pull Request 696](https://github.com/ignitionrobotics/ign-gazebo/pull/696) + * [Pull Request 696](https://github.com/gazebosim/gz-sim/pull/696) 1. Ackermann Steering Plugin. - * [Pull Request 618](https://github.com/ignitionrobotics/ign-gazebo/pull/618) + * [Pull Request 618](https://github.com/gazebosim/gz-sim/pull/618) 1. Remove bounding box when model is deleted - * [Pull Request 675](https://github.com/ignitionrobotics/ign-gazebo/pull/675) + * [Pull Request 675](https://github.com/gazebosim/gz-sim/pull/675) 1. Cache link poses to improve performance. - * [Pull Request 669](https://github.com/ignitionrobotics/ign-gazebo/pull/669) + * [Pull Request 669](https://github.com/gazebosim/gz-sim/pull/669) 1. Check empty world name in Scene3d. - * [Pull Request 662](https://github.com/ignitionrobotics/ign-gazebo/pull/662) + * [Pull Request 662](https://github.com/gazebosim/gz-sim/pull/662) 1. All changes up to 3.8.0. -### Ignition Gazebo 4.6.0 (2021-03-01) +### Gazebo Sim 4.6.0 (2021-03-01) 1. Use a custom data structure to manage entity feature maps. - * [Pull Request 586](https://github.com/ignitionrobotics/ign-gazebo/pull/586) + * [Pull Request 586](https://github.com/gazebosim/gz-sim/pull/586) 1. Limit scene broadcast publications when paused. - * [Pull Request 497](https://github.com/ignitionrobotics/ign-gazebo/pull/497) + * [Pull Request 497](https://github.com/gazebosim/gz-sim/pull/497) 1. Report performer count in PerformerDetector plugin. - * [Pull Request 652](https://github.com/ignitionrobotics/ign-gazebo/pull/652) + * [Pull Request 652](https://github.com/gazebosim/gz-sim/pull/652) 1. Cache top level and static to speed up physics system. - * [Pull Request 656](https://github.com/ignitionrobotics/ign-gazebo/pull/656) + * [Pull Request 656](https://github.com/gazebosim/gz-sim/pull/656) 1. Support particle emitter modification using partial message. - * [Pull Request 651](https://github.com/ignitionrobotics/ign-gazebo/pull/651) + * [Pull Request 651](https://github.com/gazebosim/gz-sim/pull/651) 1. Set LD_LIBRARY_PATH on Actions CI. - * [Pull Request 650](https://github.com/ignitionrobotics/ign-gazebo/pull/650) + * [Pull Request 650](https://github.com/gazebosim/gz-sim/pull/650) 1. Fix flaky SceneBroadcaster test. - * [Pull Request 641](https://github.com/ignitionrobotics/ign-gazebo/pull/641) + * [Pull Request 641](https://github.com/gazebosim/gz-sim/pull/641) 1. Add a convenience function for getting possibly non-existing components. - * [Pull Request 629](https://github.com/ignitionrobotics/ign-gazebo/pull/629) + * [Pull Request 629](https://github.com/gazebosim/gz-sim/pull/629) 1. Add msg to show the computed temperature range computed from temperature gradient. - * [Pull Request 643](https://github.com/ignitionrobotics/ign-gazebo/pull/643) + * [Pull Request 643](https://github.com/gazebosim/gz-sim/pull/643) 1. Add TF/Pose_V pub in DiffDrive. - * [Pull Request 548](https://github.com/ignitionrobotics/ign-gazebo/pull/548) + * [Pull Request 548](https://github.com/gazebosim/gz-sim/pull/548) 1. Relax flaky performance test. - * [Pull Request 640](https://github.com/ignitionrobotics/ign-gazebo/pull/640) + * [Pull Request 640](https://github.com/gazebosim/gz-sim/pull/640) 1. Improve velocity control test. - * [Pull Request 642](https://github.com/ignitionrobotics/ign-gazebo/pull/642) + * [Pull Request 642](https://github.com/gazebosim/gz-sim/pull/642) 1. Validity check for user defined topics in JointPositionController. - * [Pull Request 639](https://github.com/ignitionrobotics/ign-gazebo/pull/639) + * [Pull Request 639](https://github.com/gazebosim/gz-sim/pull/639) 1. Add laser_retro support. - * [Pull Request 603](https://github.com/ignitionrobotics/ign-gazebo/pull/603) + * [Pull Request 603](https://github.com/gazebosim/gz-sim/pull/603) 1. Fix pose of plane visual with non-default normal vector. - * [Pull Request 574](https://github.com/ignitionrobotics/ign-gazebo/pull/574) + * [Pull Request 574](https://github.com/gazebosim/gz-sim/pull/574) -### Ignition Gazebo 4.5.0 (2020-02-17) +### Gazebo Sim 4.5.0 (2020-02-17) 1. Added particle system. - * [Pull Request 516](https://github.com/ignitionrobotics/ign-gazebo/pull/516) + * [Pull Request 516](https://github.com/gazebosim/gz-sim/pull/516) 1. Add Light Usercommand and include Light parameters in the componentInspector - * [Pull Request 482](https://github.com/ignitionrobotics/ign-gazebo/pull/482) + * [Pull Request 482](https://github.com/gazebosim/gz-sim/pull/482) 1. Added link to HW-accelerated video recording. - * [Pull Request 627](https://github.com/ignitionrobotics/ign-gazebo/pull/627) + * [Pull Request 627](https://github.com/gazebosim/gz-sim/pull/627) 1. Fix EntityComponentManager race condition. - * [Pull Request 601](https://github.com/ignitionrobotics/ign-gazebo/pull/601) + * [Pull Request 601](https://github.com/gazebosim/gz-sim/pull/601) 1. Add SDF topic validity check. - * [Pull Request 632](https://github.com/ignitionrobotics/ign-gazebo/pull/632) + * [Pull Request 632](https://github.com/gazebosim/gz-sim/pull/632) 1. Add JointTrajectoryController system plugin. - * [Pull Request 473](https://github.com/ignitionrobotics/ign-gazebo/pull/473) + * [Pull Request 473](https://github.com/gazebosim/gz-sim/pull/473) -### Ignition Gazebo 4.4.0 (2020-02-10) +### Gazebo Sim 4.4.0 (2020-02-10) 1. Added issue and PR templates - * [Pull Request 613](https://github.com/ignitionrobotics/ign-gazebo/pull/613) + * [Pull Request 613](https://github.com/gazebosim/gz-sim/pull/613) 1. Fix segfault in SetRemovedComponentsMsgs method - * [Pull Request 495](https://github.com/ignitionrobotics/ign-gazebo/pull/495) + * [Pull Request 495](https://github.com/gazebosim/gz-sim/pull/495) 1. Make topics configurable for joint controllers - * [Pull Request 584](https://github.com/ignitionrobotics/ign-gazebo/pull/584) + * [Pull Request 584](https://github.com/gazebosim/gz-sim/pull/584) 1. Add about dialog - * [Pull Request 609](https://github.com/ignitionrobotics/ign-gazebo/pull/609) + * [Pull Request 609](https://github.com/gazebosim/gz-sim/pull/609) 1. Add thermal sensor system for configuring thermal camera properties - * [Pull Request 614](https://github.com/ignitionrobotics/ign-gazebo/pull/614) + * [Pull Request 614](https://github.com/gazebosim/gz-sim/pull/614) -### Ignition Gazebo 4.3.0 (2020-02-02) +### Gazebo Sim 4.3.0 (2020-02-02) 1. Non-blocking paths request. - * [Pull Request 555](https://github.com/ignitionrobotics/ign-gazebo/pull/555) + * [Pull Request 555](https://github.com/gazebosim/gz-sim/pull/555) 1. Parallelize State call in ECM. - * [Pull Request 451](https://github.com/ignitionrobotics/ign-gazebo/pull/451) + * [Pull Request 451](https://github.com/gazebosim/gz-sim/pull/451) 1. Allow to create light with the create service. - * [Pull Request 513](https://github.com/ignitionrobotics/ign-gazebo/pull/513) + * [Pull Request 513](https://github.com/gazebosim/gz-sim/pull/513) 1. Added size to ground_plane in examples. - * [Pull Request 573](https://github.com/ignitionrobotics/ign-gazebo/pull/573) + * [Pull Request 573](https://github.com/gazebosim/gz-sim/pull/573) 1. Fix finding PBR materials. - * [Pull Request 575](https://github.com/ignitionrobotics/ign-gazebo/pull/575) + * [Pull Request 575](https://github.com/gazebosim/gz-sim/pull/575) 1. Publish all periodic change components in Scene Broadcaster. - * [Pull Request 544](https://github.com/ignitionrobotics/ign-gazebo/pull/544) + * [Pull Request 544](https://github.com/gazebosim/gz-sim/pull/544) -1. Backport state update changes from pull request [#486](https://github.com/ignitionrobotics/ign-gazebo/pull/486). - * [Pull Request 583](https://github.com/ignitionrobotics/ign-gazebo/pull/583) +1. Backport state update changes from pull request [#486](https://github.com/gazebosim/gz-sim/pull/486). + * [Pull Request 583](https://github.com/gazebosim/gz-sim/pull/583) 1. Fix code_check errors. - * [Pull Request 582](https://github.com/ignitionrobotics/ign-gazebo/pull/582) + * [Pull Request 582](https://github.com/gazebosim/gz-sim/pull/582) 1. Visualize collisions. - * [Pull Request 531](https://github.com/ignitionrobotics/ign-gazebo/pull/531) + * [Pull Request 531](https://github.com/gazebosim/gz-sim/pull/531) 1. Remove playback SDF param in Dome. - * [Pull Request 570](https://github.com/ignitionrobotics/ign-gazebo/pull/570) + * [Pull Request 570](https://github.com/gazebosim/gz-sim/pull/570) 1. Tutorial on migrating SDF files from Gazebo classic. - * [Pull Request 400](https://github.com/ignitionrobotics/ign-gazebo/pull/400) + * [Pull Request 400](https://github.com/gazebosim/gz-sim/pull/400) 1. World Exporter. - * [Pull Request 474](https://github.com/ignitionrobotics/ign-gazebo/pull/474) + * [Pull Request 474](https://github.com/gazebosim/gz-sim/pull/474) 1. Model Creation tutorial using services. - * [Pull Request 530](https://github.com/ignitionrobotics/ign-gazebo/pull/530) + * [Pull Request 530](https://github.com/gazebosim/gz-sim/pull/530) 1. Fix topLevelModel Method. - * [Pull Request 600](https://github.com/ignitionrobotics/ign-gazebo/pull/600) + * [Pull Request 600](https://github.com/gazebosim/gz-sim/pull/600) 1. Add heat signature option to thermal system. - * [Pull Request 498](https://github.com/ignitionrobotics/ign-gazebo/pull/498) + * [Pull Request 498](https://github.com/gazebosim/gz-sim/pull/498) 1. Add service and GUI to configure physics parameters (step size and RTF). - * [Pull Request 536](https://github.com/ignitionrobotics/ign-gazebo/pull/536) + * [Pull Request 536](https://github.com/gazebosim/gz-sim/pull/536) 1. Refactor UNIT_Server_TEST. - * [Pull Request 594](https://github.com/ignitionrobotics/ign-gazebo/pull/594) + * [Pull Request 594](https://github.com/gazebosim/gz-sim/pull/594) -1. Use Ignition GUI render event. - * [Pull Request 598](https://github.com/ignitionrobotics/ign-gazebo/pull/598) +1. Use Gazebo GUI render event. + * [Pull Request 598](https://github.com/gazebosim/gz-sim/pull/598) -### Ignition Gazebo 4.2.0 (2020-01-13) +### Gazebo Sim 4.2.0 (2020-01-13) 1. Automatically load a subset of world plugins. - * [Pull Request 537](https://github.com/ignitionrobotics/ign-gazebo/pull/537) + * [Pull Request 537](https://github.com/gazebosim/gz-sim/pull/537) 1. Fix to handle multiple logical cameras. - * [Pull Request 539](https://github.com/ignitionrobotics/ign-gazebo/pull/539) + * [Pull Request 539](https://github.com/gazebosim/gz-sim/pull/539) 1. Improve ign tool support on macOS. - * [Pull Request 477](https://github.com/ignitionrobotics/ign-gazebo/pull/477) + * [Pull Request 477](https://github.com/gazebosim/gz-sim/pull/477) 1. Add support for topic statistics on breadcrumb deployments. - * [Pull Request 532](https://github.com/ignitionrobotics/ign-gazebo/pull/532) + * [Pull Request 532](https://github.com/gazebosim/gz-sim/pull/532) 1. Fix slot in Plotting plugin. - * [Pull Request 490](https://github.com/ignitionrobotics/ign-gazebo/pull/490) + * [Pull Request 490](https://github.com/gazebosim/gz-sim/pull/490) 1. Fix shadow artifacts by disabling double sided rendering. - * [Pull Request 446](https://github.com/ignitionrobotics/ign-gazebo/pull/446) + * [Pull Request 446](https://github.com/gazebosim/gz-sim/pull/446) 1. Kinetic energy monitor plugin. - * [Pull Request 492](https://github.com/ignitionrobotics/ign-gazebo/pull/492) + * [Pull Request 492](https://github.com/gazebosim/gz-sim/pull/492) 1. Change nullptr to a int ptr for qt 5.15.2. - * [Pull Request 527](https://github.com/ignitionrobotics/ign-gazebo/pull/527) + * [Pull Request 527](https://github.com/gazebosim/gz-sim/pull/527) 1. Generate valid topics everywhere (support names with spaces). - * [Pull Request 522](https://github.com/ignitionrobotics/ign-gazebo/pull/522) + * [Pull Request 522](https://github.com/gazebosim/gz-sim/pull/522) 1. All changes up to version 3.7.0. -### Ignition Gazebo 4.1.0 (2020-12-11) +### Gazebo Sim 4.1.0 (2020-12-11) 1. Update Dockerfiles to use focal images - * [pull request 388](https://github.com/ignitionrobotics/ign-gazebo/pull/388) + * [pull request 388](https://github.com/gazebosim/gz-sim/pull/388) 1. Updated source build instructions for ign-gazebo4 - * [pull request 404](https://github.com/ignitionrobotics/ign-gazebo/pull/404) + * [pull request 404](https://github.com/gazebosim/gz-sim/pull/404) 1. Add tests for the AnimationTime component - * [pull request 433](https://github.com/ignitionrobotics/ign-gazebo/pull/433) + * [pull request 433](https://github.com/gazebosim/gz-sim/pull/433) 1. Fix pose msg conversion when msg is missing orientation - * [pull request 450](https://github.com/ignitionrobotics/ign-gazebo/pull/450) - * [pull request 459](https://github.com/ignitionrobotics/ign-gazebo/pull/459) + * [pull request 450](https://github.com/gazebosim/gz-sim/pull/450) + * [pull request 459](https://github.com/gazebosim/gz-sim/pull/459) 1. Resolved updated codecheck issues - * [pull request 443](https://github.com/ignitionrobotics/ign-gazebo/pull/443) - * [pull request 457](https://github.com/ignitionrobotics/ign-gazebo/pull/457) - * [pull request 459](https://github.com/ignitionrobotics/ign-gazebo/pull/459) + * [pull request 443](https://github.com/gazebosim/gz-sim/pull/443) + * [pull request 457](https://github.com/gazebosim/gz-sim/pull/457) + * [pull request 459](https://github.com/gazebosim/gz-sim/pull/459) 1. Use new backpack version in tests - * [pull request 455](https://github.com/ignitionrobotics/ign-gazebo/pull/455) - * [pull request 457](https://github.com/ignitionrobotics/ign-gazebo/pull/457) - * [pull request 459](https://github.com/ignitionrobotics/ign-gazebo/pull/459) + * [pull request 455](https://github.com/gazebosim/gz-sim/pull/455) + * [pull request 457](https://github.com/gazebosim/gz-sim/pull/457) + * [pull request 459](https://github.com/gazebosim/gz-sim/pull/459) 1. Fix segfault in the Breadcrumb system when associated model is unloaded - * [pull request 454](https://github.com/ignitionrobotics/ign-gazebo/pull/454) - * [pull request 457](https://github.com/ignitionrobotics/ign-gazebo/pull/457) - * [pull request 459](https://github.com/ignitionrobotics/ign-gazebo/pull/459) + * [pull request 454](https://github.com/gazebosim/gz-sim/pull/454) + * [pull request 457](https://github.com/gazebosim/gz-sim/pull/457) + * [pull request 459](https://github.com/gazebosim/gz-sim/pull/459) 1. Added user commands to example thermal camera world - * [pull request 442](https://github.com/ignitionrobotics/ign-gazebo/pull/442) - * [pull request 459](https://github.com/ignitionrobotics/ign-gazebo/pull/459) + * [pull request 442](https://github.com/gazebosim/gz-sim/pull/442) + * [pull request 459](https://github.com/gazebosim/gz-sim/pull/459) 1. Helper function to set component data - * [pull request 436](https://github.com/ignitionrobotics/ign-gazebo/pull/436) - * [pull request 469](https://github.com/ignitionrobotics/ign-gazebo/pull/469) + * [pull request 436](https://github.com/gazebosim/gz-sim/pull/436) + * [pull request 469](https://github.com/gazebosim/gz-sim/pull/469) 1. Remove unneeded if statement - * [pull request 432](https://github.com/ignitionrobotics/ign-gazebo/pull/432) - * [pull request 469](https://github.com/ignitionrobotics/ign-gazebo/pull/469) + * [pull request 432](https://github.com/gazebosim/gz-sim/pull/432) + * [pull request 469](https://github.com/gazebosim/gz-sim/pull/469) 1. Fix flaky RecordAndPlayback test in INTEGRATION_log_system - * [pull request 463](https://github.com/ignitionrobotics/ign-gazebo/pull/463) - * [pull request 469](https://github.com/ignitionrobotics/ign-gazebo/pull/469) + * [pull request 463](https://github.com/gazebosim/gz-sim/pull/463) + * [pull request 469](https://github.com/gazebosim/gz-sim/pull/469) 1. Make PeerTracker test more robust - * [pull request 452](https://github.com/ignitionrobotics/ign-gazebo/pull/452) - * [pull request 469](https://github.com/ignitionrobotics/ign-gazebo/pull/469) + * [pull request 452](https://github.com/gazebosim/gz-sim/pull/452) + * [pull request 469](https://github.com/gazebosim/gz-sim/pull/469) 1. Use a [std::promise](https://en.cppreference.com/w/cpp/thread/promise)/[std::future](https://en.cppreference.com/w/cpp/thread/future) mechanism to avoid waiting in a looop until all `stepAck` messages are received - * [pull request 470](https://github.com/ignitionrobotics/ign-gazebo/pull/470) + * [pull request 470](https://github.com/gazebosim/gz-sim/pull/470) 1. Optical Tactile Sensor Plugin - * [pull request 229](https://github.com/ignitionrobotics/ign-gazebo/pull/229) + * [pull request 229](https://github.com/gazebosim/gz-sim/pull/229) 1. All changes up to and including those in version 3.5.0 and version 2.25.0 -### Ignition Gazebo 4.0.0 (2020-09-30) +### Gazebo Sim 4.0.0 (2020-09-30) 1. Names with spaces: add string serializer - * [pull request 244](https://github.com/ignitionrobotics/ign-gazebo/pull/244) + * [pull request 244](https://github.com/gazebosim/gz-sim/pull/244) 1. Filter mesh collision based on `collide_bitmask` property - * [pull request 160](https://github.com/ignitionrobotics/ign-gazebo/pull/160) + * [pull request 160](https://github.com/gazebosim/gz-sim/pull/160) 1. Add force focus when mouse enters render window - * [pull request 97](https://github.com/ignitionrobotics/ign-gazebo/pull/97) + * [pull request 97](https://github.com/gazebosim/gz-sim/pull/97) 1. Fixed docblock showGrid - * [pull request 152](https://github.com/ignitionrobotics/ign-gazebo/pull/152) + * [pull request 152](https://github.com/gazebosim/gz-sim/pull/152) 1. More actor components and follow plugin - * [pull request 157](https://github.com/ignitionrobotics/ign-gazebo/pull/157) + * [pull request 157](https://github.com/gazebosim/gz-sim/pull/157) 1. Filter the record menu and write the format to the file according to which button the user pushed (mp4 or ogv) - * [pull request 153](https://github.com/ignitionrobotics/ign-gazebo/pull/153) + * [pull request 153](https://github.com/gazebosim/gz-sim/pull/153) 1. Fix scene manager losing header file - * [pull request 211](https://github.com/ignitionrobotics/ign-gazebo/pull/211) + * [pull request 211](https://github.com/gazebosim/gz-sim/pull/211) 1. Fixed left menu events - * [pull request 218](https://github.com/ignitionrobotics/ign-gazebo/pull/218) + * [pull request 218](https://github.com/gazebosim/gz-sim/pull/218) 1. Fix yaw units typo in Component Inspector plugin - * [pull request 238](https://github.com/ignitionrobotics/ign-gazebo/pull/238) + * [pull request 238](https://github.com/gazebosim/gz-sim/pull/238) 1. Enable alpha based transparency on PBR materials by default - * [pull request 249](https://github.com/ignitionrobotics/ign-gazebo/pull/249) + * [pull request 249](https://github.com/gazebosim/gz-sim/pull/249) 1. Qt auto scale factor for HiDPI displays - * [pull request 291](https://github.com/ignitionrobotics/ign-gazebo/pull/291) + * [pull request 291](https://github.com/gazebosim/gz-sim/pull/291) 1. Sync components removal - * [pull request 272](https://github.com/ignitionrobotics/ign-gazebo/pull/272) + * [pull request 272](https://github.com/gazebosim/gz-sim/pull/272) 1. Add error handling for JointAxis::SetXyz and remove use of use_parent_model_frame - * [pull request 288](https://github.com/ignitionrobotics/ign-gazebo/pull/288) + * [pull request 288](https://github.com/gazebosim/gz-sim/pull/288) 1. Make some tests more robust - * [pull request 314](https://github.com/ignitionrobotics/ign-gazebo/pull/314) + * [pull request 314](https://github.com/gazebosim/gz-sim/pull/314) 1. Fix Qt5 warnings for using anchors - * [pull request 363](https://github.com/ignitionrobotics/ign-gazebo/pull/363) + * [pull request 363](https://github.com/gazebosim/gz-sim/pull/363) 1. Plotting Components Plugin - * [pull request 270](https://github.com/ignitionrobotics/ign-gazebo/pull/270) + * [pull request 270](https://github.com/gazebosim/gz-sim/pull/270) 1. Visualize Lidar Plugin - * [pull request 301](https://github.com/ignitionrobotics/ign-gazebo/pull/301) - * [pull request 391](https://github.com/ignitionrobotics/ign-gazebo/pull/391) + * [pull request 301](https://github.com/gazebosim/gz-sim/pull/301) + * [pull request 391](https://github.com/gazebosim/gz-sim/pull/391) 1. Replaced common::Time for std::chrono - * [pull request 309](https://github.com/ignitionrobotics/ign-gazebo/pull/309) + * [pull request 309](https://github.com/gazebosim/gz-sim/pull/309) 1. Tutorial, examples and documentation updates - * [pull request 380](https://github.com/ignitionrobotics/ign-gazebo/pull/380) - * [pull request 386](https://github.com/ignitionrobotics/ign-gazebo/pull/386) - * [pull request 387](https://github.com/ignitionrobotics/ign-gazebo/pull/387) - * [pull request 390](https://github.com/ignitionrobotics/ign-gazebo/pull/390) + * [pull request 380](https://github.com/gazebosim/gz-sim/pull/380) + * [pull request 386](https://github.com/gazebosim/gz-sim/pull/386) + * [pull request 387](https://github.com/gazebosim/gz-sim/pull/387) + * [pull request 390](https://github.com/gazebosim/gz-sim/pull/390) 1. Migration from BitBucket to GitHub - * [pull request 73](https://github.com/ignitionrobotics/ign-gazebo/pull/73) - * [pull request 68](https://github.com/ignitionrobotics/ign-gazebo/pull/68) - * [pull request 67](https://github.com/ignitionrobotics/ign-gazebo/pull/67) - * [pull request 130](https://github.com/ignitionrobotics/ign-gazebo/pull/130) + * [pull request 73](https://github.com/gazebosim/gz-sim/pull/73) + * [pull request 68](https://github.com/gazebosim/gz-sim/pull/68) + * [pull request 67](https://github.com/gazebosim/gz-sim/pull/67) + * [pull request 130](https://github.com/gazebosim/gz-sim/pull/130) 1. Use interpolate\_x sdf parameter for actor animations * [BitBucket pull request 536](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/536) @@ -1901,615 +1901,615 @@ * [BitBucket pull request 565](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/565) 1. Add window focus upon mouse entering the render window - * [Github pull request 97](https://github.com/ignitionrobotics/ign-gazebo/pull/97) + * [Github pull request 97](https://github.com/gazebosim/gz-sim/pull/97) -## Ignition Gazebo 3.x +## Gazebo Sim 3.x -### Ignition Gazebo 3.X.X (20XX-XX-XX) +### Gazebo Sim 3.X.X (20XX-XX-XX) -### Ignition Gazebo 3.12.0 (2021-11-11) +### Gazebo Sim 3.12.0 (2021-11-11) 1. Prevent creation of spurious `` elements when saving worlds - * [Pull request #1192](https://github.com/ignitionrobotics/ign-gazebo/pull/1192) + * [Pull request #1192](https://github.com/gazebosim/gz-sim/pull/1192) 1. Added support for tracked vehicles - * [Pull request #869](https://github.com/ignitionrobotics/ign-gazebo/pull/869) + * [Pull request #869](https://github.com/gazebosim/gz-sim/pull/869) 1. Add components to dynamically set joint limits - * [Pull request #847](https://github.com/ignitionrobotics/ign-gazebo/pull/847) + * [Pull request #847](https://github.com/gazebosim/gz-sim/pull/847) 1. Fix updating a component's data via SerializedState msg - * [Pull request #1149](https://github.com/ignitionrobotics/ign-gazebo/pull/1149) + * [Pull request #1149](https://github.com/gazebosim/gz-sim/pull/1149) 1. Sensor systems work if loaded after sensors - * [Pull request #1104](https://github.com/ignitionrobotics/ign-gazebo/pull/1104) + * [Pull request #1104](https://github.com/gazebosim/gz-sim/pull/1104) 1. Fix generation of systems library symlinks in build directory - * [Pull request #1160](https://github.com/ignitionrobotics/ign-gazebo/pull/1160) + * [Pull request #1160](https://github.com/gazebosim/gz-sim/pull/1160) -1. Backport gazebo::Util::validTopic() from ign-gazebo4. - * [Pull request #1153](https://github.com/ignitionrobotics/ign-gazebo/pull/1153) +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 - * [Pull request #1147](https://github.com/ignitionrobotics/ign-gazebo/pull/1147) + * [Pull request #1147](https://github.com/gazebosim/gz-sim/pull/1147) 1. Use uint64_t for ComponentInspector Entity IDs - * [Pull request #1144](https://github.com/ignitionrobotics/ign-gazebo/pull/1144) + * [Pull request #1144](https://github.com/gazebosim/gz-sim/pull/1144) 1. Fix integers and floats on component inspector - * [Pull request #1143](https://github.com/ignitionrobotics/ign-gazebo/pull/1143) + * [Pull request #1143](https://github.com/gazebosim/gz-sim/pull/1143) -### Ignition Gazebo 3.11.0 (2021-10-21) +### Gazebo Sim 3.11.0 (2021-10-21) 1. Updates to camera video record from subt. - * [Pull request #1117](https://github.com/ignitionrobotics/ign-gazebo/pull/1117) + * [Pull request #1117](https://github.com/gazebosim/gz-sim/pull/1117) 1. Fix performance level test flakiness. - * [Pull request #1129](https://github.com/ignitionrobotics/ign-gazebo/pull/1129) + * [Pull request #1129](https://github.com/gazebosim/gz-sim/pull/1129) -### Ignition Gazebo 3.10.0 (2021-10-15) +### Gazebo Sim 3.10.0 (2021-10-15) 1. Performance: use std::unordered_map where possible in SceneManager - * [Pull request #1083](https://github.com/ignitionrobotics/ign-gazebo/pull/1083) + * [Pull request #1083](https://github.com/gazebosim/gz-sim/pull/1083) 1. Enable new CMake policy to fix protobuf compilation - * [Pull request #1059](https://github.com/ignitionrobotics/ign-gazebo/pull/1059) + * [Pull request #1059](https://github.com/gazebosim/gz-sim/pull/1059) 1. Fix setting cast_shadows for visuals without material - * [Pull request #1015](https://github.com/ignitionrobotics/ign-gazebo/pull/1015) + * [Pull request #1015](https://github.com/gazebosim/gz-sim/pull/1015) 1. Remove duplicate XML tag in pendulum_links example world - * [Pull request #1002](https://github.com/ignitionrobotics/ign-gazebo/pull/1002) + * [Pull request #1002](https://github.com/gazebosim/gz-sim/pull/1002) 1. Enable sensor metrics on example worlds - * [Pull request #982](https://github.com/ignitionrobotics/ign-gazebo/pull/982) + * [Pull request #982](https://github.com/gazebosim/gz-sim/pull/982) 1. Improved doxygen - * [Pull request #996](https://github.com/ignitionrobotics/ign-gazebo/pull/996) + * [Pull request #996](https://github.com/gazebosim/gz-sim/pull/996) 1. JointPositionController: Improve misleading error message - * [Pull request #1098](https://github.com/ignitionrobotics/ign-gazebo/pull/1098) + * [Pull request #1098](https://github.com/gazebosim/gz-sim/pull/1098) 1. Adjust pose decimals based on element width - * [Pull request #1089](https://github.com/ignitionrobotics/ign-gazebo/pull/1089) + * [Pull request #1089](https://github.com/gazebosim/gz-sim/pull/1089) 1. Fixed IMU system plugin - * [Pull request #1043](https://github.com/ignitionrobotics/ign-gazebo/pull/1043) + * [Pull request #1043](https://github.com/gazebosim/gz-sim/pull/1043) 1. Use QTimer to update plugins in the Qt thread - * [Pull request #1095](https://github.com/ignitionrobotics/ign-gazebo/pull/1095) + * [Pull request #1095](https://github.com/gazebosim/gz-sim/pull/1095) -### Ignition Gazebo 3.9.0 (2021-08-16) +### Gazebo Sim 3.9.0 (2021-08-16) 1. Entity tree: prevent creation of repeated entity items - * [Pull request #974](https://github.com/ignitionrobotics/ign-gazebo/pull/974) + * [Pull request #974](https://github.com/gazebosim/gz-sim/pull/974) 1. Don't use $HOME on most tests (InternalFixture) - * [Pull request #971](https://github.com/ignitionrobotics/ign-gazebo/pull/971) + * [Pull request #971](https://github.com/gazebosim/gz-sim/pull/971) 1. Be more specific when looking for physics plugins - * [Pull request #965](https://github.com/ignitionrobotics/ign-gazebo/pull/965) + * [Pull request #965](https://github.com/gazebosim/gz-sim/pull/965) 1. Drag and drop meshes into scene - * [Pull request #939](https://github.com/ignitionrobotics/ign-gazebo/pull/939) + * [Pull request #939](https://github.com/gazebosim/gz-sim/pull/939) 1. Set protobuf_MODULE_COMPATIBLE before any find_package call - * [Pull request #957](https://github.com/ignitionrobotics/ign-gazebo/pull/957) + * [Pull request #957](https://github.com/gazebosim/gz-sim/pull/957) 1. [DiffDrive] add enable/disable - * [Pull request #772](https://github.com/ignitionrobotics/ign-gazebo/pull/772) + * [Pull request #772](https://github.com/gazebosim/gz-sim/pull/772) 1. Fix component inspector shutdown crash - * [Pull request #724](https://github.com/ignitionrobotics/ign-gazebo/pull/724) + * [Pull request #724](https://github.com/gazebosim/gz-sim/pull/724) 1. Add UserCommands Plugin. - * [Pull request #719](https://github.com/ignitionrobotics/ign-gazebo/pull/719) + * [Pull request #719](https://github.com/gazebosim/gz-sim/pull/719) 1. Setting the intiial velocity for a model or joint - * [Pull request #693](https://github.com/ignitionrobotics/ign-gazebo/pull/693) + * [Pull request #693](https://github.com/gazebosim/gz-sim/pull/693) 1. Examples and tutorial on using rendering API from plugins - * [Pull request #596](https://github.com/ignitionrobotics/ign-gazebo/pull/596) + * [Pull request #596](https://github.com/gazebosim/gz-sim/pull/596) -1. Add missing IGNITION_GAZEBO_VISIBLE macros - * [Pull request #563](https://github.com/ignitionrobotics/ign-gazebo/pull/563) +1. Add missing GZ_GAZEBO_VISIBLE macros + * [Pull request #563](https://github.com/gazebosim/gz-sim/pull/563) 1. Fix visibility macro names when used by a different component (Windows) - * [Pull request #564](https://github.com/ignitionrobotics/ign-gazebo/pull/564) + * [Pull request #564](https://github.com/gazebosim/gz-sim/pull/564) 1. No install apt recommends and clear cache - * [Pull request #423](https://github.com/ignitionrobotics/ign-gazebo/pull/423) + * [Pull request #423](https://github.com/gazebosim/gz-sim/pull/423) 1. Add 25percent darker view angle icons - * [Pull request #426](https://github.com/ignitionrobotics/ign-gazebo/pull/426) + * [Pull request #426](https://github.com/gazebosim/gz-sim/pull/426) 1. Expose a test fixture helper class - * [Pull request #926](https://github.com/ignitionrobotics/ign-gazebo/pull/926) + * [Pull request #926](https://github.com/gazebosim/gz-sim/pull/926) 1. Fix logic to disable server default plugins loading - * [Pull request #953](https://github.com/ignitionrobotics/ign-gazebo/pull/953) + * [Pull request #953](https://github.com/gazebosim/gz-sim/pull/953) 1. removed unneeded plugin update - * [Pull request #944](https://github.com/ignitionrobotics/ign-gazebo/pull/944) + * [Pull request #944](https://github.com/gazebosim/gz-sim/pull/944) 1. Functions to enable velocity and acceleration checks on Link - * [Pull request #935](https://github.com/ignitionrobotics/ign-gazebo/pull/935) + * [Pull request #935](https://github.com/gazebosim/gz-sim/pull/935) 1. Support adding systems that don't come from a plugin - * [Pull request #936](https://github.com/ignitionrobotics/ign-gazebo/pull/936) + * [Pull request #936](https://github.com/gazebosim/gz-sim/pull/936) 1. 3D plot GUI plugin - * [Pull request #917](https://github.com/ignitionrobotics/ign-gazebo/pull/917) + * [Pull request #917](https://github.com/gazebosim/gz-sim/pull/917) 1. Add a convenience function for getting possibly non-existing components. - * [Pull request #629](https://github.com/ignitionrobotics/ign-gazebo/pull/629) + * [Pull request #629](https://github.com/gazebosim/gz-sim/pull/629) 1. Fix topLevelModel method - * [Pull request #600](https://github.com/ignitionrobotics/ign-gazebo/pull/600) + * [Pull request #600](https://github.com/gazebosim/gz-sim/pull/600) 1. World exporter - * [Pull request #474](https://github.com/ignitionrobotics/ign-gazebo/pull/474) + * [Pull request #474](https://github.com/gazebosim/gz-sim/pull/474) 1. Fix finding PBR materials - * [Pull request #575](https://github.com/ignitionrobotics/ign-gazebo/pull/575) + * [Pull request #575](https://github.com/gazebosim/gz-sim/pull/575) 1. Handle multiple logical cameras - * [Pull request #539](https://github.com/ignitionrobotics/ign-gazebo/pull/539) + * [Pull request #539](https://github.com/gazebosim/gz-sim/pull/539) 1. Make some tests more robust - * [Pull request #314](https://github.com/ignitionrobotics/ign-gazebo/pull/314) + * [Pull request #314](https://github.com/gazebosim/gz-sim/pull/314) 1. Fix codecheck - * [Pull request #887](https://github.com/ignitionrobotics/ign-gazebo/pull/887) + * [Pull request #887](https://github.com/gazebosim/gz-sim/pull/887) 1. Hello world plugin added - * [Pull request #699](https://github.com/ignitionrobotics/ign-gazebo/pull/699) + * [Pull request #699](https://github.com/gazebosim/gz-sim/pull/699) 1. Model info CLI `ign model` - * [Pull request #893](https://github.com/ignitionrobotics/ign-gazebo/pull/893) + * [Pull request #893](https://github.com/gazebosim/gz-sim/pull/893) 1. Don't create components for entities that don't exist - * [Pull request #927](https://github.com/ignitionrobotics/ign-gazebo/pull/927) + * [Pull request #927](https://github.com/gazebosim/gz-sim/pull/927) 1. Adds Mesh Tutorial - * [Pull request #915](https://github.com/ignitionrobotics/ign-gazebo/pull/915) + * [Pull request #915](https://github.com/gazebosim/gz-sim/pull/915) 1. Fix updating GUI plugin on load - * [Pull request #904](https://github.com/ignitionrobotics/ign-gazebo/pull/904) + * [Pull request #904](https://github.com/gazebosim/gz-sim/pull/904) 1. Fix documentation for the Sensor component - * [Pull request #898](https://github.com/ignitionrobotics/ign-gazebo/pull/898) + * [Pull request #898](https://github.com/gazebosim/gz-sim/pull/898) 1. Use UINT64_MAX for kComponentTpyeIDInvalid instead of relying on underflow - * [Pull request #889](https://github.com/ignitionrobotics/ign-gazebo/pull/889) + * [Pull request #889](https://github.com/gazebosim/gz-sim/pull/889) 1. Fix mouse view control target position - * [Pull request #879](https://github.com/ignitionrobotics/ign-gazebo/pull/879) + * [Pull request #879](https://github.com/gazebosim/gz-sim/pull/879) 1. Set GUI camera pose - * [Pull request #863](https://github.com/ignitionrobotics/ign-gazebo/pull/863) + * [Pull request #863](https://github.com/gazebosim/gz-sim/pull/863) 1. Enables confirmation dialog when closing Gazebo. - * [Pull request #850](https://github.com/ignitionrobotics/ign-gazebo/pull/850) + * [Pull request #850](https://github.com/gazebosim/gz-sim/pull/850) 1. Depend on ign-rendering 3.5 - * [Pull request #867](https://github.com/ignitionrobotics/ign-gazebo/pull/867) + * [Pull request #867](https://github.com/gazebosim/gz-sim/pull/867) 1. Using math::SpeedLimiter on the diff_drive controller. - * [Pull request #833](https://github.com/ignitionrobotics/ign-gazebo/pull/833) + * [Pull request #833](https://github.com/gazebosim/gz-sim/pull/833) 1. New example: get an ECM snapshot from an external program - * [Pull request #859](https://github.com/ignitionrobotics/ign-gazebo/pull/859) + * [Pull request #859](https://github.com/gazebosim/gz-sim/pull/859) 1. Fix WindEffects Plugin bug, not configuring new links - * [Pull request #844](https://github.com/ignitionrobotics/ign-gazebo/pull/844) + * [Pull request #844](https://github.com/gazebosim/gz-sim/pull/844) 1. Fix potentially flaky integration component test case - * [Pull request #848](https://github.com/ignitionrobotics/ign-gazebo/pull/848) + * [Pull request #848](https://github.com/gazebosim/gz-sim/pull/848) 1. Cleanup and alphabetize plugin headers - * [Pull request #838](https://github.com/ignitionrobotics/ign-gazebo/pull/838) + * [Pull request #838](https://github.com/gazebosim/gz-sim/pull/838) 1. Removed duplicated code with rendering::sceneFromFirstRenderEngine - * [Pull request #819](https://github.com/ignitionrobotics/ign-gazebo/pull/819) + * [Pull request #819](https://github.com/gazebosim/gz-sim/pull/819) 1. Remove unused headers in video_recoder plugin - * [Pull request #834](https://github.com/ignitionrobotics/ign-gazebo/pull/834) + * [Pull request #834](https://github.com/gazebosim/gz-sim/pull/834) 1. Use moveToHelper from ign-rendering - * [Pull request #825](https://github.com/ignitionrobotics/ign-gazebo/pull/825) + * [Pull request #825](https://github.com/gazebosim/gz-sim/pull/825) 1. Remove tools/code_check and update codecov - * [Pull request #814](https://github.com/ignitionrobotics/ign-gazebo/pull/814) + * [Pull request #814](https://github.com/gazebosim/gz-sim/pull/814) 1. Add service and GUI to configure physics parameters - * [Pull request #536](https://github.com/ignitionrobotics/ign-gazebo/pull/536) - * [Pull request #812](https://github.com/ignitionrobotics/ign-gazebo/pull/812) + * [Pull request #536](https://github.com/gazebosim/gz-sim/pull/536) + * [Pull request #812](https://github.com/gazebosim/gz-sim/pull/812) 1. Fix documentation for EntityComponentManager::EachNew - * [Pull request #795](https://github.com/ignitionrobotics/ign-gazebo/pull/795) + * [Pull request #795](https://github.com/gazebosim/gz-sim/pull/795) 1. Fix macOS build: components::Name in benchmark - * [Pull request #784](https://github.com/ignitionrobotics/ign-gazebo/pull/784) + * [Pull request #784](https://github.com/gazebosim/gz-sim/pull/784) 1. Don't store duplicate ComponentTypeId in ECM - * [Pull request #751](https://github.com/ignitionrobotics/ign-gazebo/pull/751) + * [Pull request #751](https://github.com/gazebosim/gz-sim/pull/751) 1. [TPE] Support setting individual link velocity - * [Pull request #427](https://github.com/ignitionrobotics/ign-gazebo/pull/427) + * [Pull request #427](https://github.com/gazebosim/gz-sim/pull/427) 1. 👩‍🌾 Enable Focal CI - * [Pull request #646](https://github.com/ignitionrobotics/ign-gazebo/pull/646) + * [Pull request #646](https://github.com/gazebosim/gz-sim/pull/646) 1. Update benchmark comparison instructions - * [Pull request #766](https://github.com/ignitionrobotics/ign-gazebo/pull/766) + * [Pull request #766](https://github.com/gazebosim/gz-sim/pull/766) 1. Use Protobuf_IMPORT_DIRS instead of PROTOBUF_IMPORT_DIRS for compatibility with Protobuf CMake config - * [Pull request #715](https://github.com/ignitionrobotics/ign-gazebo/pull/715) + * [Pull request #715](https://github.com/gazebosim/gz-sim/pull/715) 1. Do not pass -Wno-unused-parameter to MSVC compiler - * [Pull request #716](https://github.com/ignitionrobotics/ign-gazebo/pull/716) + * [Pull request #716](https://github.com/gazebosim/gz-sim/pull/716) 1. Scenebroadcaster sensors - * [Pull request #698](https://github.com/ignitionrobotics/ign-gazebo/pull/698) + * [Pull request #698](https://github.com/gazebosim/gz-sim/pull/698) 1. Make it so joint state publisher is quieter - * [Pull request #696](https://github.com/ignitionrobotics/ign-gazebo/pull/696) + * [Pull request #696](https://github.com/gazebosim/gz-sim/pull/696) -### Ignition Gazebo 3.8.0 (2021-03-17) +### Gazebo Sim 3.8.0 (2021-03-17) 1. Add joint position controller GUI, also enable tests for GUI plugins - * [Pull request #534](https://github.com/ignitionrobotics/ign-gazebo/pull/534) + * [Pull request #534](https://github.com/gazebosim/gz-sim/pull/534) 1. Remove visibility from headers that are not installed - * [Pull request #665](https://github.com/ignitionrobotics/ign-gazebo/pull/665) + * [Pull request #665](https://github.com/gazebosim/gz-sim/pull/665) 1. Added screenshot to toolbar - * [Pull request #588](https://github.com/ignitionrobotics/ign-gazebo/pull/588) + * [Pull request #588](https://github.com/gazebosim/gz-sim/pull/588) 1. Improve ign tool support on macOS - * [Pull request #477](https://github.com/ignitionrobotics/ign-gazebo/pull/477) + * [Pull request #477](https://github.com/gazebosim/gz-sim/pull/477) 1. change nullptr to a int ptr for qt 5.15.2 bug - * [Pull request #527](https://github.com/ignitionrobotics/ign-gazebo/pull/527) + * [Pull request #527](https://github.com/gazebosim/gz-sim/pull/527) 1. Kinetic energy monitor plugin - * [Pull request #492](https://github.com/ignitionrobotics/ign-gazebo/pull/492) + * [Pull request #492](https://github.com/gazebosim/gz-sim/pull/492) 1. Use a std::promise/std::future to avoid busy waiting the step ack messages in NetworkManagerPrimary - * [Pull request #470](https://github.com/ignitionrobotics/ign-gazebo/pull/470) + * [Pull request #470](https://github.com/gazebosim/gz-sim/pull/470) 1. clarified performer example - * [Pull request #390](https://github.com/ignitionrobotics/ign-gazebo/pull/390) + * [Pull request #390](https://github.com/gazebosim/gz-sim/pull/390) 1. Add tutorial tweaks - * [Pull request #380](https://github.com/ignitionrobotics/ign-gazebo/pull/380) + * [Pull request #380](https://github.com/gazebosim/gz-sim/pull/380) 1. Fix Qt5 warnings for using anchors - * [Pull request #363](https://github.com/ignitionrobotics/ign-gazebo/pull/363) + * [Pull request #363](https://github.com/gazebosim/gz-sim/pull/363) 1. Update codeowners - * [Pull request #305](https://github.com/ignitionrobotics/ign-gazebo/pull/305) + * [Pull request #305](https://github.com/gazebosim/gz-sim/pull/305) 1. Qt auto scale factor for HiDPI displays - * [Pull request #291](https://github.com/ignitionrobotics/ign-gazebo/pull/291) + * [Pull request #291](https://github.com/gazebosim/gz-sim/pull/291) 1. Fix yaw units - * [Pull request #238](https://github.com/ignitionrobotics/ign-gazebo/pull/238) + * [Pull request #238](https://github.com/gazebosim/gz-sim/pull/238) 1. Fixed docblock showGrid - * [Pull request #152](https://github.com/ignitionrobotics/ign-gazebo/pull/152) + * [Pull request #152](https://github.com/gazebosim/gz-sim/pull/152) 1. Fix entity tree for large worlds - * [Pull request #673](https://github.com/ignitionrobotics/ign-gazebo/pull/673) + * [Pull request #673](https://github.com/gazebosim/gz-sim/pull/673) 1. Master branch updates - * [Pull request #672](https://github.com/ignitionrobotics/ign-gazebo/pull/672) + * [Pull request #672](https://github.com/gazebosim/gz-sim/pull/672) 1. Backport #561: Use common::setenv - * [Pull request #666](https://github.com/ignitionrobotics/ign-gazebo/pull/666) + * [Pull request #666](https://github.com/gazebosim/gz-sim/pull/666) 1. Use a custom data structure to manage entity feature maps - * [Pull request #586](https://github.com/ignitionrobotics/ign-gazebo/pull/586) + * [Pull request #586](https://github.com/gazebosim/gz-sim/pull/586) 1. Limit scene broadcast publications when paused - * [Pull request #497](https://github.com/ignitionrobotics/ign-gazebo/pull/497) + * [Pull request #497](https://github.com/gazebosim/gz-sim/pull/497) 1. Fix flaky SceneBoradcaster test - * [Pull request #641](https://github.com/ignitionrobotics/ign-gazebo/pull/641) + * [Pull request #641](https://github.com/gazebosim/gz-sim/pull/641) 1. Add TF/Pose_V publisher in DiffDrive - * [Pull request #548](https://github.com/ignitionrobotics/ign-gazebo/pull/548) + * [Pull request #548](https://github.com/gazebosim/gz-sim/pull/548) 1. 👩‍🌾 Relax performance test - * [Pull request #640](https://github.com/ignitionrobotics/ign-gazebo/pull/640) + * [Pull request #640](https://github.com/gazebosim/gz-sim/pull/640) 1. 👩‍🌾 Improve velocity control test - * [Pull request #642](https://github.com/ignitionrobotics/ign-gazebo/pull/642) + * [Pull request #642](https://github.com/gazebosim/gz-sim/pull/642) 1. Add `laser_retro` support - * [Pull request #603](https://github.com/ignitionrobotics/ign-gazebo/pull/603) + * [Pull request #603](https://github.com/gazebosim/gz-sim/pull/603) 1. Fix pose of plane visual with non-default normal vector - * [Pull request #574](https://github.com/ignitionrobotics/ign-gazebo/pull/574) + * [Pull request #574](https://github.com/gazebosim/gz-sim/pull/574) 1. Add About dialog - * [Pull request #609](https://github.com/ignitionrobotics/ign-gazebo/pull/609) + * [Pull request #609](https://github.com/gazebosim/gz-sim/pull/609) 1. Make topics configurable for joint controllers - * [Pull request #584](https://github.com/ignitionrobotics/ign-gazebo/pull/584) + * [Pull request #584](https://github.com/gazebosim/gz-sim/pull/584) -1. Also use Ignition GUI render event - * [Pull request #598](https://github.com/ignitionrobotics/ign-gazebo/pull/598) +1. Also use Gazebo GUI render event + * [Pull request #598](https://github.com/gazebosim/gz-sim/pull/598) 1. Tutorial on migrating SDF files from Gazebo classic - * [Pull request #400](https://github.com/ignitionrobotics/ign-gazebo/pull/400) + * [Pull request #400](https://github.com/gazebosim/gz-sim/pull/400) 1. Visualize collisions - * [Pull request #531](https://github.com/ignitionrobotics/ign-gazebo/pull/531) + * [Pull request #531](https://github.com/gazebosim/gz-sim/pull/531) 1. Backport state update changes from pull request #486 - * [Pull request #583](https://github.com/ignitionrobotics/ign-gazebo/pull/583) + * [Pull request #583](https://github.com/gazebosim/gz-sim/pull/583) 1. Publish all periodic change components in Scene Broadcaster - * [Pull request #544](https://github.com/ignitionrobotics/ign-gazebo/pull/544) + * [Pull request #544](https://github.com/gazebosim/gz-sim/pull/544) 1. added size to `ground_plane` in examples - * [Pull request #573](https://github.com/ignitionrobotics/ign-gazebo/pull/573) + * [Pull request #573](https://github.com/gazebosim/gz-sim/pull/573) 1. Parallelize State call in ECM - * [Pull request #451](https://github.com/ignitionrobotics/ign-gazebo/pull/451) + * [Pull request #451](https://github.com/gazebosim/gz-sim/pull/451) 1. Non-blocking paths request - * [Pull request #555](https://github.com/ignitionrobotics/ign-gazebo/pull/555) + * [Pull request #555](https://github.com/gazebosim/gz-sim/pull/555) -### Ignition Gazebo 3.7.0 (2021-01-13) +### Gazebo Sim 3.7.0 (2021-01-13) 1. Fix examples in migration plugins tutorial. - * [Pull Request 543](https://github.com/ignitionrobotics/ign-gazebo/pull/543) + * [Pull Request 543](https://github.com/gazebosim/gz-sim/pull/543) 1. Added missing namespace in `detail/EntityComponentManager.hh`. - * [Pull Request 541](https://github.com/ignitionrobotics/ign-gazebo/pull/541) + * [Pull Request 541](https://github.com/gazebosim/gz-sim/pull/541) 1. Automatically load a subset of world plugins. - * [Pull Request 281](https://github.com/ignitionrobotics/ign-gazebo/pull/281) + * [Pull Request 281](https://github.com/gazebosim/gz-sim/pull/281) 1. Update gtest to 1.10.0 for Windows compilation. - * [Pull Request 506](https://github.com/ignitionrobotics/ign-gazebo/pull/506) + * [Pull Request 506](https://github.com/gazebosim/gz-sim/pull/506) 1. Updates to ardupilot migration tutorial. - * [Pull Request 525](https://github.com/ignitionrobotics/ign-gazebo/pull/525) + * [Pull Request 525](https://github.com/gazebosim/gz-sim/pull/525) 1. Don't make docs on macOS. - * [Pull Request 528](https://github.com/ignitionrobotics/ign-gazebo/pull/528) + * [Pull Request 528](https://github.com/gazebosim/gz-sim/pull/528) -### Ignition Gazebo 3.6.0 (2020-12-30) +### Gazebo Sim 3.6.0 (2020-12-30) 1. Fix pose msg conversion when msg is missing orientation - * [Pull Request 450](https://github.com/ignitionrobotics/ign-gazebo/pull/450) + * [Pull Request 450](https://github.com/gazebosim/gz-sim/pull/450) 1. Address code checker warnings - * [Pull Request 443](https://github.com/ignitionrobotics/ign-gazebo/pull/443) - * [Pull Request 491](https://github.com/ignitionrobotics/ign-gazebo/pull/491) - * [Pull Request 499](https://github.com/ignitionrobotics/ign-gazebo/pull/499) - * [Pull Request 502](https://github.com/ignitionrobotics/ign-gazebo/pull/502) + * [Pull Request 443](https://github.com/gazebosim/gz-sim/pull/443) + * [Pull Request 491](https://github.com/gazebosim/gz-sim/pull/491) + * [Pull Request 499](https://github.com/gazebosim/gz-sim/pull/499) + * [Pull Request 502](https://github.com/gazebosim/gz-sim/pull/502) 1. Test fixes - * [Pull Request 455](https://github.com/ignitionrobotics/ign-gazebo/pull/455) - * [Pull Request 463](https://github.com/ignitionrobotics/ign-gazebo/pull/463) - * [Pull Request 452](https://github.com/ignitionrobotics/ign-gazebo/pull/452) - * [Pull Request 480](https://github.com/ignitionrobotics/ign-gazebo/pull/480) + * [Pull Request 455](https://github.com/gazebosim/gz-sim/pull/455) + * [Pull Request 463](https://github.com/gazebosim/gz-sim/pull/463) + * [Pull Request 452](https://github.com/gazebosim/gz-sim/pull/452) + * [Pull Request 480](https://github.com/gazebosim/gz-sim/pull/480) 1. Documentation updates - * [Pull Request 472](https://github.com/ignitionrobotics/ign-gazebo/pull/472) + * [Pull Request 472](https://github.com/gazebosim/gz-sim/pull/472) 1. Fix segfault in the Breadcrumb system when associated model is unloaded - * [Pull Request 454](https://github.com/ignitionrobotics/ign-gazebo/pull/454) + * [Pull Request 454](https://github.com/gazebosim/gz-sim/pull/454) 1. Added user commands to example thermal camera world - * [Pull Request 442](https://github.com/ignitionrobotics/ign-gazebo/pull/442) + * [Pull Request 442](https://github.com/gazebosim/gz-sim/pull/442) 1. Helper function to set component data - * [Pull Request 436](https://github.com/ignitionrobotics/ign-gazebo/pull/436) + * [Pull Request 436](https://github.com/gazebosim/gz-sim/pull/436) 1. Remove unneeded if statement in EntityComponentManager - * [Pull Request 432](https://github.com/ignitionrobotics/ign-gazebo/pull/432) + * [Pull Request 432](https://github.com/gazebosim/gz-sim/pull/432) 1. Clarify how time is represented in each phase of a System step - * [Pull Request 467](https://github.com/ignitionrobotics/ign-gazebo/pull/467) + * [Pull Request 467](https://github.com/gazebosim/gz-sim/pull/467) 1. Switch to async state service request - * [Pull Request 461](https://github.com/ignitionrobotics/ign-gazebo/pull/461) + * [Pull Request 461](https://github.com/gazebosim/gz-sim/pull/461) 1. Update key event handling - * [Pull Request 466](https://github.com/ignitionrobotics/ign-gazebo/pull/466) + * [Pull Request 466](https://github.com/gazebosim/gz-sim/pull/466) 1. Tape Measure Plugin - * [Pull Request 456](https://github.com/ignitionrobotics/ign-gazebo/pull/456) + * [Pull Request 456](https://github.com/gazebosim/gz-sim/pull/456) 1. Move deselect and preview termination to render thread - * [Pull Request 493](https://github.com/ignitionrobotics/ign-gazebo/pull/493) + * [Pull Request 493](https://github.com/gazebosim/gz-sim/pull/493) 1. Logical audio sensor plugin - * [Pull Request 401](https://github.com/ignitionrobotics/ign-gazebo/pull/401) + * [Pull Request 401](https://github.com/gazebosim/gz-sim/pull/401) 1. add frame_id and child_frame_id attribute support for DiffDrive - * [Pull Request 361](https://github.com/ignitionrobotics/ign-gazebo/pull/361) + * [Pull Request 361](https://github.com/gazebosim/gz-sim/pull/361) 1. Add ability to record video based on sim time - * [Pull Request 414](https://github.com/ignitionrobotics/ign-gazebo/pull/414) + * [Pull Request 414](https://github.com/gazebosim/gz-sim/pull/414) 1. Add lockstep mode to video recording - * [Pull Request 419](https://github.com/ignitionrobotics/ign-gazebo/pull/419) + * [Pull Request 419](https://github.com/gazebosim/gz-sim/pull/419) 1. Disable right click menu when using measuring tool - * [Pull Request 458](https://github.com/ignitionrobotics/ign-gazebo/pull/458) + * [Pull Request 458](https://github.com/gazebosim/gz-sim/pull/458) -### Ignition Gazebo 3.5.0 (2020-11-03) +### Gazebo Sim 3.5.0 (2020-11-03) 1. Updated source build instructions - * [Pull Request 403](https://github.com/ignitionrobotics/ign-gazebo/pull/403) + * [Pull Request 403](https://github.com/gazebosim/gz-sim/pull/403) 1. More world APIs, helper function ComponentData - * [Pull Request 378](https://github.com/ignitionrobotics/ign-gazebo/pull/378) + * [Pull Request 378](https://github.com/gazebosim/gz-sim/pull/378) 1. Improve fork experience - * [Pull Request 411](https://github.com/ignitionrobotics/ign-gazebo/pull/411) + * [Pull Request 411](https://github.com/gazebosim/gz-sim/pull/411) 1. Fix a crash in the grid config plugin, set grid material - * [Pull Request 412](https://github.com/ignitionrobotics/ign-gazebo/pull/412) + * [Pull Request 412](https://github.com/gazebosim/gz-sim/pull/412) 1. Document deprecation of log playback `` SDF param - * [Pull Request 424](https://github.com/ignitionrobotics/ign-gazebo/pull/424) - * [Pull Request 425](https://github.com/ignitionrobotics/ign-gazebo/pull/425) + * [Pull Request 424](https://github.com/gazebosim/gz-sim/pull/424) + * [Pull Request 425](https://github.com/gazebosim/gz-sim/pull/425) 1. Enable mouse highlighting selection on resource spawner - * [Pull Request 402](https://github.com/ignitionrobotics/ign-gazebo/pull/402) + * [Pull Request 402](https://github.com/gazebosim/gz-sim/pull/402) 1. Add support for custom render engines - * [Pull Request 373](https://github.com/ignitionrobotics/ign-gazebo/pull/373) + * [Pull Request 373](https://github.com/gazebosim/gz-sim/pull/373) 1. Component Vector -> Map ECM Optimization - * [Pull Request 416](https://github.com/ignitionrobotics/ign-gazebo/pull/416) + * [Pull Request 416](https://github.com/gazebosim/gz-sim/pull/416) -### Ignition Gazebo 3.4.0 (2020-10-14) +### Gazebo Sim 3.4.0 (2020-10-14) 1. Fix gui sendEvent memory leaks - * [Pull Request 365](https://github.com/ignitionrobotics/ign-gazebo/pull/365) + * [Pull Request 365](https://github.com/gazebosim/gz-sim/pull/365) 1. Support nested models - * [Pull Request 258](https://github.com/ignitionrobotics/ign-gazebo/pull/258) + * [Pull Request 258](https://github.com/gazebosim/gz-sim/pull/258) 1. Generalize actor count and pose in actor population erb SDF - * [Pull Request 336](https://github.com/ignitionrobotics/ign-gazebo/pull/336) + * [Pull Request 336](https://github.com/gazebosim/gz-sim/pull/336) 1. Add more link APIs, with tutorial - * [Pull Request 375](https://github.com/ignitionrobotics/ign-gazebo/pull/375) + * [Pull Request 375](https://github.com/gazebosim/gz-sim/pull/375) 1. Add screenshots to GUI config tutorial - * [Pull Request 406](https://github.com/ignitionrobotics/ign-gazebo/pull/406) + * [Pull Request 406](https://github.com/gazebosim/gz-sim/pull/406) 1. Fix adding performers to entity tree - * [Pull Request 374](https://github.com/ignitionrobotics/ign-gazebo/pull/374) + * [Pull Request 374](https://github.com/gazebosim/gz-sim/pull/374) 1. Remove sidebar and put world control in bottom left for joint controller examples - * [Pull Request 384](https://github.com/ignitionrobotics/ign-gazebo/pull/384) + * [Pull Request 384](https://github.com/gazebosim/gz-sim/pull/384) 1. Allow executing a blocking single Server run in both paused and unpaused states - * [Pull Request 297](https://github.com/ignitionrobotics/ign-gazebo/pull/297) + * [Pull Request 297](https://github.com/gazebosim/gz-sim/pull/297) 1. Add camera video recorder system - * [Pull Request 316](https://github.com/ignitionrobotics/ign-gazebo/pull/316) + * [Pull Request 316](https://github.com/gazebosim/gz-sim/pull/316) 1. Decrease time step for quadcopter world - * [Pull Request 372](https://github.com/ignitionrobotics/ign-gazebo/pull/372) + * [Pull Request 372](https://github.com/gazebosim/gz-sim/pull/372) 1. Add support for moving the GUI camera to a pose - * [Pull Request 352](https://github.com/ignitionrobotics/ign-gazebo/pull/352) + * [Pull Request 352](https://github.com/gazebosim/gz-sim/pull/352) 1. Remove `lib`+`.so` from plugin's name - * [Pull Request 279](https://github.com/ignitionrobotics/ign-gazebo/pull/279) - * [Pull Request 335](https://github.com/ignitionrobotics/ign-gazebo/pull/335) + * [Pull Request 279](https://github.com/gazebosim/gz-sim/pull/279) + * [Pull Request 335](https://github.com/gazebosim/gz-sim/pull/335) 1. EntityComponentManager::EachRemoved documentation fix. - * [Pull Request 348](https://github.com/ignitionrobotics/ign-gazebo/pull/348) + * [Pull Request 348](https://github.com/gazebosim/gz-sim/pull/348) 1. Add more model APIs. - * [Pull Request 349](https://github.com/ignitionrobotics/ign-gazebo/pull/349) + * [Pull Request 349](https://github.com/gazebosim/gz-sim/pull/349) 1. Update dimensions of the grid config. - * [Pull Request 383](https://github.com/ignitionrobotics/ign-gazebo/pull/383) + * [Pull Request 383](https://github.com/gazebosim/gz-sim/pull/383) 1. Fix top-left toolbar layout so magnet shows. - * [Pull Request 381](https://github.com/ignitionrobotics/ign-gazebo/pull/381) + * [Pull Request 381](https://github.com/gazebosim/gz-sim/pull/381) 1. Add instructions to bitmask world. - * [Pull Request 377](https://github.com/ignitionrobotics/ign-gazebo/pull/377) + * [Pull Request 377](https://github.com/gazebosim/gz-sim/pull/377) 1. Add search and sort for resource spawner. - * [Pull Request 359](https://github.com/ignitionrobotics/ign-gazebo/pull/359) + * [Pull Request 359](https://github.com/gazebosim/gz-sim/pull/359) 1. Fix source build instructions for ign-gazebo3. - * [Pull Request 395](https://github.com/ignitionrobotics/ign-gazebo/pull/395) + * [Pull Request 395](https://github.com/gazebosim/gz-sim/pull/395) 1. Added playback scrubber GUI - * [Pull Request 299](https://github.com/ignitionrobotics/ign-gazebo/pull/299) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 299](https://github.com/gazebosim/gz-sim/pull/299) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Added wheel slip system plugin. - * [Pull Request 134](https://github.com/ignitionrobotics/ign-gazebo/pull/134) - * [Pull Request 357](https://github.com/ignitionrobotics/ign-gazebo/pull/357) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 134](https://github.com/gazebosim/gz-sim/pull/134) + * [Pull Request 357](https://github.com/gazebosim/gz-sim/pull/357) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Enhanced log playback performance. - * [Pull Request 351](https://github.com/ignitionrobotics/ign-gazebo/pull/351) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 351](https://github.com/gazebosim/gz-sim/pull/351) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Tests & Warnings: Qt 5.14, breadcrumbs, Gui, ign_TEST - * [Pull Request 327](https://github.com/ignitionrobotics/ign-gazebo/pull/327) + * [Pull Request 327](https://github.com/gazebosim/gz-sim/pull/327) 1. Added support for specifying topics to record. - * [Pull Request 315](https://github.com/ignitionrobotics/ign-gazebo/pull/315) + * [Pull Request 315](https://github.com/gazebosim/gz-sim/pull/315) 1. Make sure OpenGL core profile context is used by GzScene3D. - * [Pull Request 339](https://github.com/ignitionrobotics/ign-gazebo/pull/339) + * [Pull Request 339](https://github.com/gazebosim/gz-sim/pull/339) 1. Support relative paths for PBR materials - * [Pull Request 328](https://github.com/ignitionrobotics/ign-gazebo/pull/328) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 328](https://github.com/gazebosim/gz-sim/pull/328) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Add file extension automatically for record plugin. - * [Pull Request 303](https://github.com/ignitionrobotics/ign-gazebo/pull/303) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 303](https://github.com/gazebosim/gz-sim/pull/303) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Support spawning during log playback. - * [Pull Request 346](https://github.com/ignitionrobotics/ign-gazebo/pull/346) + * [Pull Request 346](https://github.com/gazebosim/gz-sim/pull/346) 1. Add Render Engine Cmd Line option - * [Pull Request 331](https://github.com/ignitionrobotics/ign-gazebo/pull/331) + * [Pull Request 331](https://github.com/gazebosim/gz-sim/pull/331) -### Ignition Gazebo 3.3.0 (2020-08-31) +### Gazebo Sim 3.3.0 (2020-08-31) 1. Added marker array service. - * [pull request 302](https://github.com/ignitionrobotics/ign-gazebo/pull/302) + * [pull request 302](https://github.com/gazebosim/gz-sim/pull/302) 1. Introduced a new parameter in the scene3D plugin to launch in fullscreen. - * [pull request 254](https://github.com/ignitionrobotics/ign-gazebo/pull/254) + * [pull request 254](https://github.com/gazebosim/gz-sim/pull/254) 1. Fix issue #285 by adding checks for a marker's parent. - * [pull request 290](https://github.com/ignitionrobotics/ign-gazebo/pull/290) + * [pull request 290](https://github.com/gazebosim/gz-sim/pull/290) 1. Fix non-specified material error. - * [pull request 292](https://github.com/ignitionrobotics/ign-gazebo/pull/292) + * [pull request 292](https://github.com/gazebosim/gz-sim/pull/292) 1. Added simulation world with large number of entities. - * [pull request 283](https://github.com/ignitionrobotics/ign-gazebo/pull/283) + * [pull request 283](https://github.com/gazebosim/gz-sim/pull/283) 1. Fixed parsing of the touch plugin' enabled flag. - * [pull request 275](https://github.com/ignitionrobotics/ign-gazebo/pull/275) + * [pull request 275](https://github.com/gazebosim/gz-sim/pull/275) 1. Added buoyancy system plugin. - * [pull request 252](https://github.com/ignitionrobotics/ign-gazebo/pull/252) + * [pull request 252](https://github.com/gazebosim/gz-sim/pull/252) 1. Implemented shift + drag = rotate in the GUI. - * [pull request 247](https://github.com/ignitionrobotics/ign-gazebo/pull/247) + * [pull request 247](https://github.com/gazebosim/gz-sim/pull/247) 1. Backport collision bitmask changes - * [pull request 223](https://github.com/ignitionrobotics/ign-gazebo/pull/223) + * [pull request 223](https://github.com/gazebosim/gz-sim/pull/223) 1. Added velocity command to TPE. - * [pull request 169](https://github.com/ignitionrobotics/ign-gazebo/pull/169) + * [pull request 169](https://github.com/gazebosim/gz-sim/pull/169) -1. This version includes all features in Gazebo 2.23.0 +1. This version includes all features in Gazebo Sim 2.23.0 -### Ignition Gazebo 3.2.0 (2020-05-20) +### Gazebo Sim 3.2.0 (2020-05-20) 1. Merge ign-gazebo2 to ign-gazebo3 - * [pull request 149](https://github.com/ignitionrobotics/ign-gazebo/pull/149) + * [pull request 149](https://github.com/gazebosim/gz-sim/pull/149) -### Ignition Gazebo 3.1.0 (2020-05-19) +### Gazebo Sim 3.1.0 (2020-05-19) 1. Port support for computing model bounding box in physics system - * [pull request 127](https://github.com/ignitionrobotics/ign-gazebo/pull/127) + * [pull request 127](https://github.com/gazebosim/gz-sim/pull/127) 1. Add DetachableJoint: A system that initially attaches two models via a fixed joint and allows for the models to get detached during simulation via a topic. * [BitBucket pull request 440](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/440) @@ -2538,9 +2538,9 @@ * [BitBucket pull request 514](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/514) 1. Add window focus upon mouse entering the render window - * [Github pull request 96](https://github.com/ignitionrobotics/ign-gazebo/pull/96) + * [Github pull request 96](https://github.com/gazebosim/gz-sim/pull/96) -### Ignition Gazebo 3.0.0 (2019-12-10) +### Gazebo Sim 3.0.0 (2019-12-10) 1. Add example world for collide bitmask feature * [BitBucket pull request 525](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/525) @@ -2574,161 +2574,161 @@ * [BitBucket pull request 414](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/414) -## Ignition Gazebo 2.x +## Gazebo Sim 2.x -### Ignition Gazebo 2.25.0 (2020-09-17) +### Gazebo Sim 2.25.0 (2020-09-17) 1. Added wheel slip system plugin. - * [Pull Request 134](https://github.com/ignitionrobotics/ign-gazebo/pull/134) - * [Pull Request 357](https://github.com/ignitionrobotics/ign-gazebo/pull/357) + * [Pull Request 134](https://github.com/gazebosim/gz-sim/pull/134) + * [Pull Request 357](https://github.com/gazebosim/gz-sim/pull/357) 1. Enhanced log playback performance. - * [Pull Request 351](https://github.com/ignitionrobotics/ign-gazebo/pull/351) + * [Pull Request 351](https://github.com/gazebosim/gz-sim/pull/351) 1. Tests & Warnings: Qt 5.14, breadcrumbs, Gui, ign_TEST - * [Pull Request 327](https://github.com/ignitionrobotics/ign-gazebo/pull/327) + * [Pull Request 327](https://github.com/gazebosim/gz-sim/pull/327) 1. Added support for specifying topics to record. - * [Pull Request 315](https://github.com/ignitionrobotics/ign-gazebo/pull/315) + * [Pull Request 315](https://github.com/gazebosim/gz-sim/pull/315) 1. Make sure OpenGL core profile context is used by GzScene3D. - * [Pull Request 339](https://github.com/ignitionrobotics/ign-gazebo/pull/339) + * [Pull Request 339](https://github.com/gazebosim/gz-sim/pull/339) 1. Support relative paths for PBR materials - * [Pull Request 328](https://github.com/ignitionrobotics/ign-gazebo/pull/328) + * [Pull Request 328](https://github.com/gazebosim/gz-sim/pull/328) 1. Add file extension automatically for record plugin. - * [Pull Request 303](https://github.com/ignitionrobotics/ign-gazebo/pull/303) + * [Pull Request 303](https://github.com/gazebosim/gz-sim/pull/303) 1. Support spawning during log playback. - * [Pull Request 346](https://github.com/ignitionrobotics/ign-gazebo/pull/346) + * [Pull Request 346](https://github.com/gazebosim/gz-sim/pull/346) -### Ignition Gazebo 2.24.0 (2020-09-03) +### Gazebo Sim 2.24.0 (2020-09-03) 1. Resource env var, with transport interface. - * [Pull Request 172](https://github.com/ignitionrobotics/ign-gazebo/pull/172) + * [Pull Request 172](https://github.com/gazebosim/gz-sim/pull/172) 1. Save http URIs (fix tests) - * [Pull Request 271](https://github.com/ignitionrobotics/ign-gazebo/pull/271) + * [Pull Request 271](https://github.com/gazebosim/gz-sim/pull/271) 1. Insert Local Models. - * [Pull Request 173](https://github.com/ignitionrobotics/ign-gazebo/pull/173) + * [Pull Request 173](https://github.com/gazebosim/gz-sim/pull/173) 1. Modernize actions CI. - * [Pull Request 269](https://github.com/ignitionrobotics/ign-gazebo/pull/269) + * [Pull Request 269](https://github.com/gazebosim/gz-sim/pull/269) 1. Sensor topics available through components and GUI. - * [Pull Request 266](https://github.com/ignitionrobotics/ign-gazebo/pull/266) + * [Pull Request 266](https://github.com/gazebosim/gz-sim/pull/266) 1. Customizable layouts - fully functional. - * [Pull Request 278](https://github.com/ignitionrobotics/ign-gazebo/pull/278) + * [Pull Request 278](https://github.com/gazebosim/gz-sim/pull/278) 1. Add Fuel World Support. - * [Pull Request 274](https://github.com/ignitionrobotics/ign-gazebo/pull/274) + * [Pull Request 274](https://github.com/gazebosim/gz-sim/pull/274) 1. Insert Fuel Models. - * [Pull Request 263](https://github.com/ignitionrobotics/ign-gazebo/pull/263) + * [Pull Request 263](https://github.com/gazebosim/gz-sim/pull/263) 1. Disable rendering tests on macOS that are known to fail. - * [Pull Request 209](https://github.com/ignitionrobotics/ign-gazebo/pull/209) + * [Pull Request 209](https://github.com/gazebosim/gz-sim/pull/209) 1. Fix tests on Blueprint. - * [Pull Request 295](https://github.com/ignitionrobotics/ign-gazebo/pull/295) + * [Pull Request 295](https://github.com/gazebosim/gz-sim/pull/295) 1. Publish remaining breadcrumb deployments. - * [Pull Request 308](https://github.com/ignitionrobotics/ign-gazebo/pull/308) + * [Pull Request 308](https://github.com/gazebosim/gz-sim/pull/308) -### Ignition Gazebo 2.23.0 (2020-07-28) +### Gazebo Sim 2.23.0 (2020-07-28) 1. Deactivate PerformerDetector if its parent model gets removed. - * [Pull Request 260](https://github.com/ignitionrobotics/ign-gazebo/pull/260) + * [Pull Request 260](https://github.com/gazebosim/gz-sim/pull/260) 1. Backport support for s from Fuel #255 - * [Pull Request 255](https://github.com/ignitionrobotics/ign-gazebo/pull/255) + * [Pull Request 255](https://github.com/gazebosim/gz-sim/pull/255) -### Ignition Gazebo 2.22.0 (2020-07-22) +### Gazebo Sim 2.22.0 (2020-07-22) 1. Allow zero or more key/value pairs to be added to detection header information. - * [Pull Request 257](https://github.com/ignitionrobotics/ign-gazebo/pull/257) + * [Pull Request 257](https://github.com/gazebosim/gz-sim/pull/257) -### Ignition Gazebo 2.21.0 (2020-07-16) +### Gazebo Sim 2.21.0 (2020-07-16) 1. Added support for controlling which joints are published by the JointStatePublisher. - * [Pull Request 222](https://github.com/ignitionrobotics/ign-gazebo/pull/222) + * [Pull Request 222](https://github.com/gazebosim/gz-sim/pull/222) 1. Added an additional pose offset for the performer detector plugin. - * [Pull Request 236](https://github.com/ignitionrobotics/ign-gazebo/pull/236) + * [Pull Request 236](https://github.com/gazebosim/gz-sim/pull/236) 1. Fixed battery issues and updated tutorial. - * [Pull Request 230](https://github.com/ignitionrobotics/ign-gazebo/pull/230) + * [Pull Request 230](https://github.com/gazebosim/gz-sim/pull/230) -### Ignition Gazebo 2.20.1 (2020-06-18) +### Gazebo Sim 2.20.1 (2020-06-18) 1. Properly add new models into the scenegraph. With this fix, when a model is spawned it will be added into the graph and resulting calls to the `scene/info` service will return a correct `msgs::Scene`. - * [Pull Request 212](https://github.com/ignitionrobotics/ign-gazebo/pull/212) + * [Pull Request 212](https://github.com/gazebosim/gz-sim/pull/212) -### Ignition Gazebo 2.20.0 (2020-06-09) +### Gazebo Sim 2.20.0 (2020-06-09) 1. Updated battery model to stop battery drain when there is no joint velocity/force command, and added a recharging trigger. - * [Pull Request 183](https://github.com/ignitionrobotics/ign-gazebo/pull/183) + * [Pull Request 183](https://github.com/gazebosim/gz-sim/pull/183) 1. Fix segfault in the Breadcrumbs system - * [Pull Request 180](https://github.com/ignitionrobotics/ign-gazebo/pull/180) + * [Pull Request 180](https://github.com/gazebosim/gz-sim/pull/180) 1. Added an `` element to the DiffDrive system so that a custom odometry topic can be used. - * [Pull Request 179](https://github.com/ignitionrobotics/ign-gazebo/pull/179) + * [Pull Request 179](https://github.com/gazebosim/gz-sim/pull/179) -### Ignition Gazebo 2.19.0 (2020-06-02) +### Gazebo Sim 2.19.0 (2020-06-02) 1. Use updated model names for spawned models when generating SDFormat - * [Pull Request 166](https://github.com/ignitionrobotics/ign-gazebo/pull/166) + * [Pull Request 166](https://github.com/gazebosim/gz-sim/pull/166) 1. Allow joint force commands (JointForceCmd) to dscharge a battery. - * [Pull Request 165](https://github.com/ignitionrobotics/ign-gazebo/pull/165) + * [Pull Request 165](https://github.com/gazebosim/gz-sim/pull/165) 1. Allow renaming breadcrumb models if there is a name conflict - * [Pull Request 155](https://github.com/ignitionrobotics/ign-gazebo/pull/155) + * [Pull Request 155](https://github.com/gazebosim/gz-sim/pull/155) 1. Add TriggeredPublisher system - * [Pull Request 139](https://github.com/ignitionrobotics/ign-gazebo/pull/139) + * [Pull Request 139](https://github.com/gazebosim/gz-sim/pull/139) 1. Add PerformerDetector, a system for detecting when performers enter a specified region - * [Pull Request 125](https://github.com/ignitionrobotics/ign-gazebo/pull/125) + * [Pull Request 125](https://github.com/gazebosim/gz-sim/pull/125) -### Ignition Gazebo 2.18.0 (2020-05-20) +### Gazebo Sim 2.18.0 (2020-05-20) -1. Added a `/world//create_multiple` service that parallels the current `/world//create` service. The `create_multiple` service can handle an `ignition::msgs::EntityFactory_V` message that may contain one or more entities to spawn. - * [Pull Request 146](https://github.com/ignitionrobotics/ign-gazebo/pull/146) +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 - * [Pull Request 132](https://github.com/ignitionrobotics/ign-gazebo/pull/132) + * [Pull Request 132](https://github.com/gazebosim/gz-sim/pull/132) -### Ignition Gazebo 2.17.0 (2020-05-13) +### Gazebo Sim 2.17.0 (2020-05-13) 1. Allow battery plugin to work with joint force systems. - * [Pull Request 120](https://github.com/ignitionrobotics/ign-gazebo/pull/120) + * [Pull Request 120](https://github.com/gazebosim/gz-sim/pull/120) 1. Make breadcrumb static after specified time - * [Pull Request 90](https://github.com/ignitionrobotics/ign-gazebo/pull/90) + * [Pull Request 90](https://github.com/gazebosim/gz-sim/pull/90) 1. Disable breadcrumbs if the `max_deployments` == 0. - * [Pull Request 88](https://github.com/ignitionrobotics/ign-gazebo/pull/88) + * [Pull Request 88](https://github.com/gazebosim/gz-sim/pull/88) 1. Add static pose publisher and support pose\_v msg type in pose publisher system - * [Pull Request 65](https://github.com/ignitionrobotics/ign-gazebo/pull/65) + * [Pull Request 65](https://github.com/gazebosim/gz-sim/pull/65) 1. Refactor Gui.hh so that the Gazebo GUI can be ran from other packages - * [Pull Request 79](https://github.com/ignitionrobotics/ign-gazebo/pull/79) + * [Pull Request 79](https://github.com/gazebosim/gz-sim/pull/79) 1. Add ability to save worlds to SDFormat * [BitBucket pull request 545](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/545) 1. Add window focus upon mouse entering the render window - * [Github pull request 95](https://github.com/ignitionrobotics/ign-gazebo/pull/95) + * [Github pull request 95](https://github.com/gazebosim/gz-sim/pull/95) -### Ignition Gazebo 2.16.0 (2020-03-24) +### Gazebo Sim 2.16.0 (2020-03-24) 1. Add support for computing model bounding box in physics system * [BitBucket pull request 546](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/546) @@ -2790,7 +2790,7 @@ 1. Fix shift translation bug * [BitBucket pull request 529](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/529) -### Ignition Gazebo 2.15.0 (2020-02-07) +### Gazebo Sim 2.15.0 (2020-02-07) 1. Fix seeking back in time in log playback * [BitBucket pull request 523](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/523) @@ -2816,7 +2816,7 @@ 1. Add hotkey keybindings * [BitBucket pull request 486](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/486) -### Ignition Gazebo 2.14.0 (2020-01-10) +### Gazebo Sim 2.14.0 (2020-01-10) 1. Use Actuator component to communicate between MulticopterVelocityControl and MulticopterMotorModel systems * [BitBucket pull request 498](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/498) @@ -2830,7 +2830,7 @@ 1. Fix tooltips on entity tree * [BitBucket pull request 496](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/496) -### Ignition Gazebo 2.13.0 (2019-12-17) +### Gazebo Sim 2.13.0 (2019-12-17) 1. Add Multicopter velocity controller * [BitBucket pull request 487](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/487) @@ -2850,7 +2850,7 @@ 1. Show grid using SDF file * [BitBucket pull request 461](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/461) -### Ignition Gazebo 2.12.0 (2019-11-25) +### Gazebo Sim 2.12.0 (2019-11-25) 1. Parse visual cast shadows and add CastShadows component * [BitBucket pull request 453](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/453) @@ -2876,7 +2876,7 @@ 1. Prevent crash when attempting to load more than one render engine per process * [BitBucket pull request 463](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/463) -### Ignition Gazebo 2.11.0 (2019-10-23) +### Gazebo Sim 2.11.0 (2019-10-23) 1. Handle Relative URIs * [BitBucket pull request 433](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/433) @@ -2900,7 +2900,7 @@ * [BitBucket pull request 430](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/430) * [BitBucket pull request 436](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/436) -### Ignition Gazebo 2.10.0 (2019-09-08) +### Gazebo Sim 2.10.0 (2019-09-08) 1. Custom odom frequency in sim time * [BitBucket pull request 427](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/427) @@ -2908,12 +2908,12 @@ 1. Add Move To gui plugin * [BitBucket pull request 426](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/426) -### Ignition Gazebo 2.9.0 +### Gazebo Sim 2.9.0 1. Use the JointSetVelocityCommand feature to set joint velocities * [BitBucket pull request 424](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/424) -### Ignition Gazebo 2.8.0 (2019-08-23) +### Gazebo Sim 2.8.0 (2019-08-23) 1. Add video recorder gui plugin * [BitBucket pull request 422](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/422) @@ -2924,14 +2924,14 @@ 1. Print world path when using cli * [BitBucket pull request 420](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/420) -### Ignition Gazebo 2.7.1 +### Gazebo Sim 2.7.1 1. Fix order of adding and removing rendering entities, and clean up mesh materials in the SceneManager. * [BitBucket pull request 415](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/415) * [BitBucket pull request 416](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/416) -### Ignition Gazebo 2.7.0 +### Gazebo Sim 2.7.0 1. Move creation of default log path to ServerConfig. This lets both console logs and state logs to be stored in the same directory. The console messages are always logged. Allow state log files to be overwritten. * [BitBucket pull request 413](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/413) @@ -2949,12 +2949,12 @@ See the `test/performance/READEM.md` file for more info. * [BitBucket pull request 389](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/389) -### Ignition Gazebo 2.6.1 (2019-07-26) +### Gazebo Sim 2.6.1 (2019-07-26) 1. Clear stepMsg before populating it * [BitBucket pull request 398](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/398) -### Ignition Gazebo 2.6.0 (2019-07-24) +### Gazebo Sim 2.6.0 (2019-07-24) 1. Improve performance of Pose Publisher * [BitBucket pull request 392](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/392) @@ -2962,17 +2962,17 @@ 1. Fix distributed sim * [BitBucket pull request 385](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/385) -### Ignition Gazebo 2.5.0 (2019-07-19) +### Gazebo Sim 2.5.0 (2019-07-19) 1. The LinearBatteryPlugin system publishes battery state * [BitBucket pull request 388](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/388) -### Ignition Gazebo 2.4.0 (2019-07-17) +### Gazebo Sim 2.4.0 (2019-07-17) 1. Bundle scene updates in sensor system * [BitBucket pull request 386](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/386) -### Ignition Gazebo 2.3.0 (2019-07-13) +### Gazebo Sim 2.3.0 (2019-07-13) 1. Improve physics system peformance by skipping static model updates. Components state information has been incorporated, which is used to @@ -2996,7 +2996,7 @@ * [BitBucket pull request 375](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/375) * [BitBucket pull request 376](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/376) -### Ignition Gazebo 2.2.0 +### Gazebo Sim 2.2.0 1. The DiffDrive system publishes odometry information. * [BitBucket pull request 368](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/368) @@ -3016,7 +3016,7 @@ 1. Support custom random seed from the command line. * [BitBucket pull request 362](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/362) -### Ignition Gazebo 2.1.0 +### Gazebo Sim 2.1.0 1. RenderUtil fix bad merge: check for existing entities in GzScene3D on initialization. * [BitBucket pull request 360](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/360) @@ -3040,7 +3040,7 @@ 1. Support log playback from a different path * [BitBucket pull request 355](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/355) -### Ignition Gazebo 2.0.0 +### Gazebo Sim 2.0.0 1. RenderUtil: check for existing entities in GzScene3D on initialization. * [BitBucket pull request 350](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/350) @@ -3116,7 +3116,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 @@ -3227,9 +3227,9 @@ 1. Depend on ign-sensors rendering component * [BitBucket pull request 212](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/212) -## Ignition Gazebo 1.x +## Gazebo Sim 1.x -### Ignition Gazebo 1.X.X +### Gazebo Sim 1.X.X 1. Add Wind Plugin (Ported from Gazebo classic) * [BitBucket pull request 273](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/273/) @@ -3330,7 +3330,7 @@ 1. Prevent error message when using levels * [BitBucket pull request 229](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/229) -### Ignition Gazebo 1.1.0 (2019-03-15) +### Gazebo Sim 1.1.0 (2019-03-15) 1. Distributed performers running in lockstep * [BitBucket pull request 186](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/186) @@ -3359,23 +3359,23 @@ 1. Unversioned system libraries * [BitBucket pull request 222](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/222) -### Ignition Gazebo 1.0.2 (2019-03-12) +### Gazebo Sim 1.0.2 (2019-03-12) 1. Use TARGET_SO_NAME to fix finding dartsim plugin * [BitBucket pull request 217](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/217) -### Ignition Gazebo 1.0.1 (2019-03-01) +### Gazebo Sim 1.0.1 (2019-03-01) 1. Update gazebo version number in sdf files * [BitBucket pull request 207](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/207) -### Ignition Gazebo 1.0.0 (2019-03-01) +### Gazebo Sim 1.0.0 (2019-03-01) 1. Initial release -## Ignition Gazebo 0.x +## Gazebo Sim 0.x -### Ignition Gazebo 0.1.0 +### Gazebo Sim 0.1.0 1. Add support for joints * [BitBucket pull request 77](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/77) diff --git a/Migration.md b/Migration.md index 6307225661..b559d92e2e 100644 --- a/Migration.md +++ b/Migration.md @@ -5,26 +5,32 @@ Deprecated code produces compile-time warnings. These warning serve as notification to users that their code should be upgraded. The next major release will remove the deprecated code. -## Ignition Gazebo 6.x to 7.0 +## Gazebo Sim 6.x to 7.0 * **Deprecated** + The `ParticleEmitter2` system was renamed to `ParticleEmitter`. The `ParticleEmitter2` system is now deprecated. Please use the - `ParticleEmitter` system. + `ParticleEmitter` system. +* The `ignition::gazebo` namespace is deprecated and will be removed in future versions. + Use `gz::sim` instead. +* Header files under `ignition/...` are deprecated and will be removed in future versions. + Use `gz/...` instead. +* Configuration and log files are stored under `$HOME/.gz/sim` instead of + `$HOME/.ignition/gazebo` -## Ignition Gazebo 6.1 to 6.2 +## Gazebo Sim 6.1 to 6.2 * If no `` is given to the `Thruster` plugin, the namespace now defaults to the model name, instead of an empty string. -## Ignition Gazebo 5.x to 6.x +## Gazebo Sim 5.x to 6.x * The ParticleEmitter system is deprecated. Please use the ParticleEmitter2 system. -* Marker example has been moved to Ignition GUI. +* Marker example has been moved to Gazebo GUI. -* Some GUI plugins have been moved to Ignition GUI. Gazebo users don't need to +* Some GUI plugins have been moved to Gazebo GUI. Gazebo Sim users don't need to change their configuration files, the plugins will be loaded the same way. * Grid Config * Tape Measure @@ -80,20 +86,20 @@ since pose information is being logged in the `changed_state` topic. * The `gui.config` and `server.config` files are now located in a versioned folder inside `$HOME/.ignition/gazebo`, i.e. `$HOME/.ignition/gazebo/6/gui.config`. -* The `Component::Clone` method has been marked `const` to reflect that it +* The `Component::Clone` method has been marked `const` to reflect that it should not mutate internal component state. Component implementations that overrode the `Clone` method must also be marked `const`. -## Ignition Gazebo 5.2 to 5.3 +## Gazebo Sim 5.2 to 5.3 * If no `` is given to the `Thruster` plugin, the namespace now defaults to the model name, instead of an empty string. -## Ignition Gazebo 4.x to 5.x +## Gazebo Sim 4.x to 5.x * Use `cli` component of `ignition-utils1`. -* `ignition::gazebo::RenderUtil::SelectedEntities()` now returns a +* `gz::sim::RenderUtil::SelectedEntities()` now returns a `const std::vector &` instead of forcing a copy. The calling code should create a copy if it needs to modify the vector in some way. @@ -104,30 +110,30 @@ since pose information is being logged in the `changed_state` topic. * `//` -> `///image` * `//camera_info` -> `///camera_info` -* Various `GuiEvent`s were deprecated in favor of their Ignition GUI +* Various `GuiEvent`s were deprecated in favor of their Gazebo GUI equivalents. - * **Deprecated** `ignition::gazebo::gui::SnapIntervals` - * **Replacement** `ignition::gui::SnapIntervals` - * **Deprecated** `ignition::gazebo::gui::Render` - * **Replacement** `ignition::gui::Render` - * **Deprecated** `ignition::gazebo::gui::SpawnPreviewModel` - * **Replacement** `ignition::gui::SpawnFromDescription` - * **Deprecated** `ignition::gazebo::gui::SnapPreviewPath` - * **Replacement** `ignition::gui::SnapFromPath` + * **Deprecated** `gz::sim::gui::SnapIntervals` + * **Replacement** `gz::gui::SnapIntervals` + * **Deprecated** `gz::sim::gui::Render` + * **Replacement** `gz::gui::Render` + * **Deprecated** `gz::sim::gui::SpawnPreviewModel` + * **Replacement** `gz::gui::SpawnFromDescription` + * **Deprecated** `gz::sim::gui::SnapPreviewPath` + * **Replacement** `gz::gui::SnapFromPath` * The `` tag of spot lights was previously not parsed by the scene, so all spot lights shone in the direction corresponding to the default `0 0 -1`. Since 5.x, the `` tag is correctly processed. -## Ignition Gazebo 4.0.0 to 4.X.X +## Gazebo Sim 4.0.0 to 4.X.X -* Ignition Gazebo 4.0.0 enabled double sided material by default but this +* Gazebo Sim 4.0.0 enabled double sided material by default but this caused shadow artifacts to appear on some meshes. Double sided material is now disabled and made an opt-in feature. Users can configure this property in SDF by setting the `` SDF element. -## Ignition Gazebo 3.x to 4.x +## Gazebo Sim 3.x to 4.x * The `RenderUtil::SetEnabledSensors` callback in gazebo rendering has a new required function argument for the Entity of the sensor. @@ -136,7 +142,7 @@ in SDF by setting the `` SDF element. std::string(const sdf::Sensor &, const std::string &)>)` * ***Replacement*** `public: void SetEnableSensors(bool, std::function< - std::string(const gazebo::Entity &, + std::string(const sim::Entity &, const sdf::Sensor &, const std::string &)>)` * Log playback using `` SDF parameter is removed. Use --playback command @@ -146,15 +152,15 @@ in SDF by setting the `` SDF element. * **Deprecated**: `Entity EntityFromNode(const rendering::NodePtr &_node) const;` * **Replacement**: `Entity entity = std::get(visual->UserData("gazebo-entity"));` -## Ignition Gazebo 3.12.0 to 3.X.X +## Gazebo Sim 3.12.0 to 3.X.X * Some sensors will only have the `SensorTopic` component after the 1st iteration. -## Ignition Gazebo 2.x to 3.x +## Gazebo Sim 2.x to 3.x * Use ign-rendering3, ign-sensors3 and ign-gui3. -## Ignition Gazebo 1.x to 2.x +## Gazebo Sim 1.x to 2.x * Changed component data types: * `Altimeter` now uses `sdf::Sensor` @@ -176,15 +182,15 @@ in SDF by setting the `` SDF element. * The `entity_name` field in the messages published by the imu system is updated to report its scoped name. -* Log files generated from Ignition Gazebo 1.X are no longer compatible with -Gazebo 2+ for playback. [BitBucket pull request +* Log files generated from Gazebo Sim 1.X are no longer compatible with +Gazebo Sim 2+ for playback. [BitBucket pull request #257](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/257) added an SDF message to the start of log files. * Log playback using `` SDF parameter is deprecated. Use `--playback` command line argument instead. -## Ignition Gazebo 1.0.2 to 1.1.0 +## Gazebo Sim 1.0.2 to 1.1.0 * All headers in `gazebo/network` are no longer installed. diff --git a/NEWS b/NEWS index 604eba6656..a73d9b7c1a 100644 --- a/NEWS +++ b/NEWS @@ -1 +1 @@ -http://ignitionrobotics.org +http://gazebosim.org diff --git a/README.md b/README.md index ec4f0293bc..9bc1ff623b 100644 --- a/README.md +++ b/README.md @@ -1,22 +1,22 @@ -# Ignition Gazebo : A Robotic Simulator +# Gazebo Sim : A Robotic Simulator **Maintainer:** louise AT openrobotics DOT org -[![GitHub open issues](https://img.shields.io/github/issues-raw/ignitionrobotics/ign-gazebo.svg)](https://github.com/ignitionrobotics/ign-gazebo/issues) -[![GitHub open pull requests](https://img.shields.io/github/issues-pr-raw/ignitionrobotics/ign-gazebo.svg)](https://github.com/ignitionrobotics/ign-gazebo/pulls) +[![GitHub open issues](https://img.shields.io/github/issues-raw/gazebosim/gz-sim.svg)](https://github.com/gazebosim/gz-sim/issues) +[![GitHub open pull requests](https://img.shields.io/github/issues-pr-raw/gazebosim/gz-sim.svg)](https://github.com/gazebosim/gz-sim/pulls) [![Discourse topics](https://img.shields.io/discourse/https/community.gazebosim.org/topics.svg)](https://community.gazebosim.org) [![Hex.pm](https://img.shields.io/hexpm/l/plug.svg)](https://www.apache.org/licenses/LICENSE-2.0) Build | Status -- | -- -Test coverage | [![codecov](https://codecov.io/gh/ignitionrobotics/ign-gazebo/branch/main/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-gazebo) +Test coverage | [![codecov](https://codecov.io/gh/gazebosim/gz-sim/branch/main/graph/badge.svg)](https://codecov.io/gh/gazebosim/gz-sim) Ubuntu Focal | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_gazebo-ci-main-focal-amd64)](https://build.osrfoundation.org/job/ignition_gazebo-ci-main-focal-amd64) Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_gazebo-ci-main-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_gazebo-ci-main-homebrew-amd64) Windows | [![Build Status](https://build.osrfoundation.org/job/ign_gazebo-ci-win/badge/icon)](https://build.osrfoundation.org/job/ign_gazebo-ci-win/) -Ignition Gazebo is an open source robotics simulator. Through Ignition Gazebo, users have access to high fidelity physics, rendering, and sensor models. Additionally, users and developers have multiple points of entry to simulation including a graphical user interface, plugins, and asynchronous message passing and services. +Gazebo Sim is an open source robotics simulator. Through Gazebo, users have access to high fidelity physics, rendering, and sensor models. Additionally, users and developers have multiple points of entry to simulation including a graphical user interface, plugins, and asynchronous message passing and services. -Ignition Gazebo is derived from [Gazebo](http://gazebosim.org) and represents over 16 years of development and experience in robotics and simulation. This library is part of the [Ignition Robotics](https://ignitionrobotics.org) project. +Gazebo Sim is derived from [Gazebo Classic](http://classic.gazebosim.org) and represents over 16 years of development and experience in robotics and simulation. This library is part of the [Gazebo](https://gazebosim.org) project. # Table of Contents @@ -44,45 +44,45 @@ Ignition Gazebo is derived from [Gazebo](http://gazebosim.org) and represents ov * **Dynamics simulation**: Access multiple high-performance physics engines through -[Ignition Physics](https://github.com/ignitionrobotics/ign-physics). +[Gazebo Physics](https://github.com/gazebosim/gz-physics). * **Advanced 3D graphics**: Through -[Ignition Rendering](https://github.com/ignitionrobotics/ign-rendering), +[Gazebo Rendering](https://github.com/gazebosim/gz-rendering), it's possible to use rendering engines such as OGRE v2 for realistic rendering of environments with high-quality lighting, shadows, and textures. * **Sensors and noise models**: Generate sensor data, optionally with noise, from laser range finders, 2D/3D cameras, Kinect style sensors, contact sensors, force-torque, IMU, GPS, and more, all powered by -[Ignition Sensors](https://github.com/ignitionrobotics/ign-sensors) +[Gazebo Sensors](https://github.com/gazebosim/gz-sensors) * **Plugins**: Develop custom plugins for robot, sensor, and environment control. * **Graphical interface**: Create, instrospect and interact with your simulations through plugin-based graphical interfaces powered by -[Ignition GUI](https://github.com/ignitionrobotics/ign-gui). +[Gazebo GUI](https://github.com/gazebosim/gz-gui). * **Simulation models**: Access numerous robots including PR2, Pioneer2 DX, iRobot Create, and TurtleBot, and construct environments using other physically accurate models available through -[Ignition Fuel](https://app.ignitionrobotics.org/fuel). You can also build a +[Gazebo Fuel](https://app.gazebosim.org/fuel). You can also build a new model using [SDF](http://sdformat.org). * **TCP/IP Transport**: Run simulation on remote servers and interface to Ignition -Gazebo through socket-based message passing using -[Ignition Transport](https://github.com/ignitionrobotics/ign-transport). +Gazebo Sim through socket-based message passing using +[Gazebo Transport](https://github.com/gazebosim/gz-transport). * **Command line tools**: Extensive command line tools for increased simulation introspection and control. # Install -See the [installation tutorial](https://ignitionrobotics.org/api/gazebo/6.1/install.html). +See the [installation tutorial](https://gazebosim.org/api/gazebo/6.1/install.html). # Usage -Gazebo can be run from the command line, once [installed](#install), using: +Gazebo Sim can be run from the command line, once [installed](#install), using: ``` ign gazebo @@ -100,10 +100,10 @@ In the event that the installation is a mix of Debian and from source, command line tools from `ign-tools` may not work correctly. A workaround for a single package is to define the environment variable -`IGN_CONFIG_PATH` to point to the location of the Ignition library installation, +`GZ_CONFIG_PATH` to point to the location of the Ignition library installation, where the YAML file for the package is found, such as ``` -export IGN_CONFIG_PATH=/usr/local/share/ignition +export GZ_CONFIG_PATH=/usr/local/share/ignition ``` However, that environment variable only takes a single path, which means if the @@ -112,26 +112,26 @@ installations from source are in different locations, only one can be specified. Another workaround for working with multiple Ignition libraries on the command line is using symbolic links to each library's YAML file. ``` -mkdir ~/.ignition/tools/configs -p -cd ~/.ignition/tools/configs/ +mkdir ~/.gz/tools/configs -p +cd ~/.gz/tools/configs/ ln -s /usr/local/share/ignition/fuel8.yaml . ln -s /usr/local/share/ignition/transport12.yaml . ln -s /usr/local/share/ignition/transportlog12.yaml . ... -export IGN_CONFIG_PATH=$HOME/.ignition/tools/configs +export GZ_CONFIG_PATH=$HOME/.gz/tools/configs ``` -This issue is tracked [here](https://github.com/ignitionrobotics/ign-tools/issues/8). +This issue is tracked [here](https://github.com/gazebosim/gz-tools/issues/8). # Documentation -See the [installation tutorial](https://ignitionrobotics.org/api/gazebo/6.1/install.html). +See the [installation tutorial](https://gazebosim.org/api/gazebo/6.1/install.html). # Testing -See the [installation tutorial](https://ignitionrobotics.org/api/gazebo/6.1/install.html). +See the [installation tutorial](https://gazebosim.org/api/gazebo/6.1/install.html). -See the [Writing Tests section of the contributor guide](https://github.com/ignitionrobotics/ign-gazebo/blob/main/CONTRIBUTING.md#writing-tests) for help creating or modifying tests. +See the [Writing Tests section of the contributor guide](https://github.com/gazebosim/gz-sim/blob/main/CONTRIBUTING.md#writing-tests) for help creating or modifying tests. # Folder Structure @@ -163,17 +163,17 @@ ign-gazebo # Contributing Please see -[CONTRIBUTING.md](https://github.com/ignitionrobotics/ign-gazebo/blob/main/CONTRIBUTING.md). +[CONTRIBUTING.md](https://github.com/gazebosim/gz-sim/blob/main/CONTRIBUTING.md). # Code of Conduct Please see -[CODE_OF_CONDUCT.md](https://github.com/ignitionrobotics/ign-gazebo/blob/main/CODE_OF_CONDUCT.md). +[CODE_OF_CONDUCT.md](https://github.com/gazebosim/gz-sim/blob/main/CODE_OF_CONDUCT.md). # Versioning -This library uses [Semantic Versioning](https://semver.org/). Additionally, this library is part of the [Ignition Robotics project](https://ignitionrobotics.org) which periodically releases a versioned set of compatible and complimentary libraries. See the [Ignition Robotics website](https://ignitionrobotics.org) for version and release information. +This library uses [Semantic Versioning](https://semver.org/). Additionally, this library is part of the [Gazebo project](https://gazebosim.org) which periodically releases a versioned set of compatible and complimentary libraries. See the [Gazebo website](https://gazebosim.org) for version and release information. # License -This library is licensed under [Apache 2.0](https://www.apache.org/licenses/LICENSE-2.0). See also the [LICENSE](https://github.com/ignitionrobotics/ign-gazebo/blob/main/LICENSE) file. +This library is licensed under [Apache 2.0](https://www.apache.org/licenses/LICENSE-2.0). See also the [LICENSE](https://github.com/gazebosim/gz-sim/blob/main/LICENSE) file. diff --git a/api.md.in b/api.md.in index 0fc4704def..6788ec1782 100644 --- a/api.md.in +++ b/api.md.in @@ -1,14 +1,14 @@ ## Ignition @IGN_DESIGNATION_CAP@ -Ignition @IGN_DESIGNATION_CAP@ is a component in Ignition Robotics, a set of libraries +Ignition @IGN_DESIGNATION_CAP@ is a component in Gazebo, a set of libraries 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/doc/architecture_design.md b/doc/architecture_design.md index 902e34f370..33ddd34551 100644 --- a/doc/architecture_design.md +++ b/doc/architecture_design.md @@ -1,4 +1,4 @@ -# Ignition Gazebo design +# Gazebo Sim design > This is an evolving document as design is discussed and iterated on. As features are released, the relevant parts of this document should be updated and moved to a tutorial. @@ -117,7 +117,7 @@ level and performer is only simulated at one runner at a time. It would be convenient to be able to specify standalone programs in the SDF file so they're loaded at the same time as the simulation. For example, -Gazebo's +Gazebo Sim's [JoyPlugin](https://github.com/osrf/gazebo/blob/gazebo11/plugins/JoyPlugin.hh) is a `WorldPlugin`, but it doesn't need to access any world API, or to run in the physics thread, or even to run in the gzserver process. However, @@ -125,6 +125,3 @@ it was implemented as a plugin because that makes it easier to specify in SDF. > **TODO**: Describe what this would look like. - - - diff --git a/docker/README.md b/docker/README.md index dae63aaaf1..629fc74925 100644 --- a/docker/README.md +++ b/docker/README.md @@ -1,17 +1,17 @@ -# Ignition Gazebo Dockerfiles +# Gazebo Sim Dockerfiles This directory contains a few Dockerfiles and supporting scripts. See each section below for usage information about -1. [Dockerfile.ignition](#Ignition-Gazebo-Using-Debians-In-Docker) -1. [Dockerfile.nightly](#Build-Ignition-Gazebo-Using-Nightly-Debians) +1. [Dockerfile.ignition](#Gazebo-Sim-Using-Debians-In-Docker) +1. [Dockerfile.nightly](#Build-Gazebo-Sim-Using-Nightly-Debians) -## Build Ignition Gazebo Using Nightly Debians +## Build Gazebo Sim Using Nightly Debians This section describes how to build and run a docker image based on nightly builds of downstream -[Ignition libraries](https://ignitionrobotics.org/libs). The Docker image will -use the Ignition Gazebo code found in the current source tree. +[Ignition libraries](https://gazebosim.org/libs). The Docker image will +use the Gazebo code found in the current source tree. **Requirements** @@ -24,14 +24,14 @@ use the Ignition Gazebo code found in the current source tree. **Steps** -1. Change the root directory of the Ignition Gazebo source tree. If you are +1. Change the root directory of the Gazebo Sim source tree. If you are currently in the `docker` subdirectory: ``` cd .. ``` -1. Build the ign-gazebo:base image. +1. Build the gz-gazebo:base image. ``` docker build . -f ./docker/Dockerfile.base -t ign-gazebo:base @@ -49,13 +49,13 @@ use the Ignition Gazebo code found in the current source tree. docker run -it ign-gazebo:nightly /bin/bash ``` -4. Alternatively, you can directly run Ignition Gazebo using +4. Alternatively, you can directly run Gazebo using ``` ./docker/run.bash ign-gazebo:nightly ign-gazebo-server -v 4 ``` -## Ignition Gazebo Using Debians In Docker +## Gazebo Using Debians In Docker This section describes how to build and run a docker image of an Ignition distribution using debians. @@ -69,8 +69,8 @@ distribution using debians. **Steps** 1. Build a docker image using the `build.bash` command. The first argument - must be the name of the Ignition distribution. The list of Ignition distribution can be found at [Ignition distribution](https://ignitionrobotics.org/docs). For example, to build an - image of Ignition Fortress: + must be the name of the Ignition distribution. The list of Ignition distribution can be found at [Ignition distribution](https://gazebosim.org/docs). For example, to build an + image of Gazebo Fortress: ``` ./build.bash ignition-garden ./Dockerfile.ignition @@ -83,7 +83,7 @@ distribution using debians. ./run.bash ignition-garden ``` -3. You can pass arguments to Ignition Gazebo by appending them the +3. You can pass arguments to Gazebo by appending them the `run.bash` command. For example, to load the shapes.sdf file: ``` diff --git a/docker/scripts/build_ign.sh b/docker/scripts/build_ign.sh index 2661222fc5..b9ff89f284 100755 --- a/docker/scripts/build_ign.sh +++ b/docker/scripts/build_ign.sh @@ -1,6 +1,6 @@ #!/bin/bash # Command line parameters: -# 1 - github organization name. For example ignitionrobotics or osrf. +# 1 - github organization name. For example gazebosim or osrf. # 2 - the name of the ignition repository. For example ign-math. # 3 - the name of the branch. For example ign-math7 diff --git a/docker/scripts/upload_json_benchmark.sh b/docker/scripts/upload_json_benchmark.sh index ed5e19795f..5a3c99c394 100755 --- a/docker/scripts/upload_json_benchmark.sh +++ b/docker/scripts/upload_json_benchmark.sh @@ -1,6 +1,6 @@ #!/bin/bash # Command line parameters: -# 1 - github organization name. For example ignitionrobotics or osrf. +# 1 - github organization name. For example gazebosim or osrf. # 2 - the name of the ignition repository. For example ign-math. # 3 - the name of the branch. For example ign-math7 @@ -9,4 +9,4 @@ set -o verbose # todo(nkoenig) Update the database to handle templated names. # todo(nkoenig) Use application tokens instead of jwt, which can expire. -curl -k -X POST -d @$1 https://api.ignitionrobotics.org/1.0/benchmarks/gazebo --header 'authorization: Bearer '$AUTH0_JWT_TOKEN +curl -k -X POST -d @$1 https://api.gazebosim.org/1.0/benchmarks/gazebo --header 'authorization: Bearer '$AUTH0_JWT_TOKEN diff --git a/examples/plugin/command_actor/CommandActor.cc b/examples/plugin/command_actor/CommandActor.cc index 20d02527dc..6761e62325 100644 --- a/examples/plugin/command_actor/CommandActor.cc +++ b/examples/plugin/command_actor/CommandActor.cc @@ -21,7 +21,7 @@ IGNITION_ADD_PLUGIN( command_actor::CommandActor, - ignition::gazebo::System, + gz::sim::System, command_actor::CommandActor::ISystemConfigure, command_actor::CommandActor::ISystemPreUpdate) using namespace command_actor; @@ -37,13 +37,13 @@ CommandActor::~CommandActor() } ////////////////////////////////////////////////// -void CommandActor::Configure(const ignition::gazebo::Entity &_entity, +void CommandActor::Configure(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*/) { this->entity = _entity; - ignmsg << "Command actor for entity [" << _entity << "]" << std::endl; + gzmsg << "Command actor for entity [" << _entity << "]" << std::endl; auto sdfClone = _sdf->Clone(); @@ -52,11 +52,11 @@ void CommandActor::Configure(const ignition::gazebo::Entity &_entity, originElem != nullptr; originElem = originElem->GetNextElement("origin")) { - auto pose = originElem->Get("pose"); + auto pose = originElem->Get("pose"); auto time = originElem->Get("time"); this->origins[time] = pose; - ignmsg << "Stored origin change at [" << time << "] seconds to pose [" + gzmsg << "Stored origin change at [" << time << "] seconds to pose [" << pose << "]" << std::endl; } @@ -65,19 +65,19 @@ void CommandActor::Configure(const ignition::gazebo::Entity &_entity, trajPoseElem != nullptr; trajPoseElem = trajPoseElem->GetNextElement("trajectory_pose")) { - auto pose = trajPoseElem->Get("pose"); + auto pose = trajPoseElem->Get("pose"); auto time = trajPoseElem->Get("time"); this->trajPoses[time] = pose; - ignmsg << "Stored trajectory pose change at [" << time + gzmsg << "Stored trajectory pose change at [" << time << "] seconds to pose [" << pose << "]" << std::endl; } } ////////////////////////////////////////////////// -void CommandActor::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void CommandActor::PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { auto sec = std::chrono::duration_cast( _info.simTime).count(); @@ -86,16 +86,16 @@ void CommandActor::PreUpdate(const ignition::gazebo::UpdateInfo &_info, if (sec > this->lastOriginChange && this->origins.find(sec) != this->origins.end()) { - auto poseComp = _ecm.Component( + auto poseComp = _ecm.Component( this->entity); - *poseComp = ignition::gazebo::components::Pose(this->origins[sec]); + *poseComp = gz::sim::components::Pose(this->origins[sec]); // Updates to pose component can usually be missed, so we need to mark this // as an important one-time change. - _ecm.SetChanged(this->entity, ignition::gazebo::components::Pose::typeId, - ignition::gazebo::ComponentState::OneTimeChange); + _ecm.SetChanged(this->entity, gz::sim::components::Pose::typeId, + gz::sim::ComponentState::OneTimeChange); - ignmsg << "Changing origin to [" << this->origins[sec] << "]" << std::endl; + gzmsg << "Changing origin to [" << this->origins[sec] << "]" << std::endl; this->lastOriginChange = sec; } @@ -105,20 +105,20 @@ void CommandActor::PreUpdate(const ignition::gazebo::UpdateInfo &_info, this->trajPoses.find(sec) != this->trajPoses.end()) { auto trajPoseComp = - _ecm.Component( + _ecm.Component( this->entity); if (nullptr == trajPoseComp) { _ecm.CreateComponent(this->entity, - ignition::gazebo::components::TrajectoryPose(this->trajPoses[sec])); + gz::sim::components::TrajectoryPose(this->trajPoses[sec])); } else { *trajPoseComp = - ignition::gazebo::components::TrajectoryPose(this->trajPoses[sec]); + gz::sim::components::TrajectoryPose(this->trajPoses[sec]); } - ignmsg << "Changing trajectory pose to [" << this->trajPoses[sec] << "]" + gzmsg << "Changing trajectory pose to [" << this->trajPoses[sec] << "]" << std::endl; this->lastTrajPoseChange = sec; diff --git a/examples/plugin/command_actor/CommandActor.hh b/examples/plugin/command_actor/CommandActor.hh index 3e989a0840..b01f956695 100644 --- a/examples/plugin/command_actor/CommandActor.hh +++ b/examples/plugin/command_actor/CommandActor.hh @@ -25,9 +25,9 @@ namespace command_actor /// \brief Example showing different ways of commanding an actor. class CommandActor: - 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 Constructor public: CommandActor(); @@ -36,27 +36,27 @@ namespace command_actor public: ~CommandActor() override; /// Documentation inherited - public: void Configure(const ignition::gazebo::Entity &_id, + public: void Configure(const gz::sim::Entity &_id, const std::shared_ptr &_sdf, - ignition::gazebo::EntityComponentManager &_ecm, - ignition::gazebo::EventManager &_eventMgr) final; + gz::sim::EntityComponentManager &_ecm, + gz::sim::EventManager &_eventMgr) final; // 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; /// \brief Actor entity - private: ignition::gazebo::Entity entity; + private: gz::sim::Entity entity; /// \brief Origins to change, where the key is the number of seconds from /// beginning of simulation, and the value is the new trajectory origin to /// set. - private: std::map origins; + private: std::map origins; /// \brief Trajectory poses to change, where the key is the number of /// seconds from beginning of simulation, and the value is the new /// trajectory pose to set. - private: std::map trajPoses; + private: std::map trajPoses; /// \brief Last time, in seconds, when the origin was changed. private: int lastOriginChange{0}; diff --git a/examples/plugin/command_actor/command_actor.sdf b/examples/plugin/command_actor/command_actor.sdf index e091290e95..fb38aac8b0 100644 --- a/examples/plugin/command_actor/command_actor.sdf +++ b/examples/plugin/command_actor/command_actor.sdf @@ -3,11 +3,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/examples/plugin/custom_component/CustomComponentPlugin.cc b/examples/plugin/custom_component/CustomComponentPlugin.cc index 70240785e6..f2fdc39aca 100644 --- a/examples/plugin/custom_component/CustomComponentPlugin.cc +++ b/examples/plugin/custom_component/CustomComponentPlugin.cc @@ -19,6 +19,6 @@ #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 ed2483ba2a..e75703fec2 100644 --- a/examples/plugin/custom_component/CustomComponentPlugin.hh +++ b/examples/plugin/custom_component/CustomComponentPlugin.hh @@ -32,35 +32,35 @@ 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; + gzdbg << "Creating component" << std::endl; _ecm.CreateComponent(_entity, CustomComponent(123)); // 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; - igndbg << "Component's data: " << _comp->Data() << std::endl; + gzdbg << "Entity: " << _entityEach << std::endl; + gzdbg << "Component's data: " << _comp->Data() << std::endl; return true; }); } diff --git a/examples/plugin/custom_sensor_system/CMakeLists.txt b/examples/plugin/custom_sensor_system/CMakeLists.txt index 9e75acbc34..053a1059fc 100644 --- a/examples/plugin/custom_sensor_system/CMakeLists.txt +++ b/examples/plugin/custom_sensor_system/CMakeLists.txt @@ -19,7 +19,7 @@ set(IGN_SENSORS_VER ${ignition-sensors7_VERSION_MAJOR}) include(FetchContent) FetchContent_Declare( sensors_clone - GIT_REPOSITORY https://github.com/ignitionrobotics/ign-sensors + GIT_REPOSITORY https://github.com/gazebosim/gz-sensors GIT_TAG main ) FetchContent_Populate(sensors_clone) diff --git a/examples/plugin/custom_sensor_system/OdometerSystem.cc b/examples/plugin/custom_sensor_system/OdometerSystem.cc index 893666ec30..2fd48d18dd 100644 --- a/examples/plugin/custom_sensor_system/OdometerSystem.cc +++ b/examples/plugin/custom_sensor_system/OdometerSystem.cc @@ -42,18 +42,18 @@ using namespace custom; ////////////////////////////////////////////////// -void OdometerSystem::PreUpdate(const ignition::gazebo::UpdateInfo &, - ignition::gazebo::EntityComponentManager &_ecm) +void OdometerSystem::PreUpdate(const gz::sim::UpdateInfo &, + gz::sim::EntityComponentManager &_ecm) { - _ecm.EachNew( - [&](const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::CustomSensor *_custom, - const ignition::gazebo::components::ParentEntity *_parent)->bool + _ecm.EachNew( + [&](const gz::sim::Entity &_entity, + const gz::sim::components::CustomSensor *_custom, + const gz::sim::components::ParentEntity *_parent)->bool { // Get sensor's scoped name without the world - auto sensorScopedName = ignition::gazebo::removeParentScope( - ignition::gazebo::scopedName(_entity, _ecm, "::", false), "::"); + auto sensorScopedName = gz::sim::removeParentScope( + gz::sim::scopedName(_entity, _ecm, "::", false), "::"); sdf::Sensor data = _custom->Data(); data.SetName(sensorScopedName); @@ -64,23 +64,23 @@ void OdometerSystem::PreUpdate(const ignition::gazebo::UpdateInfo &, data.SetTopic(topic); } - ignition::sensors::SensorFactory sensorFactory; + gz::sensors::SensorFactory sensorFactory; auto sensor = sensorFactory.CreateSensor(data); if (nullptr == sensor) { - ignerr << "Failed to create odometer [" << sensorScopedName << "]" + gzerr << "Failed to create odometer [" << sensorScopedName << "]" << std::endl; return false; } // Set sensor parent - auto parentName = _ecm.Component( + auto parentName = _ecm.Component( _parent->Data())->Data(); sensor->SetParent(parentName); // Set topic on Gazebo _ecm.CreateComponent(_entity, - ignition::gazebo::components::SensorTopic(sensor->Topic())); + gz::sim::components::SensorTopic(sensor->Topic())); // Keep track of this sensor this->entitySensorMap.insert(std::make_pair(_entity, @@ -91,15 +91,15 @@ void OdometerSystem::PreUpdate(const ignition::gazebo::UpdateInfo &, } ////////////////////////////////////////////////// -void OdometerSystem::PostUpdate(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) +void OdometerSystem::PostUpdate(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) { // Only update and publish if not paused. if (!_info.paused) { for (auto &[entity, sensor] : this->entitySensorMap) { - sensor->NewPosition(ignition::gazebo::worldPose(entity, _ecm).Pos()); + sensor->NewPosition(gz::sim::worldPose(entity, _ecm).Pos()); sensor->Update(_info.simTime); } } @@ -109,22 +109,22 @@ void OdometerSystem::PostUpdate(const ignition::gazebo::UpdateInfo &_info, ////////////////////////////////////////////////// void OdometerSystem::RemoveSensorEntities( - const ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::EntityComponentManager &_ecm) { - _ecm.EachRemoved( - [&](const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::CustomSensor *)->bool + _ecm.EachRemoved( + [&](const gz::sim::Entity &_entity, + const gz::sim::components::CustomSensor *)->bool { if (this->entitySensorMap.erase(_entity) == 0) { - ignerr << "Internal error, missing odometer for entity [" + gzerr << "Internal error, missing odometer for entity [" << _entity << "]" << std::endl; } return true; }); } -IGNITION_ADD_PLUGIN(OdometerSystem, ignition::gazebo::System, +IGNITION_ADD_PLUGIN(OdometerSystem, gz::sim::System, OdometerSystem::ISystemPreUpdate, OdometerSystem::ISystemPostUpdate ) diff --git a/examples/plugin/custom_sensor_system/OdometerSystem.hh b/examples/plugin/custom_sensor_system/OdometerSystem.hh index 0e4044433b..58c2901329 100644 --- a/examples/plugin/custom_sensor_system/OdometerSystem.hh +++ b/examples/plugin/custom_sensor_system/OdometerSystem.hh @@ -26,30 +26,30 @@ namespace custom /// \brief Example showing how to tie a custom sensor, in this case an /// odometer, into simulation class OdometerSystem: - public ignition::gazebo::System, - public ignition::gazebo::ISystemPreUpdate, - public ignition::gazebo::ISystemPostUpdate + public gz::sim::System, + public gz::sim::ISystemPreUpdate, + public gz::sim::ISystemPostUpdate { // Documentation inherited. // During PreUpdate, check for new sensors that were inserted // into simulation and create more components as needed. - public: void PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) final; + public: void PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) final; // Documentation inherited. // During PostUpdate, update the known sensors and publish their data. // Also remove sensors that have been deleted. - public: void PostUpdate(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) final; + public: void PostUpdate(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) final; /// \brief Remove custom sensors if their entities have been removed from /// simulation. /// \param[in] _ecm Immutable reference to ECM. private: void RemoveSensorEntities( - const ignition::gazebo::EntityComponentManager &_ecm); + const gz::sim::EntityComponentManager &_ecm); /// \brief A map of custom entities to their sensors - private: std::unordered_map> entitySensorMap; }; } diff --git a/examples/plugin/custom_sensor_system/README.md b/examples/plugin/custom_sensor_system/README.md index 7145c7b91c..4779c235e5 100644 --- a/examples/plugin/custom_sensor_system/README.md +++ b/examples/plugin/custom_sensor_system/README.md @@ -1,9 +1,9 @@ # Custom sensor system -This example shows how to use a custom sensor with Ignition Gazebo. +This example shows how to use a custom sensor with Gazebo. It uses the odometer created on this example: -[ign-sensors/examples/custom_sensor](https://github.com/ignitionrobotics/ign-sensors/tree/main/examples/custom_sensor). +[ign-sensors/examples/custom_sensor](https://github.com/gazebosim/gz-sensors/tree/main/examples/custom_sensor). ## Build diff --git a/examples/plugin/custom_sensor_system/odometer.sdf b/examples/plugin/custom_sensor_system/odometer.sdf index f9c7817b29..610ace2cc9 100644 --- a/examples/plugin/custom_sensor_system/odometer.sdf +++ b/examples/plugin/custom_sensor_system/odometer.sdf @@ -3,15 +3,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::VelocityControl"> 0.2 0 0 diff --git a/examples/plugin/gui_system_plugin/GuiSystemPlugin.cc b/examples/plugin/gui_system_plugin/GuiSystemPlugin.cc index b4de66bc4c..c7d94f4cbe 100644 --- a/examples/plugin/gui_system_plugin/GuiSystemPlugin.cc +++ b/examples/plugin/gui_system_plugin/GuiSystemPlugin.cc @@ -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 c0bd0e4795..43d8e822a0 100644 --- a/examples/plugin/gui_system_plugin/GuiSystemPlugin.hh +++ b/examples/plugin/gui_system_plugin/GuiSystemPlugin.hh @@ -15,13 +15,13 @@ * */ -#ifndef GZ_GAZEBO_GUISYSTEMPLUGIN_HH_ -#define GZ_GAZEBO_GUISYSTEMPLUGIN_HH_ +#ifndef GZ_SIM_GUISYSTEMPLUGIN_HH_ +#define GZ_SIM_GUISYSTEMPLUGIN_HH_ #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..e8ba89973d 100644 --- a/examples/plugin/gui_system_plugin/README.md +++ b/examples/plugin/gui_system_plugin/README.md @@ -2,8 +2,8 @@ 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 +Gazebo supports any kind of Gazebo GUI plugin +(`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 ed361a72aa..ed16cbe5b7 100644 --- a/examples/plugin/hello_world/HelloWorld.cc +++ b/examples/plugin/hello_world/HelloWorld.cc @@ -15,7 +15,7 @@ * */ -// We'll use a string and the ignmsg command below for a brief example. +// We'll use a string and the gzmsg command below for a brief example. // Remove these includes if your plugin doesn't need them. #include #include @@ -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 "; @@ -47,9 +47,9 @@ void HelloWorld::PostUpdate(const ignition::gazebo::UpdateInfo &_info, msg += "not "; msg += "paused."; - // Messages printed with ignmsg only show when running with verbosity 3 or + // Messages printed with gzmsg only show when running with verbosity 3 or // higher (i.e. ign gazebo -v 3) - ignmsg << msg << std::endl; + gzmsg << msg << std::endl; } diff --git a/examples/plugin/hello_world/HelloWorld.hh b/examples/plugin/hello_world/HelloWorld.hh index 536e706eca..12c11a7cc8 100644 --- a/examples/plugin/hello_world/HelloWorld.hh +++ b/examples/plugin/hello_world/HelloWorld.hh @@ -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/README.md b/examples/plugin/rendering_plugins/README.md index 9ad374ca14..a40ae12908 100644 --- a/examples/plugin/rendering_plugins/README.md +++ b/examples/plugin/rendering_plugins/README.md @@ -1,6 +1,6 @@ # Rendering plugins -Demo of 2 plugins that use Ignition Rendering, one for the server and one for the client. +Demo of 2 plugins that use Gazebo Rendering, one for the server and one for the client. ## Build diff --git a/examples/plugin/rendering_plugins/RenderingGuiPlugin.cc b/examples/plugin/rendering_plugins/RenderingGuiPlugin.cc index 201466ca79..e08fe3361a 100644 --- a/examples/plugin/rendering_plugins/RenderingGuiPlugin.cc +++ b/examples/plugin/rendering_plugins/RenderingGuiPlugin.cc @@ -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,10 +90,10 @@ 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; + gzdbg << "No rendering engine is loaded yet" << std::endl; return; } @@ -101,20 +101,20 @@ void RenderingGuiPlugin::FindScene() auto engineName = loadedEngNames[0]; if (loadedEngNames.size() > 1) { - igndbg << "More than one engine is available. " + gzdbg << "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 + gzerr << "Internal error: failed to load engine [" << engineName << "]. Grid plugin won't work." << std::endl; return; } if (engine->SceneCount() == 0) { - igndbg << "No scene has been created yet" << std::endl; + gzdbg << "No scene has been created yet" << std::endl; return; } @@ -122,13 +122,13 @@ void RenderingGuiPlugin::FindScene() auto scenePtr = engine->SceneByIndex(0); if (nullptr == scenePtr) { - ignerr << "Internal error: scene is null." << std::endl; + gzerr << "Internal error: scene is null." << std::endl; return; } if (engine->SceneCount() > 1) { - igndbg << "More than one scene is available. " + gzdbg << "More than one scene is available. " << "Using scene [" << scene->Name() << "]" << std::endl; } @@ -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 c79ebdbd36..d5b12185fe 100644 --- a/examples/plugin/rendering_plugins/RenderingGuiPlugin.hh +++ b/examples/plugin/rendering_plugins/RenderingGuiPlugin.hh @@ -22,10 +22,10 @@ #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 +/// \brief Example of a GUI plugin that uses Gazebo Rendering. +/// This plugin works with either Gazebo GUI's Scene3D or Gazebo Sim'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 4c9e583bde..aed6c9eb6d 100644 --- a/examples/plugin/rendering_plugins/RenderingServerPlugin.cc +++ b/examples/plugin/rendering_plugins/RenderingServerPlugin.cc @@ -29,13 +29,13 @@ 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,10 +69,10 @@ 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; + gzdbg << "No rendering engine is loaded yet" << std::endl; return; } @@ -80,20 +80,20 @@ void RenderingServerPlugin::FindScene() auto engineName = loadedEngNames[0]; if (loadedEngNames.size() > 1) { - igndbg << "More than one engine is available. " + gzdbg << "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 + gzerr << "Internal error: failed to load engine [" << engineName << "]. Grid plugin won't work." << std::endl; return; } if (engine->SceneCount() == 0) { - igndbg << "No scene has been created yet" << std::endl; + gzdbg << "No scene has been created yet" << std::endl; return; } @@ -101,13 +101,13 @@ void RenderingServerPlugin::FindScene() auto scenePtr = engine->SceneByIndex(0); if (nullptr == scenePtr) { - ignerr << "Internal error: scene is null." << std::endl; + gzerr << "Internal error: scene is null." << std::endl; return; } if (engine->SceneCount() > 1) { - igndbg << "More than one scene is available. " + gzdbg << "More than one scene is available. " << "Using scene [" << scene->Name() << "]" << std::endl; } @@ -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 55515cd3a2..e0379b76bc 100644 --- a/examples/plugin/rendering_plugins/RenderingServerPlugin.hh +++ b/examples/plugin/rendering_plugins/RenderingServerPlugin.hh @@ -20,29 +20,29 @@ #include #include -/// \brief Server-side system that uses Ignition Rendering APIs. +/// \brief Server-side system that uses Gazebo 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 68f77eb736..88db41a5bc 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/reset_plugin/JointPositionRandomizer.cc b/examples/plugin/reset_plugin/JointPositionRandomizer.cc index 1f53bfac49..fb160b2391 100644 --- a/examples/plugin/reset_plugin/JointPositionRandomizer.cc +++ b/examples/plugin/reset_plugin/JointPositionRandomizer.cc @@ -15,17 +15,17 @@ * */ -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; namespace reset_plugin { class JointPositionRandomizer : public System, @@ -72,6 +72,6 @@ class JointPositionRandomizer : public System, } // namespace reset_plugin IGNITION_ADD_PLUGIN(reset_plugin::JointPositionRandomizer, - ignition::gazebo::System, + gz::sim::System, reset_plugin::JointPositionRandomizer::ISystemConfigure, reset_plugin::JointPositionRandomizer::ISystemReset) diff --git a/examples/plugin/reset_plugin/README.md b/examples/plugin/reset_plugin/README.md index 9a1c25b207..5a37034b64 100644 --- a/examples/plugin/reset_plugin/README.md +++ b/examples/plugin/reset_plugin/README.md @@ -31,4 +31,4 @@ Then run a world that loads the plugin as follows: In another terminal, run the following to reset the world. - ign service -s /world/default/control --reqtype ignition.msgs.WorldControl --reptype ignition.msgs.Boolean --timeout 3000 --req 'reset: {all: true}' + ign service -s /world/default/control --reqtype gz.msgs.WorldControl --reptype gz.msgs.Boolean --timeout 3000 --req 'reset: {all: true}' diff --git a/examples/plugin/reset_plugin/joint_position_randomizer.sdf b/examples/plugin/reset_plugin/joint_position_randomizer.sdf index 0d2055fdb5..7d79f5d3f4 100644 --- a/examples/plugin/reset_plugin/joint_position_randomizer.sdf +++ b/examples/plugin/reset_plugin/joint_position_randomizer.sdf @@ -3,13 +3,13 @@ To reset the world, run: - ign service -s /world/default/control \-\-reqtype ignition.msgs.WorldControl \-\-reptype ignition.msgs.Boolean \-\-timeout 3000 \-\-req 'reset: {all: true}' + ign service -s /world/default/control \-\-reqtype gz.msgs.WorldControl \-\-reptype gz.msgs.Boolean \-\-timeout 3000 \-\-req 'reset: {all: true}' --> - - - + + + true diff --git a/examples/plugin/system_plugin/SampleSystem.cc b/examples/plugin/system_plugin/SampleSystem.cc index 7573a94e67..56edc4ef59 100644 --- a/examples/plugin/system_plugin/SampleSystem.cc +++ b/examples/plugin/system_plugin/SampleSystem.cc @@ -6,7 +6,7 @@ // 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,9 +20,9 @@ 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; + gzmsg << "SampleSystem::PostUpdate" << std::endl; } //! [implementSampleSystem] diff --git a/examples/plugin/system_plugin/SampleSystem.hh b/examples/plugin/system_plugin/SampleSystem.hh index 235860c835..b5fd49799b 100644 --- a/examples/plugin/system_plugin/SampleSystem.hh +++ b/examples/plugin/system_plugin/SampleSystem.hh @@ -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 a6bec142bf..02f4eb629a 100644 --- a/examples/plugin/system_plugin/SampleSystem2.cc +++ b/examples/plugin/system_plugin/SampleSystem2.cc @@ -5,7 +5,7 @@ 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; + gzmsg << "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; + gzmsg << "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; + gzmsg << "SampleSystem2::PostUpdate" << std::endl; } diff --git a/examples/scripts/distributed/primary.sdf b/examples/scripts/distributed/primary.sdf index 20644d3006..88e7d83bc3 100644 --- a/examples/scripts/distributed/primary.sdf +++ b/examples/scripts/distributed/primary.sdf @@ -3,7 +3,7 @@ + name="gz::sim::systems::SceneBroadcaster"> @@ -203,7 +203,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 6bdac8c0c4..d0be106c90 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"> @@ -208,7 +208,7 @@ - + sphere diff --git a/examples/scripts/distributed_levels/distributed_levels.sdf.erb b/examples/scripts/distributed_levels/distributed_levels.sdf.erb index b3f03c56ed..8b4ad3c1ec 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"> <% end %> @@ -305,7 +305,7 @@ - + <% for shape in shapes diff --git a/examples/scripts/distributed_levels/primary.sdf b/examples/scripts/distributed_levels/primary.sdf index b9074299cf..5ccfae4475 100644 --- a/examples/scripts/distributed_levels/primary.sdf +++ b/examples/scripts/distributed_levels/primary.sdf @@ -12,7 +12,7 @@ + name="gz::sim::systems::SceneBroadcaster"> @@ -845,7 +845,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 8b996ee96c..5bda0572b9 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"> @@ -854,7 +854,7 @@ - + diff --git a/examples/scripts/log_video_recorder/README.md b/examples/scripts/log_video_recorder/README.md index 3dc25c22d6..2108cc3fca 100644 --- a/examples/scripts/log_video_recorder/README.md +++ b/examples/scripts/log_video_recorder/README.md @@ -35,7 +35,7 @@ timestamped directory where the `record_one_run.bash` is in. ## Changing camera follow behavior > This feature hasn't been ported to Fortress yet, see -> https://github.com/ignitionrobotics/ign-gui/issues/298 +> https://github.com/gazebosim/gz-gui/issues/298 ## Troubleshooting diff --git a/examples/scripts/log_video_recorder/log_video_recorder.sdf b/examples/scripts/log_video_recorder/log_video_recorder.sdf index e333935ddf..1fb964b42a 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/scripts/python_api/README.md b/examples/scripts/python_api/README.md index a828853737..fdf9b6b212 100644 --- a/examples/scripts/python_api/README.md +++ b/examples/scripts/python_api/README.md @@ -1,6 +1,6 @@ # Gazebo Python API -This example shows how to use Gazebo's Python API. +This example shows how to use Gazebo Sim's Python API. For more information, see the -[Python interfaces](https://ignitionrobotics.org/api/gazebo/6.4/python_interfaces.html) tutorial. +[Python interfaces](https://gazebosim.org/api/gazebo/6.4/python_interfaces.html) tutorial. diff --git a/examples/scripts/python_api/gravity.sdf b/examples/scripts/python_api/gravity.sdf index ee1161fa5f..43d46db809 100644 --- a/examples/scripts/python_api/gravity.sdf +++ b/examples/scripts/python_api/gravity.sdf @@ -3,7 +3,7 @@ + name="gz::sim::systems::Physics"> diff --git a/examples/scripts/python_api/testFixture.py b/examples/scripts/python_api/testFixture.py index 46a20e0fe9..1740934366 100644 --- a/examples/scripts/python_api/testFixture.py +++ b/examples/scripts/python_api/testFixture.py @@ -13,7 +13,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -# If you compiled Ignition Gazebo from source you should modify your +# If you compiled Gazebo from source you should modify your # `PYTHONPATH`: # # export PYTHONPATH=$PYTHONPATH:/install/lib/python diff --git a/examples/standalone/comms/publisher.cc b/examples/standalone/comms/publisher.cc index 27c2b99bc0..c7e996770e 100644 --- a/examples/standalone/comms/publisher.cc +++ b/examples/standalone/comms/publisher.cc @@ -61,10 +61,10 @@ int main(int argc, char **argv) std::signal(SIGTERM, signal_handler); // Create a transport node and advertise a topic. - ignition::transport::Node node; + gz::transport::Node node; std::string topic = "/broker/msgs"; - auto pub = node.Advertise(topic); + auto pub = node.Advertise(topic); if (!pub) { std::cerr << "Error advertising topic [" << topic << "]" << std::endl; @@ -74,7 +74,7 @@ int main(int argc, char **argv) std::this_thread::sleep_for(std::chrono::milliseconds(100)); // Prepare the message. - ignition::msgs::Dataframe msg; + gz::msgs::Dataframe msg; msg.set_src_address("addr1"); msg.set_dst_address(argv[1]); @@ -83,7 +83,7 @@ int main(int argc, char **argv) while (!g_terminatePub) { // Prepare the payload. - ignition::msgs::StringMsg payload; + gz::msgs::StringMsg payload; payload.set_data("hello world " + std::to_string(counter)); std::string serializedData; if (!payload.SerializeToString(&serializedData)) diff --git a/examples/standalone/custom_server/README.md b/examples/standalone/custom_server/README.md index 967d244f88..5db02b8b16 100644 --- a/examples/standalone/custom_server/README.md +++ b/examples/standalone/custom_server/README.md @@ -1,7 +1,7 @@ # Custom server This example demonstrates how to run a simulation server headless -using the C++ API, instead of using Ignition Gazebo from the command line. +using the C++ API, instead of using Gazebo from the command line. ## Build Instructions diff --git a/examples/standalone/custom_server/custom_server.cc b/examples/standalone/custom_server/custom_server.cc index 56a3f76963..96abc26f1a 100644 --- a/examples/standalone/custom_server/custom_server.cc +++ b/examples/standalone/custom_server/custom_server.cc @@ -22,16 +22,16 @@ 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 a9407ca6d2..6d9e57794d 100644 --- a/examples/standalone/each_performance/each.cc +++ b/examples/standalone/each_performance/each.cc @@ -23,8 +23,8 @@ #include #include -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ////////////////////////////////////////////////// // This program will output performance comparison data between diff --git a/examples/standalone/entity_creation/entity_creation.cc b/examples/standalone/entity_creation/entity_creation.cc index 60ba90e99c..42f965a8e5 100644 --- a/examples/standalone/entity_creation/entity_creation.cc +++ b/examples/standalone/entity_creation/entity_creation.cc @@ -22,7 +22,7 @@ #include // Create a transport node. -ignition::transport::Node node; +gz::transport::Node node; // timeout used for services constexpr unsigned int timeout = 5000; @@ -30,9 +30,9 @@ constexpr unsigned int timeout = 5000; void createLight() { bool result; - ignition::msgs::Boolean rep; + gz::msgs::Boolean rep; //! [create light] - ignition::msgs::EntityFactory entityFactoryRequest; + gz::msgs::EntityFactory entityFactoryRequest; entityFactoryRequest.mutable_light()->set_name("point"); entityFactoryRequest.mutable_light()->set_range(4); @@ -40,12 +40,12 @@ void createLight() entityFactoryRequest.mutable_light()->set_attenuation_constant(0.2); entityFactoryRequest.mutable_light()->set_attenuation_quadratic(0.01); entityFactoryRequest.mutable_light()->set_cast_shadows(false); - entityFactoryRequest.mutable_light()->set_type(ignition::msgs::Light::POINT); - ignition::msgs::Set( + entityFactoryRequest.mutable_light()->set_type(gz::msgs::Light::POINT); + gz::msgs::Set( entityFactoryRequest.mutable_light()->mutable_direction(), - ignition::math::Vector3d(0.5, 0.2, -0.9)); - ignition::msgs::Set(entityFactoryRequest.mutable_light()->mutable_pose(), - ignition::math::Pose3d(0.0, 0, 3.0, 0.0, 0.0, 0.0)); + gz::math::Vector3d(0.5, 0.2, -0.9)); + gz::msgs::Set(entityFactoryRequest.mutable_light()->mutable_pose(), + gz::math::Pose3d(0.0, 0, 3.0, 0.0, 0.0, 0.0)); //! [create light] //! [call service create] @@ -70,8 +70,8 @@ void createEntityFromStr(const std::string modelStr) { //! [call service create sphere] bool result; - ignition::msgs::EntityFactory req; - ignition::msgs::Boolean res; + gz::msgs::EntityFactory req; + gz::msgs::Boolean res; req.set_sdf(modelStr); bool executed = node.Request("/world/empty/create", @@ -94,12 +94,12 @@ void createEntityFromStr(const std::string modelStr) ////////////////////////////////////////////////// std::string generateLightStr( const std::string light_type, const std::string name, - const bool cast_shadows, const ignition::math::Pose3d pose, - const ignition::math::Color diffuse, - const ignition::math::Color specular, + const bool cast_shadows, const gz::math::Pose3d pose, + const gz::math::Color diffuse, + const gz::math::Color specular, const double attRange, const double attConstant, const double attLinear, const double attQuadratic, - const ignition::math::Vector3d direction, + const gz::math::Vector3d direction, const double spot_inner_angle, const double spot_outer_angle, const double spot_falloff @@ -175,11 +175,11 @@ int main(int argc, char **argv) createEntityFromStr( generateLightStr("spot", "spot_light", false, - ignition::math::Pose3d(0, 0, 4, 0, 0, 0), - ignition::math::Color(0, 0, 1.0, 1.0), - ignition::math::Color(0, 0, 1.0, 1.0), + gz::math::Pose3d(0, 0, 4, 0, 0, 0), + gz::math::Color(0, 0, 1.0, 1.0), + gz::math::Color(0, 0, 1.0, 1.0), 1.0, 0.2, 0.2, 0.001, - ignition::math::Vector3d(0.5, 0.2, -0.9), + gz::math::Vector3d(0.5, 0.2, -0.9), 0.15, 0.45, 1.0)); createLight(); diff --git a/examples/standalone/external_ecm/external_ecm.cc b/examples/standalone/external_ecm/external_ecm.cc index f7faff8176..7ed1526540 100644 --- a/examples/standalone/external_ecm/external_ecm.cc +++ b/examples/standalone/external_ecm/external_ecm.cc @@ -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 b32569abc9..34c3ec026b 100644 --- a/examples/standalone/gtest_setup/command_TEST.cc +++ b/examples/standalone/gtest_setup/command_TEST.cc @@ -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 02e18da59c..cccc44c3c8 100644 --- a/examples/standalone/gtest_setup/gravity_TEST.cc +++ b/examples/standalone/gtest_setup/gravity_TEST.cc @@ -29,40 +29,40 @@ 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 893bdeed1d..8f3b646cf8 100644 --- a/examples/standalone/joy_to_twist/README.md +++ b/examples/standalone/joy_to_twist/README.md @@ -1,9 +1,9 @@ # Joy to Twist Standalone program that subscribes to -[ignition::msgs::Joy](https://ignitionrobotics.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) +[gz::msgs::Joy](https://gazebosim.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) messages and converts publishes -[ignition::msgs::Twist](https://ignitionrobotics.org/api/msgs/5.6/classignition_1_1msgs_1_1Twist.html) +[gz::msgs::Twist](https://gazebosim.org/api/msgs/5.6/classignition_1_1msgs_1_1Twist.html) messages according to user-defined configuration. ## Build @@ -34,7 +34,7 @@ messages that it can consume. See the demo below for a full integrated example. ## Demo example -Ignition Gazebo ships with an example file which has a differential drive vehicle +Gazebo ships with an example file which has a differential drive vehicle that can be controlled using a joystick. You can run it as follows: 1. In a terminal, run the joystick executable which will publish joystick diff --git a/examples/standalone/joy_to_twist/joy_to_twist.cc b/examples/standalone/joy_to_twist/joy_to_twist.cc index 6848992561..c485ebb021 100644 --- a/examples/standalone/joy_to_twist/joy_to_twist.cc +++ b/examples/standalone/joy_to_twist/joy_to_twist.cc @@ -22,25 +22,25 @@ #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/CMakeLists.txt b/examples/standalone/joystick/CMakeLists.txt index 065d97d604..1cf70b35b3 100644 --- a/examples/standalone/joystick/CMakeLists.txt +++ b/examples/standalone/joystick/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) # joystick currently works only on linux -project(ignition-gazebo-joystick) +project(gz-sim-joystick) if(${CMAKE_SYSTEM_NAME} STREQUAL "Linux") find_package(ignition-transport12 QUIET REQUIRED OPTIONAL_COMPONENTS log) diff --git a/examples/standalone/joystick/README.md b/examples/standalone/joystick/README.md index 9e05e2e172..d658e9253e 100644 --- a/examples/standalone/joystick/README.md +++ b/examples/standalone/joystick/README.md @@ -1,8 +1,8 @@ # Joystick Standalone program that publishes -[ignition::msgs::Joy](https://ignitionrobotics.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) -messages from a joystick device using Ignition Transport. +[gz::msgs::Joy](https://gazebosim.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) +messages from a joystick device using Gazebo Transport. The mapping of joystick buttons to fields in the message is the same as [this](http://wiki.ros.org/joy). @@ -43,7 +43,7 @@ echoing the `/joy` topic: ## Demo example -Ignition Gazebo ships with an example file which has a differential drive vehicle +Gazebo ships with an example file which has a differential drive vehicle that can be controlled using a joystick. You can run it as follows: 1. In a terminal, run the joystick executable as described above to publish diff --git a/examples/standalone/joystick/joystick.cc b/examples/standalone/joystick/joystick.cc index 55ffd15ab1..79b2e6844b 100644 --- a/examples/standalone/joystick/joystick.cc +++ b/examples/standalone/joystick/joystick.cc @@ -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/README.md b/examples/standalone/keyboard/README.md index 8912a81839..0430689caa 100644 --- a/examples/standalone/keyboard/README.md +++ b/examples/standalone/keyboard/README.md @@ -25,7 +25,7 @@ You can run the example as follows: ## Demo example -Ignition Gazebo ships with an example file which has a differential drive vehicle +Gazebo ships with an example file which has a differential drive vehicle that can be controlled using a keyboard. You can run it as follows: 1. In a terminal, run the keyboard executable as described above: diff --git a/examples/standalone/keyboard/keyboard.cc b/examples/standalone/keyboard/keyboard.cc index d6db34b274..eb2494fe21 100644 --- a/examples/standalone/keyboard/keyboard.cc +++ b/examples/standalone/keyboard/keyboard.cc @@ -47,12 +47,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 @@ -174,11 +174,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); @@ -220,19 +220,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/light_control/light_control.cc b/examples/standalone/light_control/light_control.cc index 568496eaaa..21014c50b8 100644 --- a/examples/standalone/light_control/light_control.cc +++ b/examples/standalone/light_control/light_control.cc @@ -26,7 +26,7 @@ using namespace std::chrono_literals; // Create a transport node. -ignition::transport::Node node; +gz::transport::Node node; bool result; // timeout used for services @@ -42,9 +42,9 @@ float directionZ = -0.9; void createLight() { - ignition::msgs::Boolean rep; + gz::msgs::Boolean rep; //! [create light] - ignition::msgs::EntityFactory entityFactoryRequest; + gz::msgs::EntityFactory entityFactoryRequest; entityFactoryRequest.mutable_light()->set_name("point"); entityFactoryRequest.mutable_light()->set_range(4); @@ -52,12 +52,12 @@ void createLight() entityFactoryRequest.mutable_light()->set_attenuation_constant(0.2); entityFactoryRequest.mutable_light()->set_attenuation_quadratic(0.01); entityFactoryRequest.mutable_light()->set_cast_shadows(false); - entityFactoryRequest.mutable_light()->set_type(ignition::msgs::Light::POINT); - ignition::msgs::Set( + entityFactoryRequest.mutable_light()->set_type(gz::msgs::Light::POINT); + gz::msgs::Set( entityFactoryRequest.mutable_light()->mutable_direction(), - ignition::math::Vector3d(directionX, directionY, directionZ)); - ignition::msgs::Set(entityFactoryRequest.mutable_light()->mutable_pose(), - ignition::math::Pose3d(0.0, 0, 3.0, 0.0, 0.0, 0.0)); + gz::math::Vector3d(directionX, directionY, directionZ)); + gz::msgs::Set(entityFactoryRequest.mutable_light()->mutable_pose(), + gz::math::Pose3d(0.0, 0, 3.0, 0.0, 0.0, 0.0)); //! [create light] bool executedEntityFactory = node.Request("/world/empty/create", @@ -94,8 +94,8 @@ void createSphere() )"; - ignition::msgs::EntityFactory req; - ignition::msgs::Boolean res; + gz::msgs::EntityFactory req; + gz::msgs::Boolean res; req.set_sdf(modelStr); bool executed = node.Request("/world/empty/create", @@ -117,8 +117,8 @@ void createSphere() ////////////////////////////////////////////////// int main(int argc, char **argv) { - ignition::msgs::Boolean rep; - ignition::msgs::Light lightRequest; + gz::msgs::Boolean rep; + gz::msgs::Light lightRequest; auto lightConfigService = "/world/empty/light_config"; createSphere(); @@ -148,16 +148,16 @@ int main(int argc, char **argv) lightRequest.set_attenuation_constant(0.2); lightRequest.set_attenuation_quadratic(0.01); lightRequest.set_cast_shadows(false); - lightRequest.set_type(ignition::msgs::Light::POINT); + lightRequest.set_type(gz::msgs::Light::POINT); // direction field only affects spot / directional lights - ignition::msgs::Set(lightRequest.mutable_direction(), - ignition::math::Vector3d(directionX, directionY, directionZ)); - ignition::msgs::Set(lightRequest.mutable_pose(), - ignition::math::Pose3d(0.0, -1.5, 3.0, 0.0, 0.0, 0.0)); - ignition::msgs::Set(lightRequest.mutable_diffuse(), - ignition::math::Color(r, g, b, 1)); - ignition::msgs::Set(lightRequest.mutable_specular(), - ignition::math::Color(r, g, b, 1)); + gz::msgs::Set(lightRequest.mutable_direction(), + gz::math::Vector3d(directionX, directionY, directionZ)); + gz::msgs::Set(lightRequest.mutable_pose(), + gz::math::Pose3d(0.0, -1.5, 3.0, 0.0, 0.0, 0.0)); + gz::msgs::Set(lightRequest.mutable_diffuse(), + gz::math::Color(r, g, b, 1)); + gz::msgs::Set(lightRequest.mutable_specular(), + gz::math::Color(r, g, b, 1)); //! [modify light] bool executed = node.Request(lightConfigService, lightRequest, timeout, rep, result); diff --git a/examples/standalone/multi_lrauv_race/multi_lrauv_race.cc b/examples/standalone/multi_lrauv_race/multi_lrauv_race.cc index d24291d525..a30cf0c827 100644 --- a/examples/standalone/multi_lrauv_race/multi_lrauv_race.cc +++ b/examples/standalone/multi_lrauv_race/multi_lrauv_race.cc @@ -53,28 +53,28 @@ int main(int argc, char** argv) ns.push_back("triton"); ns.push_back("daphne"); - ignition::transport::Node node; + gz::transport::Node node; std::vector rudderTopics; rudderTopics.resize(ns.size(), ""); - std::vector rudderPubs; + std::vector rudderPubs; rudderPubs.resize(ns.size()); std::vector propellerTopics; propellerTopics.resize(ns.size(), ""); - std::vector propellerPubs; + std::vector propellerPubs; propellerPubs.resize(ns.size()); // Set up topic names and publishers for (int i = 0; i < ns.size(); i++) { - rudderTopics[i] = ignition::transport::TopicUtils::AsValidTopic( + rudderTopics[i] = gz::transport::TopicUtils::AsValidTopic( "/model/" + ns[i] + "/joint/vertical_fins_joint/0/cmd_pos"); - rudderPubs[i] = node.Advertise(rudderTopics[i]); + rudderPubs[i] = node.Advertise(rudderTopics[i]); - propellerTopics[i] = ignition::transport::TopicUtils::AsValidTopic( + propellerTopics[i] = gz::transport::TopicUtils::AsValidTopic( "/model/" + ns[i] + "/joint/propeller_joint/cmd_pos"); - propellerPubs[i] = node.Advertise( + propellerPubs[i] = node.Advertise( propellerTopics[i]); } @@ -90,13 +90,13 @@ int main(int argc, char** argv) for (int i = 0; i < ns.size(); i++) { rudderCmds[i] = random_angle_within_limits(-0.01, 0.01); - ignition::msgs::Double rudderMsg; + gz::msgs::Double rudderMsg; rudderMsg.set_data(rudderCmds[i]); rudderPubs[i].Publish(rudderMsg); propellerCmds[i] = random_thrust_within_limits( -6.14 * artificial_speedup, 0); - ignition::msgs::Double propellerMsg; + gz::msgs::Double propellerMsg; propellerMsg.set_data(propellerCmds[i]); propellerPubs[i].Publish(propellerMsg); diff --git a/examples/standalone/scene_requester/scene_requester.cc b/examples/standalone/scene_requester/scene_requester.cc index 4ca074c892..bfe977280d 100644 --- a/examples/standalone/scene_requester/scene_requester.cc +++ b/examples/standalone/scene_requester/scene_requester.cc @@ -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 171a9cbe92..8febd5b51a 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 81a56a11b7..498f244540 100644 --- a/examples/worlds/ackermann_steering.sdf +++ b/examples/worlds/ackermann_steering.sdf @@ -1,10 +1,10 @@ + 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/auv_controls.sdf b/examples/worlds/auv_controls.sdf index 224ed03ef5..319dbb97b1 100644 --- a/examples/worlds/auv_controls.sdf +++ b/examples/worlds/auv_controls.sdf @@ -17,12 +17,12 @@ 1. Move the rudder: ign topic -t /model/tethys/joint/vertical_fins_joint/0/cmd_pos \ - -m ignition.msgs.Double -p 'data: -0.17' + -m gz.msgs.Double -p 'data: -0.17' 2. Propel the vehicle: ign topic -t /model/tethys/joint/propeller_joint/cmd_thrust - -m ignition.msgs.Double -p 'data: -31' + -m gz.msgs.Double -p 'data: -31' --> @@ -39,19 +39,19 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Buoyancy"> 1000 @@ -76,21 +76,21 @@ + name="gz::sim::systems::JointPositionController"> horizontal_fins_joint 0.1 + name="gz::sim::systems::JointPositionController"> vertical_fins_joint 0.1 + name="gz::sim::systems::Thruster"> tethys propeller_joint 0.004422 @@ -103,7 +103,7 @@ + name="gz::sim::systems::LiftDrag"> 1000 4.13 -1.1 @@ -121,7 +121,7 @@ + name="gz::sim::systems::LiftDrag"> 1000 4.13 -1.1 @@ -139,7 +139,7 @@ + name="gz::sim::systems::Hydrodynamics"> base_link -4.876161 -126.324739 diff --git a/examples/worlds/breadcrumbs.sdf b/examples/worlds/breadcrumbs.sdf index b3ade84636..e8c4db2a66 100644 --- a/examples/worlds/breadcrumbs.sdf +++ b/examples/worlds/breadcrumbs.sdf @@ -6,12 +6,12 @@ To move the vehicle: - ign topic -t "/model/vehicle_blue/cmd_vel" -m ignition.msgs.Twist -p "linear: {x: 0.5}" + ign topic -t "/model/vehicle_blue/cmd_vel" -m gz.msgs.Twist -p "linear: {x: 0.5}" To drop breadcrumbs: - ign topic -t "/B1/deploy" -m ignition.msgs.Empty -p "unused: true" - ign topic -t "/B2/deploy" -m ignition.msgs.Empty -p "unused: true" + ign topic -t "/B1/deploy" -m gz.msgs.Empty -p "unused: true" + ign topic -t "/B2/deploy" -m gz.msgs.Empty -p "unused: true" --> @@ -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 7ba29ec521..58b064af32 100644 --- a/examples/worlds/buoyancy.sdf +++ b/examples/worlds/buoyancy.sdf @@ -1,6 +1,6 @@ @@ -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 @@ -204,13 +204,13 @@ + name="gz::sim::systems::ApplyJointForce"> propeller_joint + name="gz::sim::systems::LiftDrag"> 1000 1.2535816618911175 -1.4326647564469914 @@ -227,7 +227,7 @@ + name="gz::sim::systems::LiftDrag"> 1000 1.2535816618911175 -1.4326647564469914 @@ -244,7 +244,7 @@ + name="gz::sim::systems::LiftDrag"> 1000 1.2535816618911175 @@ -262,7 +262,7 @@ + name="gz::sim::systems::LiftDrag"> 1000 1.2535816618911175 diff --git a/examples/worlds/buoyancy_engine.sdf b/examples/worlds/buoyancy_engine.sdf index 763ef206ba..955a3152fc 100644 --- a/examples/worlds/buoyancy_engine.sdf +++ b/examples/worlds/buoyancy_engine.sdf @@ -24,10 +24,10 @@ listens to the topic `buoyancy_engine` or - The fluid density of the liquid its suspended in kgm^-3. [optional, float, default=1000kgm^-3] ## Topics -* Subscribes to a ignition::msgs::Double on `buoyancy_engine` or +* Subscribes to a gz::msgs::Double on `buoyancy_engine` or `/model/{namespace}/buoyancy_engine`. This is the set point for the engine. -* Publishes a ignition::msgs::Double on `buoyancy_engine` or +* Publishes a gz::msgs::Double on `buoyancy_engine` or `/model/{namespace}/buoyancy_engine/current_volume` on the current volume ## Examples @@ -41,13 +41,13 @@ until it breaches and then start oscillating around the surface. On the other hand the box on the right will rise forever as no surface is set. Enter the following in a separate terminal: ``` -ign topic -t /model/buoyant_box/buoyancy_engine/ -m ignition.msgs.Double +ign topic -t /model/buoyant_box/buoyancy_engine/ -m gz.msgs.Double -p "data: 0.003" ``` The boxes will float up. Note that the box on the left will start oscillating once it breaches the surface. ``` -ign topic -t /model/buoyant_box/buoyancy_engine/ -m ignition.msgs.Double +ign topic -t /model/buoyant_box/buoyancy_engine/ -m gz.msgs.Double -p "data: 0.001" ``` The boxes will go down. @@ -70,24 +70,24 @@ ign topic -t /model/buoyant_box/buoyancy_engine/current_volume -e + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Contact"> + name="gz::sim::systems::Buoyancy"> 1000 @@ -133,7 +133,7 @@ ign topic -t /model/buoyant_box/buoyancy_engine/current_volume -e + name="gz::sim::systems::BuoyancyEngine"> body buoyant_box 0.0 @@ -173,7 +173,7 @@ ign topic -t /model/buoyant_box/buoyancy_engine/current_volume -e + name="gz::sim::systems::BuoyancyEngine"> body buoyant_box 0.0 diff --git a/examples/worlds/camera_sensor.sdf b/examples/worlds/camera_sensor.sdf index 8e8c090728..aeff9c4dfd 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 abd7817c68..d4caee8394 100644 --- a/examples/worlds/camera_video_record_dbl_pendulum.sdf +++ b/examples/worlds/camera_video_record_dbl_pendulum.sdf @@ -4,11 +4,11 @@ Call the following service to start video recording: - ign service -s /camera/record_video --reqtype ignition.msgs.VideoRecord --reptype ignition.msgs.Boolean --timeout 300 --req 'start: true, format:"mp4", save_filename:"test.mp4"' + ign service -s /camera/record_video --reqtype gz.msgs.VideoRecord --reptype gz.msgs.Boolean --timeout 300 --req 'start: true, format:"mp4", save_filename:"test.mp4"' Call the following service to stop video recording: - ign service -s /camera/record_video --reqtype ignition.msgs.VideoRecord --reptype ignition.msgs.Boolean --timeout 300 --req 'stop: true' + ign service -s /camera/record_video --reqtype gz.msgs.VideoRecord --reptype gz.msgs.Boolean --timeout 300 --req 'stop: true' The video is saved to test.mp4 @@ -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..b5fa5665a6 100644 --- a/examples/worlds/contact_sensor.sdf +++ b/examples/worlds/contact_sensor.sdf @@ -1,7 +1,7 @@ - + name="gz::sim::systems::TriggeredPublisher"> + 87 - + data: 10.0 - + name="gz::sim::systems::TriggeredPublisher"> + 88 - + data: -1.0 - + name="gz::sim::systems::TriggeredPublisher"> + 83 - + data: 0.0 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/default.sdf b/examples/worlds/default.sdf index a963e7e709..acd9c876d6 100644 --- a/examples/worlds/default.sdf +++ b/examples/worlds/default.sdf @@ -3,7 +3,7 @@ This world has no GUI configurations of its own. When loading `ign gazebo default.sdf` for the first time, this will be loaded - using the default configuration, saved at `~/.ignition/gazebo/gui.config`. + using the default configuration, saved at `~/.gz/sim/gui.config`. The default configuration can be edited manually, or by choosing `Save configuration` from the top-left menu. diff --git a/examples/worlds/depth_camera_sensor.sdf b/examples/worlds/depth_camera_sensor.sdf index 80ce0abf93..0c4b1eb4ed 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..675032a251 100644 --- a/examples/worlds/detachable_joint.sdf +++ b/examples/worlds/detachable_joint.sdf @@ -6,13 +6,13 @@ To move the vehicle: - ign topic -t "/model/vehicle_blue/cmd_vel" -m ignition.msgs.Twist -p "linear: {x: 0.5}" + ign topic -t "/model/vehicle_blue/cmd_vel" -m gz.msgs.Twist -p "linear: {x: 0.5}" To drop breadcrumbs: - ign topic -t "/B1/detach" -m ignition.msgs.Empty -p "unused: true" - ign topic -t "/B2/detach" -m ignition.msgs.Empty -p "unused: true" - ign topic -t "/B3/detach" -m ignition.msgs.Empty -p "unused: true" + ign topic -t "/B1/detach" -m gz.msgs.Empty -p "unused: true" + ign topic -t "/B2/detach" -m gz.msgs.Empty -p "unused: true" + ign topic -t "/B3/detach" -m gz.msgs.Empty -p "unused: true" --> @@ -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 79fb0ba80b..36c826ef65 100644 --- a/examples/worlds/diff_drive.sdf +++ b/examples/worlds/diff_drive.sdf @@ -1,12 +1,12 @@ + 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 2f42cf7608..ca44e12f3c 100644 --- a/examples/worlds/fuel_textured_mesh.sdf +++ b/examples/worlds/fuel_textured_mesh.sdf @@ -1,6 +1,6 @@ @@ -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 07020dda9b..2e877ff70e 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/graded_buoyancy.sdf b/examples/worlds/graded_buoyancy.sdf index e4fff750d8..088b1d4040 100644 --- a/examples/worlds/graded_buoyancy.sdf +++ b/examples/worlds/graded_buoyancy.sdf @@ -1,6 +1,6 @@ @@ -13,19 +13,19 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Buoyancy"> 1000 diff --git a/examples/worlds/grid.sdf b/examples/worlds/grid.sdf index affe914178..0a62b9662d 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 685bace5d0..a05a842d22 100644 --- a/examples/worlds/import_mesh.sdf +++ b/examples/worlds/import_mesh.sdf @@ -1,6 +1,6 @@ @@ -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 b3838229b7..27d226d3b6 100644 --- a/examples/worlds/joint_controller.sdf +++ b/examples/worlds/joint_controller.sdf @@ -1,28 +1,28 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -118,7 +118,7 @@ + name="gz::sim::systems::JointController"> j1 5.0 @@ -205,7 +205,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 d1c09e43d4..0ac07eaefb 100644 --- a/examples/worlds/joint_position_controller.sdf +++ b/examples/worlds/joint_position_controller.sdf @@ -1,22 +1,22 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -114,7 +114,7 @@ + name="gz::sim::systems::JointPositionController"> j1 rotor_cmd 1 diff --git a/examples/worlds/joint_trajectory_controller.sdf b/examples/worlds/joint_trajectory_controller.sdf index 6d5155129e..4240a1ed06 100644 --- a/examples/worlds/joint_trajectory_controller.sdf +++ b/examples/worlds/joint_trajectory_controller.sdf @@ -1,12 +1,12 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> 0.4 0.4 0.4 @@ -334,7 +334,7 @@ + name="gz::sim::systems::JointTrajectoryController"> RR_position_control_joint1 0.7854 20 @@ -498,7 +498,7 @@ + name="gz::sim::systems::JointTrajectoryController"> 0.6 @@ -654,7 +654,7 @@ + name="gz::sim::systems::JointTrajectoryController"> custom_topic_effort_control diff --git a/examples/worlds/kinetic_energy_monitor.sdf b/examples/worlds/kinetic_energy_monitor.sdf index 30de44ede4..313fb34d5f 100644 --- a/examples/worlds/kinetic_energy_monitor.sdf +++ b/examples/worlds/kinetic_energy_monitor.sdf @@ -1,6 +1,6 @@ + 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..1012a2b1db 100644 --- a/examples/worlds/levels_no_performers.sdf +++ b/examples/worlds/levels_no_performers.sdf @@ -1,25 +1,25 @@ linear_battery 4.2 diff --git a/examples/worlds/lift_drag_nested.sdf b/examples/worlds/lift_drag_nested.sdf index 1587410928..7e6742c74f 100644 --- a/examples/worlds/lift_drag_nested.sdf +++ b/examples/worlds/lift_drag_nested.sdf @@ -7,7 +7,7 @@ Try sending commands: - ign topic -t "/model/lift_drag_demo_model/joint/rod_1_joint/cmd_force" -m ignition.msgs.Double -p "data: 0.7" + ign topic -t "/model/lift_drag_demo_model/joint/rod_1_joint/cmd_force" -m gz.msgs.Double -p "data: 0.7" Listen to joint states: @@ -18,15 +18,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -253,11 +253,11 @@ + name="gz::sim::systems::JointStatePublisher"> + name="gz::sim::systems::LiftDrag"> 0.1 0.1 0.001 @@ -271,7 +271,7 @@ + name="gz::sim::systems::LiftDrag"> 0.1 0.1 0.001 @@ -285,7 +285,7 @@ + name="gz::sim::systems::ApplyJointForce"> rod_1_joint diff --git a/examples/worlds/lights.sdf b/examples/worlds/lights.sdf index 61d2d92fd1..2de3cf79c3 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 fc07fe8ab7..ec6e3e954e 100644 --- a/examples/worlds/linear_battery_demo.sdf +++ b/examples/worlds/linear_battery_demo.sdf @@ -10,23 +10,23 @@ Move both vehicles: - ign topic -t "/model/vehicle_blue/cmd_vel" -m ignition.msgs.Twist -p "linear: {x: 6.0} angular: {z: 0.4}" - ign topic -t "/model/vehicle_green/cmd_vel" -m ignition.msgs.Twist -p "linear: {x: 6.0} angular: {z: 0.4}" + ign topic -t "/model/vehicle_blue/cmd_vel" -m gz.msgs.Twist -p "linear: {x: 6.0} angular: {z: 0.4}" + ign topic -t "/model/vehicle_green/cmd_vel" -m gz.msgs.Twist -p "linear: {x: 6.0} angular: {z: 0.4}" Listen to battery state of charge: ign topic -e -t /model/vehicle_blue/battery/linear_battery/state Recharge the battery using a service (default): - ign service -s /model/vehicle_blue/battery/linear_battery/recharge/start --reqtype ignition.msgs.Boolean --reptype ignition.msgs.Empty --req 'data:true' --timeout 1000 + ign service -s /model/vehicle_blue/battery/linear_battery/recharge/start --reqtype gz.msgs.Boolean --reptype gz.msgs.Empty --req 'data:true' --timeout 1000 Recharge the battery using a topic (optional if is true): - ign topic -t /model/vehicle_blue/battery/linear_battery/recharge/start -m ignition.msgs.Boolean -p 'data:true' + ign topic -t /model/vehicle_blue/battery/linear_battery/recharge/start -m gz.msgs.Boolean -p 'data:true' Stop recharging the battery using a service (default): - ign service -s /model/vehicle_blue/battery/linear_battery/recharge/stop --reqtype ignition.msgs.Boolean --reptype ignition.msgs.Empty --req 'data:true' --timeout 1000 + ign service -s /model/vehicle_blue/battery/linear_battery/recharge/stop --reqtype gz.msgs.Boolean --reptype gz.msgs.Empty --req 'data:true' --timeout 1000 Stop recharging the battery using a topic (optional if is true): - ign topic -t /model/vehicle_blue/battery/linear_battery/recharge/stop -m ignition.msgs.Boolean -p 'data:true' + ign topic -t /model/vehicle_blue/battery/linear_battery/recharge/stop -m gz.msgs.Boolean -p 'data:true' After the battery runs out, no force is applied to the joints in the blue vehicle. It eventually comes to a stop due to friction in its joints. Had there been no joint friction, @@ -38,11 +38,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -263,7 +263,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint_green right_wheel_joint_green 1.25 @@ -271,7 +271,7 @@ + name="gz::sim::systems::LinearBatteryPlugin"> linear_battery 4.2 @@ -468,7 +468,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint_blue right_wheel_joint_blue 1.25 @@ -476,7 +476,7 @@ + name="gz::sim::systems::LinearBatteryPlugin"> linear_battery 12.592 12.592 diff --git a/examples/worlds/log_record_dbl_pendulum.sdf b/examples/worlds/log_record_dbl_pendulum.sdf index 5d09ef9fdd..d3a225380f 100644 --- a/examples/worlds/log_record_dbl_pendulum.sdf +++ b/examples/worlds/log_record_dbl_pendulum.sdf @@ -2,16 +2,16 @@ @@ -22,19 +22,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 ba534c82fd..c37dffe0cf 100644 --- a/examples/worlds/log_record_keyboard.sdf +++ b/examples/worlds/log_record_keyboard.sdf @@ -2,32 +2,32 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::LogRecord"> @@ -248,7 +248,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint_green right_wheel_joint_green 1.25 @@ -426,7 +426,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 222181127e..9d47a63646 100644 --- a/examples/worlds/log_record_resources.sdf +++ b/examples/worlds/log_record_resources.sdf @@ -2,30 +2,30 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::LogRecord"> 1 0 diff --git a/examples/worlds/log_record_shapes.sdf b/examples/worlds/log_record_shapes.sdf index 41efbe1c66..e63d32c588 100644 --- a/examples/worlds/log_record_shapes.sdf +++ b/examples/worlds/log_record_shapes.sdf @@ -2,17 +2,17 @@ @@ -22,19 +22,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..b6252d4b9e 100644 --- a/examples/worlds/logical_audio_sensor_plugin.sdf +++ b/examples/worlds/logical_audio_sensor_plugin.sdf @@ -12,12 +12,12 @@ To play the source attached to the blue box, run the following command: ign service -s /model/blue_box/sensor/source_1/play - --reqtype ignition.msgs.Empty --reptype ignition.msgs.Boolean + --reqtype gz.msgs.Empty --reptype gz.msgs.Boolean --timeout 1000 --req 'unused: false' To stop the source attached to the blue box, run the following command: ign service -s /model/blue_box/sensor/source_1/stop - --reqtype ignition.msgs.Empty --reptype ignition.msgs.Boolean + --reqtype gz.msgs.Empty --reptype gz.msgs.Boolean --timeout 1000 --req 'unused: false' To observe microphone detections, use the /mic_/detection topic. @@ -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..bb791de1ea 100644 --- a/examples/worlds/logical_camera_sensor.sdf +++ b/examples/worlds/logical_camera_sensor.sdf @@ -1,6 +1,6 @@ @@ -18,15 +18,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -77,7 +77,7 @@ - + 0 2 0.325 0 -0 0 @@ -345,7 +345,7 @@ + name="gz::sim::systems::MecanumDrive"> front_left_wheel_joint front_right_wheel_joint rear_left_wheel_joint diff --git a/examples/worlds/minimal_scene.sdf b/examples/worlds/minimal_scene.sdf index 90f85eac6d..b0b7e50230 100644 --- a/examples/worlds/minimal_scene.sdf +++ b/examples/worlds/minimal_scene.sdf @@ -1,7 +1,7 @@ + name="gz::sim::systems::JointPositionController"> horizontal_fins_joint 0.1 + name="gz::sim::systems::JointPositionController"> vertical_fins_joint 0.1 + name="gz::sim::systems::Thruster"> tethys propeller_joint 0.004422 @@ -96,7 +96,7 @@ + name="gz::sim::systems::LiftDrag"> 1000 4.13 -1.1 @@ -114,7 +114,7 @@ + name="gz::sim::systems::LiftDrag"> 1000 4.13 -1.1 @@ -131,7 +131,7 @@ + name="gz::sim::systems::Hydrodynamics"> base_link -4.876161 -126.324739 @@ -163,21 +163,21 @@ + name="gz::sim::systems::JointPositionController"> horizontal_fins_joint 0.1 + name="gz::sim::systems::JointPositionController"> vertical_fins_joint 0.1 + name="gz::sim::systems::Thruster"> triton propeller_joint 0.004422 @@ -190,7 +190,7 @@ + name="gz::sim::systems::LiftDrag"> 1000 4.13 -1.1 @@ -208,7 +208,7 @@ + name="gz::sim::systems::LiftDrag"> 1000 4.13 -1.1 @@ -225,7 +225,7 @@ + name="gz::sim::systems::Hydrodynamics"> base_link -4.876161 -126.324739 @@ -257,21 +257,21 @@ + name="gz::sim::systems::JointPositionController"> horizontal_fins_joint 0.1 + name="gz::sim::systems::JointPositionController"> vertical_fins_joint 0.1 + name="gz::sim::systems::Thruster"> daphne propeller_joint 0.004422 @@ -284,7 +284,7 @@ + name="gz::sim::systems::LiftDrag"> 1000 4.13 -1.1 @@ -302,7 +302,7 @@ + name="gz::sim::systems::LiftDrag"> 1000 4.13 -1.1 @@ -319,7 +319,7 @@ + name="gz::sim::systems::Hydrodynamics"> base_link -4.876161 -126.324739 diff --git a/examples/worlds/multicopter_velocity_control.sdf b/examples/worlds/multicopter_velocity_control.sdf index effbeeafff..3dc0d95202 100644 --- a/examples/worlds/multicopter_velocity_control.sdf +++ b/examples/worlds/multicopter_velocity_control.sdf @@ -6,11 +6,11 @@ You can use the velocity controller and command linear velocity and yaw angular Send commands to the quadcopter to go straight up: - ign topic -t "/X3/gazebo/command/twist" -m ignition.msgs.Twist -p "linear: {x:0 y: 0 z: 0.1} angular {z: 0}" + ign topic -t "/X3/gazebo/command/twist" -m gz.msgs.Twist -p "linear: {x:0 y: 0 z: 0.1} angular {z: 0}" To hover - ign topic -t "/X3/gazebo/command/twist" -m ignition.msgs.Twist -p " " + ign topic -t "/X3/gazebo/command/twist" -m gz.msgs.Twist -p " " Listen to odometry: @@ -19,11 +19,11 @@ You can use the velocity controller and command linear velocity and yaw angular Send commands to the hexacopter to go straight up: - ign topic -t "/X4/gazebo/command/twist" -m ignition.msgs.Twist -p "linear: {x:0 y: 0 z: 0.1} angular {z: 0}" + ign topic -t "/X4/gazebo/command/twist" -m gz.msgs.Twist -p "linear: {x:0 y: 0 z: 0.1} angular {z: 0}" To hover - ign topic -t "/X4/gazebo/command/twist" -m ignition.msgs.Twist -p " " + ign topic -t "/X4/gazebo/command/twist" -m gz.msgs.Twist -p " " Listen to odometry: @@ -39,19 +39,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 @@ -102,7 +102,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 @@ -122,7 +122,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 @@ -142,7 +142,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 @@ -162,7 +162,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 @@ -182,7 +182,7 @@ You can use the velocity controller and command linear velocity and yaw angular + name="gz::sim::systems::MulticopterVelocityControl"> X3 gazebo/command/twist enable @@ -221,7 +221,7 @@ You can use the velocity controller and command linear velocity and yaw angular + name="gz::sim::systems::OdometryPublisher"> 3 @@ -232,7 +232,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 @@ -252,7 +252,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 @@ -272,7 +272,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 @@ -292,7 +292,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 @@ -312,7 +312,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 @@ -332,7 +332,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 @@ -354,7 +354,7 @@ You can use the velocity controller and command linear velocity and yaw angular + name="gz::sim::systems::MulticopterVelocityControl"> X4 gazebo/command/twist enable @@ -416,7 +416,7 @@ You can use the velocity controller and command linear velocity and yaw angular + name="gz::sim::systems::OdometryPublisher"> 3 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/optical_tactile_sensor_plugin.sdf b/examples/worlds/optical_tactile_sensor_plugin.sdf index 06262adb00..e2c84a00b9 100644 --- a/examples/worlds/optical_tactile_sensor_plugin.sdf +++ b/examples/worlds/optical_tactile_sensor_plugin.sdf @@ -7,8 +7,8 @@ Disable the sensor with: ign service -s /optical_tactile_plugin/enable \ - --reqtype ignition.msgs.Boolean \ - --reptype ignition.msgs.Empty \ + --reqtype gz.msgs.Boolean \ + --reptype gz.msgs.Empty \ --timeout 2000 --req 'data: false' --> @@ -17,23 +17,23 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Contact"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Sensors"> ogre2 @@ -243,7 +243,7 @@ false + name="gz::sim::systems::OpticalTactilePlugin"> true optical_tactile_plugin true diff --git a/examples/worlds/particle_emitter.sdf b/examples/worlds/particle_emitter.sdf index 36fae35919..cd4ca08306 100644 --- a/examples/worlds/particle_emitter.sdf +++ b/examples/worlds/particle_emitter.sdf @@ -9,15 +9,15 @@ To disable the particle emitter: - ign topic -t /model/fog_generator/link/fog_link/particle_emitter/emitter/cmd -m ignition.msgs.ParticleEmitter -p 'emitting: {data: false}' + ign topic -t /model/fog_generator/link/fog_link/particle_emitter/emitter/cmd -m gz.msgs.ParticleEmitter -p 'emitting: {data: false}' Enable back the particle emitter: - ign topic -t /model/fog_generator/link/fog_link/particle_emitter/emitter/cmd -m ignition.msgs.ParticleEmitter -p 'emitting: {data: true}' + ign topic -t /model/fog_generator/link/fog_link/particle_emitter/emitter/cmd -m gz.msgs.ParticleEmitter -p 'emitting: {data: true}' Then, change the particle rate: - ign topic -t /model/fog_generator/link/fog_link/particle_emitter/emitter/cmd -m ignition.msgs.ParticleEmitter -p 'rate: {data: 100}' + ign topic -t /model/fog_generator/link/fog_link/particle_emitter/emitter/cmd -m gz.msgs.ParticleEmitter -p 'rate: {data: 100}' --> @@ -29,21 +29,21 @@ + name="gz::sim::systems::Physics"> libignition-physics-tpe-plugin.so + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::ParticleEmitter"> diff --git a/examples/worlds/pendulum_links.sdf b/examples/worlds/pendulum_links.sdf index 1927835b7a..8b86e6bdf3 100644 --- a/examples/worlds/pendulum_links.sdf +++ b/examples/worlds/pendulum_links.sdf @@ -1,11 +1,11 @@ @@ -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/perfect_comms.sdf b/examples/worlds/perfect_comms.sdf index 090d71aa45..c83ffae5e3 100644 --- a/examples/worlds/perfect_comms.sdf +++ b/examples/worlds/perfect_comms.sdf @@ -1,6 +1,6 @@ @@ -14,19 +14,19 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name='gz::sim::systems::Sensors'> @@ -378,7 +378,7 @@ + name="gz::sim::systems::LiftDrag"> 0.2 10.000 0.0001 @@ -396,7 +396,7 @@ + name="gz::sim::systems::LiftDrag"> 0.2 10.000 0.0001 @@ -727,7 +727,7 @@ + name="gz::sim::systems::LiftDrag"> 0.1 4.000 0.001 @@ -745,7 +745,7 @@ + name="gz::sim::systems::LiftDrag"> 0.1 4.000 0.001 @@ -763,7 +763,7 @@ + name="gz::sim::systems::LiftDrag"> 0.02 4.000 0.001 @@ -781,7 +781,7 @@ + name="gz::sim::systems::LiftDrag"> 0.02 4.000 0.001 @@ -799,7 +799,7 @@ + name="gz::sim::systems::LiftDrag"> 0.00 2.000 @@ -818,7 +818,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..d8d0f31575 100644 --- a/examples/worlds/pose_publisher.sdf +++ b/examples/worlds/pose_publisher.sdf @@ -1,6 +1,6 @@ @@ -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/rf_comms.sdf b/examples/worlds/rf_comms.sdf index 4338b56601..00cae588d7 100644 --- a/examples/worlds/rf_comms.sdf +++ b/examples/worlds/rf_comms.sdf @@ -1,6 +1,6 @@ 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 91b52529c4..6e722a8757 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/skid_steer_mecanum.sdf b/examples/worlds/skid_steer_mecanum.sdf index 970facaabf..9c86851d9e 100644 --- a/examples/worlds/skid_steer_mecanum.sdf +++ b/examples/worlds/skid_steer_mecanum.sdf @@ -1,10 +1,10 @@ + name="gz::sim::systems::NavSat"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Physics"> diff --git a/examples/worlds/thermal_camera.sdf b/examples/worlds/thermal_camera.sdf index cb37b61619..70d64a519c 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"> @@ -259,7 +259,7 @@ + name="gz::sim::systems::Thermal"> 285.0 @@ -343,7 +343,7 @@ thermal_camera_8bit/image + name="gz::sim::systems::ThermalSensor"> 253.15 673.15 3.0 diff --git a/examples/worlds/touch_plugin.sdf b/examples/worlds/touch_plugin.sdf index 7497a15984..f1277a5dfb 100644 --- a/examples/worlds/touch_plugin.sdf +++ b/examples/worlds/touch_plugin.sdf @@ -8,8 +8,8 @@ The plugin's parameters are documented in src/systems/touchplugin/TouchPlugin.hh If the plugin is not enabled by default send this command to enable ign service -s /white_touches_only_green/enable \ - --reqtype ignition.msgs.Boolean \ - --reptype ignition.msgs.Empty \ + --reqtype gz.msgs.Boolean \ + --reptype gz.msgs.Empty \ --timeout 3000 \ --req 'data:true' @@ -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..b2132df1cf 100644 --- a/examples/worlds/track_drive.sdf +++ b/examples/worlds/track_drive.sdf @@ -1,12 +1,12 @@ + 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 cf9cd29acc..d224d41b32 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,99 +1113,99 @@ - + name="gz::sim::systems::TriggeredPublisher"> + 87 - + linear: {x: 1.0}, angular: {z: 0.0} - + name="gz::sim::systems::TriggeredPublisher"> + 88 - + linear: {x: -1.0}, angular: {z: 0.0} - + name="gz::sim::systems::TriggeredPublisher"> + 83 - + linear: {x: 0.0}, angular: {z: 0.0} - + name="gz::sim::systems::TriggeredPublisher"> + 65 - + linear: {x: 0.0}, angular: {z: 1.0} - + name="gz::sim::systems::TriggeredPublisher"> + 68 - + linear: {x: 0.0}, angular: {z: -1.0} - + name="gz::sim::systems::TriggeredPublisher"> + 81 - + linear: {x: 1.0}, angular: {z: 1.0} - + name="gz::sim::systems::TriggeredPublisher"> + 69 - + linear: {x: 1.0}, angular: {z: -1.0} - + name="gz::sim::systems::TriggeredPublisher"> + 90 - + linear: {x: -1.0}, angular: {z: 1.0} - + name="gz::sim::systems::TriggeredPublisher"> + 67 - + linear: {x: -1.0}, angular: {z: -1.0} diff --git a/examples/worlds/trajectory_follower.sdf b/examples/worlds/trajectory_follower.sdf index a07936c181..a31aa46ec2 100644 --- a/examples/worlds/trajectory_follower.sdf +++ b/examples/worlds/trajectory_follower.sdf @@ -1,16 +1,16 @@ @@ -21,15 +21,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -111,7 +111,7 @@ + name="gz::sim::systems::TrajectoryFollower"> box_link true 10 @@ -162,7 +162,7 @@ + name="gz::sim::systems::TrajectoryFollower"> box_link true 10 @@ -213,7 +213,7 @@ + name="gz::sim::systems::TrajectoryFollower"> box_link true 10 diff --git a/examples/worlds/triggered_publisher.sdf b/examples/worlds/triggered_publisher.sdf index 303f78beca..90e2999c3a 100644 --- a/examples/worlds/triggered_publisher.sdf +++ b/examples/worlds/triggered_publisher.sdf @@ -1,9 +1,9 @@ - + name="gz::sim::systems::TriggeredPublisher"> + 87 - + linear: {x: 2.0}, angular: {z: 0.0} - + name="gz::sim::systems::TriggeredPublisher"> + 88 - + linear: {x: -2.0}, angular: {z: 0.0} - + name="gz::sim::systems::TriggeredPublisher"> + 68 - + linear: {x: 0.0}, angular: {z: -0.5} - + name="gz::sim::systems::TriggeredPublisher"> + 65 - + linear: {x: 0.0}, angular: {z: 0.5} - + name="gz::sim::systems::TriggeredPublisher"> + 83 - + linear: {x: 0.0}, angular: {z: 0.0} - + vehicle 2 2 2 diff --git a/examples/worlds/velocity_control.sdf b/examples/worlds/velocity_control.sdf index 1150268c3e..2ec03b7b11 100644 --- a/examples/worlds/velocity_control.sdf +++ b/examples/worlds/velocity_control.sdf @@ -1,12 +1,12 @@ @@ -18,15 +18,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -240,7 +240,7 @@ + name="gz::sim::systems::VelocityControl"> @@ -415,7 +415,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 5f0775c046..5821c00aba 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/visibility.sdf b/examples/worlds/visibility.sdf index 31bec366b3..e8e57771df 100644 --- a/examples/worlds/visibility.sdf +++ b/examples/worlds/visibility.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/visualize_contacts.sdf b/examples/worlds/visualize_contacts.sdf index f39994dced..5d39a0b161 100644 --- a/examples/worlds/visualize_contacts.sdf +++ b/examples/worlds/visualize_contacts.sdf @@ -14,19 +14,19 @@ Contacts will be visualized as blue spheres and green cylinders. + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Contact"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::UserCommands"> diff --git a/examples/worlds/visualize_lidar.sdf b/examples/worlds/visualize_lidar.sdf index d38fe690ce..2071b3b641 100644 --- a/examples/worlds/visualize_lidar.sdf +++ b/examples/worlds/visualize_lidar.sdf @@ -11,16 +11,16 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre2 + name="gz::sim::systems::SceneBroadcaster"> @@ -503,7 +503,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint right_wheel_joint 1.25 diff --git a/examples/worlds/wide_angle_camera.sdf b/examples/worlds/wide_angle_camera.sdf index 3fef95edd4..1941f54e9a 100644 --- a/examples/worlds/wide_angle_camera.sdf +++ b/examples/worlds/wide_angle_camera.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/wind.sdf b/examples/worlds/wind.sdf index 34cfceffa5..9fdeae1deb 100644 --- a/examples/worlds/wind.sdf +++ b/examples/worlds/wind.sdf @@ -4,22 +4,22 @@ After starting the simulation, the wind velocity can be adjusted by publishing a Wind message Example: - ign topic -t "/world/wind_demo/wind/" -m ignition.msgs.Wind -p "linear_velocity: {x:-50, y:50}, enable_wind: true" + ign topic -t "/world/wind_demo/wind/" -m gz.msgs.Wind -p "linear_velocity: {x:-50, y:50}, enable_wind: true" --> + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -368,7 +368,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/gz/sim/Conversions.hh b/include/gz/sim/Conversions.hh index 0fc0be3dcd..5f55f4e3a6 100644 --- a/include/gz/sim/Conversions.hh +++ b/include/gz/sim/Conversions.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_CONVERSIONS_HH_ -#define GZ_GAZEBO_CONVERSIONS_HH_ +#ifndef GZ_SIM_CONVERSIONS_HH_ +#define GZ_SIM_CONVERSIONS_HH_ #include #include @@ -57,24 +57,24 @@ #include "gz/sim/Export.hh" #include "gz/sim/Types.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_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 + void GZ_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. + /// to the values contained in a sim::UpdateInfo object. /// \param[out] _msg WorldStatistics message to set. /// \param[in] _in UpdateInfo object. - void IGNITION_GAZEBO_VISIBLE + void GZ_GAZEBO_VISIBLE set(msgs::WorldStatistics *_msg, const UpdateInfo &_in); /// \brief Helper function that sets a mutable msgs::Time object @@ -82,7 +82,7 @@ namespace ignition /// object. /// \param[out] _msg Time message to set. /// \param[in] _in Chrono duration object. - void IGNITION_GAZEBO_VISIBLE + void GZ_GAZEBO_VISIBLE set(msgs::Time *_msg, const std::chrono::steady_clock::duration &_in); /// \brief Generic conversion from an SDF geometry to another type. @@ -232,7 +232,7 @@ namespace ignition /// \param[in] _in SDF light type. /// \return Conversion result. /// \tparam Out Output type. - std::string IGNITION_GAZEBO_VISIBLE + std::string GZ_GAZEBO_VISIBLE convert(const sdf::LightType &_in); /// \brief Generic conversion from a light message to another type. @@ -256,7 +256,7 @@ namespace ignition /// \brief Specialized conversion from a string to a sdf light type /// \param[in] _in String with the light type. /// \return Light type emun SDF object. - sdf::LightType IGNITION_GAZEBO_VISIBLE + sdf::LightType GZ_GAZEBO_VISIBLE convert(const std::string &_in); /// \brief Generic conversion from an SDF gui to another type. @@ -560,7 +560,7 @@ namespace ignition } /// \brief Specialized conversion from a world statistics message to an - /// `ignition::gazebo::UpdateInfo` object. + /// `gz::sim::UpdateInfo` object. /// \param[in] _in WorldStatistics message. /// \return Update info. template<> diff --git a/include/gz/sim/Entity.hh b/include/gz/sim/Entity.hh index b4a8f08c75..7e5df06803 100644 --- a/include/gz/sim/Entity.hh +++ b/include/gz/sim/Entity.hh @@ -14,23 +14,23 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_ENTITY_HH_ -#define GZ_GAZEBO_ENTITY_HH_ +#ifndef GZ_SIM_ENTITY_HH_ +#define GZ_SIM_ENTITY_HH_ #include #include #include /// \brief This library is part of the [Ignition -/// Robotics](https://ignitionrobotics.org) project. -namespace ignition +/// Robotics](https://gazebosim.org) project. +namespace gz { /// \brief Gazebo is a leading open source robotics simulator, that /// provides high fidelity physics, rendering, and sensor simulation. - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_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. diff --git a/include/gz/sim/EntityComponentManager.hh b/include/gz/sim/EntityComponentManager.hh index 2717264da9..65fce6fb7b 100644 --- a/include/gz/sim/EntityComponentManager.hh +++ b/include/gz/sim/EntityComponentManager.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_ENTITYCOMPONENTMANAGER_HH_ -#define GZ_GAZEBO_ENTITYCOMPONENTMANAGER_HH_ +#ifndef GZ_SIM_ENTITYCOMPONENTMANAGER_HH_ +#define GZ_SIM_ENTITYCOMPONENTMANAGER_HH_ #include #include @@ -41,14 +41,14 @@ #include "gz/sim/components/Component.hh" #include "gz/sim/detail/View.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { // Forward declarations. - class IGNITION_GAZEBO_HIDDEN EntityComponentManagerPrivate; + class GZ_GAZEBO_HIDDEN EntityComponentManagerPrivate; class EntityComponentManagerDiff; /// \brief Type alias for the graph that holds entities. @@ -64,7 +64,7 @@ namespace ignition /// components and entities. /// A component can be of any class which inherits from /// `components::BaseComponent`. - class IGNITION_GAZEBO_VISIBLE EntityComponentManager + class GZ_GAZEBO_VISIBLE EntityComponentManager { /// \brief Constructor public: EntityComponentManager(); @@ -128,7 +128,7 @@ namespace ignition /// update step. /// /// \details It is recommended that systems don't call this function - /// directly, and instead use the `gazebo::SdfEntityCreator` class to + /// directly, and instead use the `sim::SdfEntityCreator` class to /// remove entities. /// /// \param[in] _entity Entity to be removed. @@ -187,7 +187,7 @@ namespace ignition /// \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 + /// 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 @@ -205,7 +205,7 @@ namespace ignition /// \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 IGN_DEPRECATED(6) EntityHasComponent(const Entity _entity, + public: bool GZ_DEPRECATED(6) EntityHasComponent(const Entity _entity, const ComponentKey &_key) const; /// \brief Check whether an entity has a specific component type. @@ -228,7 +228,7 @@ namespace ignition /// \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 IGN_DEPRECATED(6) RemoveComponent( + public: bool GZ_DEPRECATED(6) RemoveComponent( const Entity _entity, const ComponentKey &_key); /// \brief Remove a component from an entity based on a type id. @@ -285,7 +285,7 @@ namespace ignition /// \return The component associated with the key, or nullptr if the /// component could not be found. public: template - const ComponentTypeT IGN_DEPRECATED(6) * Component( + const ComponentTypeT GZ_DEPRECATED(6) * Component( const ComponentKey &_key) const; /// \brief Get a mutable component based on a key. @@ -293,7 +293,7 @@ namespace ignition /// \return The component associated with the key, or nullptr if the /// component could not be found. public: template - ComponentTypeT IGN_DEPRECATED(6) * Component( + ComponentTypeT GZ_DEPRECATED(6) * Component( const ComponentKey &_key); /// \brief Get a mutable component assigned to an entity based on a @@ -345,13 +345,13 @@ namespace ignition /// This function is now deprecated, and will always return nullptr. /// \return nullptr. public: template - const ComponentTypeT IGN_DEPRECATED(6) * First() const; + const ComponentTypeT GZ_DEPRECATED(6) * First() const; /// \brief The first component instance of the specified type. /// This function is now deprecated, and will always return nullptr. /// \return nullptr. public: template - ComponentTypeT IGN_DEPRECATED(6) * First(); + ComponentTypeT GZ_DEPRECATED(6) * First(); /// \brief Get an entity which matches the value of all the given /// components. For example, the following will return the entity which @@ -663,13 +663,13 @@ namespace ignition /// \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); + 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: gazebo::ComponentState ComponentState(const Entity _entity, + public: sim::ComponentState ComponentState(const Entity _entity, const ComponentTypeId _typeId) const; /// \brief All future entities will have an id that starts at _offset. diff --git a/include/gz/sim/EventManager.hh b/include/gz/sim/EventManager.hh index c6484d2247..f88e82f7f3 100644 --- a/include/gz/sim/EventManager.hh +++ b/include/gz/sim/EventManager.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_EVENTMANAGER_HH_ -#define GZ_GAZEBO_EVENTMANAGER_HH_ +#ifndef GZ_SIM_EVENTMANAGER_HH_ +#define GZ_SIM_EVENTMANAGER_HH_ #include #include @@ -30,14 +30,14 @@ #include #include -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { // Forward declarations. - class IGNITION_GAZEBO_HIDDEN EventManagerPrivate; + class GZ_GAZEBO_HIDDEN EventManagerPrivate; /// \brief The EventManager is used to send/receive notifications of /// simulator events. @@ -46,7 +46,7 @@ namespace ignition /// 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. + /// See \ref gz::sim::events for a complete list of events. /// TODO: if visibility is added here the MSVC is unable to compile it. /// The use of smart pointer inside the unordered_map (events method) is @@ -65,7 +65,7 @@ namespace ignition /// \return A Connection pointer, which will automatically call /// Disconnect when it goes out of scope. public: template - ignition::common::ConnectionPtr + gz::common::ConnectionPtr Connect(const typename E::CallbackT &_subscriber) { if (this->events.find(typeid(E)) == this->events.end()) { @@ -81,7 +81,7 @@ namespace ignition } else { - ignerr << "Failed to connect event: " + gzerr << "Failed to connect event: " << typeid(E).name() << std::endl; return nullptr; } @@ -113,7 +113,7 @@ namespace ignition } else { - ignerr << "Failed to signal event: " + gzerr << "Failed to signal event: " << typeid(E).name() << std::endl; } } @@ -142,11 +142,11 @@ namespace ignition /// \brief Container of used signals. private: std::unordered_map, + std::unique_ptr, Hasher, EqualTo> events; }; } } } -#endif // GZ_GAZEBO_EVENTMANAGER_HH_ +#endif // GZ_SIM_EVENTMANAGER_HH_ diff --git a/include/gz/sim/Events.hh b/include/gz/sim/Events.hh index bc4df20744..a7337e84d1 100644 --- a/include/gz/sim/Events.hh +++ b/include/gz/sim/Events.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_EVENTS_HH_ -#define GZ_GAZEBO_EVENTS_HH_ +#ifndef GZ_SIM_EVENTS_HH_ +#define GZ_SIM_EVENTS_HH_ #include @@ -24,12 +24,12 @@ #include "gz/sim/config.hh" #include "gz/sim/Entity.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { /// \brief Namespace for all events. Refer to the EventManager class for /// more information about events. namespace events @@ -40,18 +40,18 @@ namespace ignition /// /// For example, to pause simulation use: /// \code - /// eventManager.Emit(true); + /// eventManager.Emit(true); /// \endcode - using Pause = ignition::common::EventT; + 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(); + /// eventManager.Emit(); /// \endcode - using Stop = ignition::common::EventT; + 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 @@ -60,7 +60,7 @@ namespace ignition struct LoadPluginsTag>; } } // namespace events - } // namespace gazebo -} // namespace ignition + } // namespace sim +} // namespace gz -#endif // GZ_GAZEBO_EVENTS_HH_ +#endif // GZ_SIM_EVENTS_HH_ diff --git a/include/gz/sim/Link.hh b/include/gz/sim/Link.hh index 1c53b55503..7b84e784ec 100644 --- a/include/gz/sim/Link.hh +++ b/include/gz/sim/Link.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_LINK_HH_ -#define GZ_GAZEBO_LINK_HH_ +#ifndef GZ_SIM_LINK_HH_ +#define GZ_SIM_LINK_HH_ #include #include @@ -32,14 +32,14 @@ #include #include -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { // Forward declarations. - class IGNITION_GAZEBO_HIDDEN LinkPrivate; + class GZ_GAZEBO_HIDDEN LinkPrivate; // /// \class Link Link.hh gz/sim/Link.hh /// \brief This class provides wrappers around entities and components @@ -60,11 +60,11 @@ namespace ignition /// Link link(entity); /// std::string name = link.Name(ecm); /// - class IGNITION_GAZEBO_VISIBLE Link + class GZ_GAZEBO_VISIBLE Link { /// \brief Constructor /// \param[in] _entity Link entity - public: explicit Link(gazebo::Entity _entity = kNullEntity); + public: explicit Link(sim::Entity _entity = kNullEntity); /// \brief Copy constructor /// \param[in] _link Link to copy. @@ -89,11 +89,11 @@ namespace ignition /// \brief Get the entity which this Link is related to. /// \return Link entity. - public: gazebo::Entity Entity() const; + public: sim::Entity Entity() const; /// \brief Reset Entity to a new one /// \param[in] _newEntity New link entity. - public: void ResetEntity(gazebo::Entity _newEntity); + public: void ResetEntity(sim::Entity _newEntity); /// \brief Check whether this link correctly refers to an entity that /// has a components::Link. @@ -130,7 +130,7 @@ namespace ignition /// \param[in] _ecm Entity-component manager. /// \param[in] _name Collision name. /// \return Collision entity. - public: gazebo::Entity CollisionByName(const EntityComponentManager &_ecm, + public: 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 @@ -138,19 +138,19 @@ namespace ignition /// \param[in] _ecm Entity-component manager. /// \param[in] _name Visual name. /// \return Visual entity. - public: gazebo::Entity VisualByName(const EntityComponentManager &_ecm, + public: 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( + 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( + public: std::vector Visuals( const EntityComponentManager &_ecm) const; /// \brief Get the number of collisions which are immediate children of diff --git a/include/gz/sim/Model.hh b/include/gz/sim/Model.hh index c8a3ff4cf7..7e13c74675 100644 --- a/include/gz/sim/Model.hh +++ b/include/gz/sim/Model.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_MODEL_HH_ -#define GZ_GAZEBO_MODEL_HH_ +#ifndef GZ_SIM_MODEL_HH_ +#define GZ_SIM_MODEL_HH_ #include #include @@ -28,14 +28,14 @@ #include #include -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { // Forward declarations. - class IGNITION_GAZEBO_HIDDEN ModelPrivate; + class GZ_GAZEBO_HIDDEN ModelPrivate; // /// \class Model Model.hh gz/sim/Model.hh /// \brief This class provides wrappers around entities and components @@ -57,10 +57,10 @@ namespace ignition /// std::string name = model.Name(ecm); /// /// \todo(louise) Store the ecm instead of passing it at every API call. - class IGNITION_GAZEBO_VISIBLE Model { + class GZ_GAZEBO_VISIBLE Model { /// \brief Constructor /// \param[in] _entity Model entity - public: explicit Model(gazebo::Entity _entity = kNullEntity); + public: explicit Model(sim::Entity _entity = kNullEntity); /// \brief Copy constructor /// \param[in] _model Model to copy. @@ -85,7 +85,7 @@ namespace ignition /// \brief Get the entity which this Model is related to. /// \return Model entity. - public: gazebo::Entity Entity() const; + public: sim::Entity Entity() const; /// \brief Check whether this model correctly refers to an entity that /// has a components::Model. @@ -127,7 +127,7 @@ namespace ignition /// \param[in] _name Joint name. /// \return Joint entity. /// \todo(anyone) Make const - public: gazebo::Entity JointByName(const EntityComponentManager &_ecm, + public: sim::Entity JointByName(const EntityComponentManager &_ecm, const std::string &_name); /// \brief Get the ID of a link entity which is an immediate child of @@ -136,25 +136,25 @@ namespace ignition /// \param[in] _name Link name. /// \return Link entity. /// \todo(anyone) Make const - public: gazebo::Entity LinkByName(const EntityComponentManager &_ecm, + public: 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( + 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( + public: std::vector Links( const EntityComponentManager &_ecm) const; /// \brief Get all models which are immediate children of this model. /// \param[in] _ecm Entity-component manager. /// \return All models in this model. - public: std::vector Models( + public: std::vector Models( const EntityComponentManager &_ecm) const; /// \brief Get the number of joints which are immediate children of this diff --git a/include/gz/sim/Primitives.hh b/include/gz/sim/Primitives.hh index 3f2f950a49..01b12a5d13 100644 --- a/include/gz/sim/Primitives.hh +++ b/include/gz/sim/Primitives.hh @@ -15,23 +15,23 @@ * */ -#ifndef GZ_GAZEBO_PRIMITIVES_HH_ -#define GZ_GAZEBO_PRIMITIVES_HH_ +#ifndef GZ_SIM_PRIMITIVES_HH_ +#define GZ_SIM_PRIMITIVES_HH_ #include #include #include -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { /// \brief Enumeration of available primitive shape types - enum class IGNITION_GAZEBO_VISIBLE PrimitiveShape + enum class GZ_GAZEBO_VISIBLE PrimitiveShape { kBox, kCapsule, @@ -41,7 +41,7 @@ namespace ignition }; /// \brief Enumeration of available primitive light types - enum class IGNITION_GAZEBO_VISIBLE PrimitiveLight + enum class GZ_GAZEBO_VISIBLE PrimitiveLight { kDirectional, kPoint, @@ -53,7 +53,7 @@ namespace ignition /// \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 + std::string GZ_GAZEBO_VISIBLE getPrimitiveShape(const PrimitiveShape &_type); /// \brief Return an SDF string of one of the available primitive @@ -61,7 +61,7 @@ namespace ignition /// \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 + std::string GZ_GAZEBO_VISIBLE getPrimitiveLight(const PrimitiveLight &_type); /// \brief Return an SDF string of one of the available primitive shape or @@ -71,13 +71,13 @@ namespace ignition /// 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 + std::string GZ_GAZEBO_VISIBLE getPrimitive(const std::string &_typeName); } - } // namespace gazebo -} // namespace ignition + } // namespace sim +} // namespace gz -#endif // GZ_GAZEBO_PRIMITIVES_HH_ +#endif // GZ_SIM_PRIMITIVES_HH_ diff --git a/include/gz/sim/SdfEntityCreator.hh b/include/gz/sim/SdfEntityCreator.hh index 641aa5e127..83ed1f7f30 100644 --- a/include/gz/sim/SdfEntityCreator.hh +++ b/include/gz/sim/SdfEntityCreator.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_CREATEREMOVE_HH_ -#define GZ_GAZEBO_CREATEREMOVE_HH_ +#ifndef GZ_SIM_CREATEREMOVE_HH_ +#define GZ_SIM_CREATEREMOVE_HH_ #include @@ -37,12 +37,12 @@ #include #include -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { // Forward declarations. class SdfEntityCreatorPrivate; // @@ -55,7 +55,7 @@ namespace ignition /// 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 + class GZ_GAZEBO_VISIBLE SdfEntityCreator { /// \brief Constructor /// \param[in] _ecm Entity component manager. This class keeps a pointer diff --git a/include/gz/sim/Server.hh b/include/gz/sim/Server.hh index d29e9b08e5..6803210218 100644 --- a/include/gz/sim/Server.hh +++ b/include/gz/sim/Server.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_SERVER_HH_ -#define GZ_GAZEBO_SERVER_HH_ +#ifndef GZ_SIM_SERVER_HH_ +#define GZ_SIM_SERVER_HH_ #include #include @@ -27,12 +27,12 @@ #include #include -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { // Forware declarations class ServerPrivate; @@ -44,7 +44,7 @@ namespace ignition /// A basic simulation server can be instantiated and run using /// /// ``` - /// ignition::gazebo::Server server; + /// gz::sim::Server server; /// server.Run(); /// ``` /// @@ -53,9 +53,9 @@ namespace ignition /// elements contained in the file. /// /// ``` - /// ignition::gazebo::ServerConfig config; + /// gz::sim::ServerConfig config; /// config.SetSdfFile("path_to_file.sdf"); - /// ignition::gazebo::Server server(config); + /// gz::sim::Server server(config); /// server.Run(); /// ``` /// @@ -80,17 +80,17 @@ namespace ignition /// /// List syntax: *service_name(request_msg_type) : response_msg_type* /// - /// 1. `/world//scene/info(none)` : ignition::msgs::Scene + /// 1. `/world//scene/info(none)` : gz::msgs::Scene /// + Returns the current scene information. /// - /// 2. `/gazebo/resource_paths/get` : ignition::msgs::StringMsg_V + /// 2. `/gazebo/resource_paths/get` : gz::msgs::StringMsg_V /// + Get list of resource paths. /// - /// 3. `/gazebo/resource_paths/add` : ignition::msgs::Empty + /// 3. `/gazebo/resource_paths/add` : gz::msgs::Empty /// + Add new resource paths. /// - /// 4. `/server_control`(ignition::msgs::ServerControl) : - /// ignition::msgs::Boolean + /// 4. `/server_control`(gz::msgs::ServerControl) : + /// gz::msgs::Boolean /// + Control the simulation server. /// /// ## Topics @@ -101,15 +101,15 @@ namespace ignition /// /// List syntax: *topic_name : published_msg_type* /// - /// 1. `/world//clock` : ignition::msgs::Clock + /// 1. `/world//clock` : gz::msgs::Clock /// - /// 2. `/world//stats` : ignition::msgs::WorldStatistics + /// 2. `/world//stats` : gz::msgs::WorldStatistics /// + This topic is throttled to 5Hz. /// - /// 3. `/gazebo/resource_paths` : ignition::msgs::StringMsg_V + /// 3. `/gazebo/resource_paths` : gz::msgs::StringMsg_V /// + Updated list of resource paths. /// - class IGNITION_GAZEBO_VISIBLE Server + class GZ_GAZEBO_VISIBLE Server { /// \brief Construct the server using the parameters specified in a /// ServerConfig. diff --git a/include/gz/sim/ServerConfig.hh b/include/gz/sim/ServerConfig.hh index 90fad6b5d5..6ec0cd844e 100644 --- a/include/gz/sim/ServerConfig.hh +++ b/include/gz/sim/ServerConfig.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_SERVERCONFIG_HH_ -#define GZ_GAZEBO_SERVERCONFIG_HH_ +#ifndef GZ_SIM_SERVERCONFIG_HH_ +#define GZ_SIM_SERVERCONFIG_HH_ #include #include @@ -28,12 +28,12 @@ #include #include -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { // Forward declarations. class ServerConfigPrivate; @@ -41,7 +41,7 @@ namespace ignition /// \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 GZ_GAZEBO_VISIBLE ServerConfig { /// \brief Type of SDF source. public: enum class SourceType @@ -67,7 +67,7 @@ namespace ignition /// 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 + public: class GZ_GAZEBO_VISIBLE PluginInfo { /// \brief Default constructor. public: PluginInfo(); @@ -424,14 +424,14 @@ namespace ignition /// \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 + GZ_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 + GZ_GAZEBO_VISIBLE parsePluginsFromString(const std::string &_str); /// \brief Load plugin information, following ordering. @@ -456,7 +456,7 @@ namespace ignition // /// \return A list of plugins to load, based on above ordering std::list - IGNITION_GAZEBO_VISIBLE + GZ_GAZEBO_VISIBLE loadPluginInfo(bool _isPlayback = false); } } diff --git a/include/gz/sim/System.hh b/include/gz/sim/System.hh index 45fbb2ecde..042b062730 100644 --- a/include/gz/sim/System.hh +++ b/include/gz/sim/System.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_SYSTEM_HH_ -#define GZ_GAZEBO_SYSTEM_HH_ +#ifndef GZ_SIM_SYSTEM_HH_ +#define GZ_SIM_SYSTEM_HH_ #include @@ -27,12 +27,12 @@ #include -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { /// \brief Namespace for all System plugins. Refer to the System class for /// more information about systems. namespace systems {} diff --git a/include/gz/sim/SystemLoader.hh b/include/gz/sim/SystemLoader.hh index c44cac1367..2564e32574 100644 --- a/include/gz/sim/SystemLoader.hh +++ b/include/gz/sim/SystemLoader.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_SYSTEMLOADER_HH_ -#define GZ_GAZEBO_SYSTEMLOADER_HH_ +#ifndef GZ_SIM_SYSTEMLOADER_HH_ +#define GZ_SIM_SYSTEMLOADER_HH_ #include #include @@ -27,18 +27,18 @@ #include #include -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { // Forward declarations. - class IGNITION_GAZEBO_HIDDEN SystemLoaderPrivate; + class GZ_GAZEBO_HIDDEN SystemLoaderPrivate; /// \class SystemLoader SystemLoader.hh gz/sim/SystemLoader.hh /// \brief Class for loading/unloading System plugins. - class IGNITION_GAZEBO_VISIBLE SystemLoader + class GZ_GAZEBO_VISIBLE SystemLoader { /// \brief Constructor public: explicit SystemLoader(); @@ -77,5 +77,5 @@ namespace ignition using SystemLoaderPtr = std::shared_ptr; } } -#endif // GZ_GAZEBO_SYSTEMLOADER_HH_ +#endif // GZ_SIM_SYSTEMLOADER_HH_ diff --git a/include/gz/sim/SystemPluginPtr.hh b/include/gz/sim/SystemPluginPtr.hh index b90b5002b8..f99e0e2b71 100644 --- a/include/gz/sim/SystemPluginPtr.hh +++ b/include/gz/sim/SystemPluginPtr.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_SYSTEMPLUGINPTR_HH_ -#define GZ_GAZEBO_SYSTEMPLUGINPTR_HH_ +#ifndef GZ_SIM_SYSTEMPLUGINPTR_HH_ +#define GZ_SIM_SYSTEMPLUGINPTR_HH_ #include #include -namespace ignition +namespace gz { - namespace gazebo + namespace sim { - using SystemPluginPtr = ignition::plugin::SpecializedPluginPtr< + using SystemPluginPtr = gz::plugin::SpecializedPluginPtr< System, ISystemConfigure, ISystemPreUpdate, diff --git a/include/gz/sim/TestFixture.hh b/include/gz/sim/TestFixture.hh index a0c758fa4e..52c925eaff 100644 --- a/include/gz/sim/TestFixture.hh +++ b/include/gz/sim/TestFixture.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_TESTFIXTURE_HH_ -#define GZ_GAZEBO_TESTFIXTURE_HH_ +#ifndef GZ_SIM_TESTFIXTURE_HH_ +#define GZ_SIM_TESTFIXTURE_HH_ #include #include @@ -25,25 +25,25 @@ #include "gz/sim/Server.hh" #include "gz/sim/ServerConfig.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { // -class IGNITION_GAZEBO_HIDDEN TestFixturePrivate; +class GZ_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"); +/// gz::sim::TestFixture fixture("path_to.sdf"); /// /// // Register callbacks, for example: -/// fixture.OnPostUpdate([&](const gazebo::UpdateInfo &, -/// const gazebo::EntityComponentManager &_ecm) +/// fixture.OnPostUpdate([&](const sim::UpdateInfo &, +/// const sim::EntityComponentManager &_ecm) /// { /// // Add expectations here /// }).Finalize(); @@ -52,7 +52,7 @@ class IGNITION_GAZEBO_HIDDEN TestFixturePrivate; /// // Run the server /// fixture.Server()->Run(true, 1000, false); /// -class IGNITION_GAZEBO_VISIBLE TestFixture +class GZ_GAZEBO_VISIBLE TestFixture { /// \brief Constructor /// \param[in] _path Path to SDF file. @@ -100,7 +100,7 @@ class IGNITION_GAZEBO_VISIBLE TestFixture public: TestFixture &Finalize(); /// \brief Get pointer to underlying server. - public: std::shared_ptr Server() const; + public: std::shared_ptr Server() const; /// \internal /// \brief Pointer to private data. diff --git a/include/gz/sim/Types.hh b/include/gz/sim/Types.hh index 0080e46905..869de5425f 100644 --- a/include/gz/sim/Types.hh +++ b/include/gz/sim/Types.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_TYPES_HH_ -#define GZ_GAZEBO_TYPES_HH_ +#ifndef GZ_SIM_TYPES_HH_ +#define GZ_SIM_TYPES_HH_ #include #include @@ -24,12 +24,12 @@ #include "gz/sim/Entity.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { // Forward declarations. class EntityComponentManager; @@ -86,7 +86,7 @@ namespace ignition /// \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`. + /// 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 diff --git a/include/gz/sim/Util.hh b/include/gz/sim/Util.hh index e718b6b575..79d4d42c61 100644 --- a/include/gz/sim/Util.hh +++ b/include/gz/sim/Util.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_UTIL_HH_ -#define GZ_GAZEBO_UTIL_HH_ +#ifndef GZ_SIM_UTIL_HH_ +#define GZ_SIM_UTIL_HH_ #include #include @@ -28,18 +28,18 @@ #include "gz/sim/Export.hh" #include "gz/sim/Types.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_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, + math::Pose3d GZ_GAZEBO_VISIBLE worldPose(const Entity &_entity, const EntityComponentManager &_ecm); /// \brief Helper function to generate scoped name for an entity. @@ -48,7 +48,7 @@ namespace ignition /// \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, + std::string GZ_GAZEBO_VISIBLE scopedName(const Entity &_entity, const EntityComponentManager &_ecm, const std::string &_delim = "/", bool _includePrefix = true); @@ -75,7 +75,7 @@ namespace ignition /// 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( + std::unordered_set GZ_GAZEBO_VISIBLE entitiesFromScopedName( const std::string &_scopedName, const EntityComponentManager &_ecm, Entity _relativeTo = kNullEntity, const std::string &_delim = "::"); @@ -83,16 +83,16 @@ namespace ignition /// \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`. + /// 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: /// - /// `gazebo::components::Model::typeId == entityTypeId(entity, ecm)` + /// `sim::components::Model::typeId == entityTypeId(entity, ecm)` /// /// In case the entity isn't of any known type, this will return - /// `ignition::gazebo::kComponentTypeIdInvalid`. + /// `gz::sim::kComponentTypeIdInvalid`. /// /// In case the entity has more than one type, only one of them will be /// returned. This is not standard usage. @@ -100,7 +100,7 @@ namespace ignition /// \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, + ComponentTypeId GZ_GAZEBO_VISIBLE entityTypeId(const Entity &_entity, const EntityComponentManager &_ecm); /// \brief Generally, each entity will be of some specific high-level type, @@ -120,20 +120,20 @@ namespace ignition /// \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, + std::string GZ_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, + Entity GZ_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( + Entity GZ_GAZEBO_VISIBLE worldEntity( const EntityComponentManager &_ecm); /// \brief Helper function to remove a parent scope from a given name. @@ -141,7 +141,7 @@ namespace ignition /// \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( + std::string GZ_GAZEBO_VISIBLE removeParentScope( const std::string &_name, const std::string &_delim); /// \brief Combine a URI and a file path into a full path. @@ -152,18 +152,18 @@ namespace ignition /// 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, + std::string GZ_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(); + std::vector GZ_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( + void GZ_GAZEBO_VISIBLE addResourcePaths( const std::vector &_paths = {}); /// \brief Get the top level model of an entity @@ -171,7 +171,7 @@ namespace ignition /// \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( + gz::sim::Entity GZ_GAZEBO_VISIBLE topLevelModel( const Entity &_entity, const EntityComponentManager &_ecm); @@ -187,10 +187,10 @@ namespace ignition /// 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( + std::string GZ_GAZEBO_VISIBLE validTopic( const std::vector &_topics); - /// \brief Helper function that returns a valid Ignition Transport topic + /// \brief Helper function that returns a valid Gazebo Transport topic /// consisting of the scoped name for the provided entity. /// /// For example, if the provided entity has a scoped name of @@ -202,10 +202,10 @@ namespace ignition /// \param[in] _entity The entity to generate the topic name for. /// \param[in] _ecm The entity component manager. /// \param[in] _excludeWorld True to exclude the world name from the topic. - /// \return An Ignition Transport topic name based on the scoped name of + /// \return A Gazebo Transport topic name based on the scoped name of /// the provided entity, or empty string if a topic name could not be /// generated. - std::string IGNITION_GAZEBO_VISIBLE topicFromScopedName( + std::string GZ_GAZEBO_VISIBLE topicFromScopedName( const Entity &_entity, const EntityComponentManager &_ecm, bool _excludeWorld = true); @@ -225,7 +225,7 @@ namespace ignition /// known. /// \return Full path to the SDF world file. An empty string is returned /// if the file could not be found. - std::string IGNITION_GAZEBO_VISIBLE resolveSdfWorldFile( + std::string GZ_GAZEBO_VISIBLE resolveSdfWorldFile( const std::string &_sdfFilename, const std::string &_fuelResourceCache = ""); @@ -263,7 +263,7 @@ namespace ignition /// \return The entity's latitude (deg), longitude (deg) and elevation (m). /// If the entity doesn't have a pose, or the world's spherical coordinates /// haven't been defined, this will return nullopt. - std::optional IGNITION_GAZEBO_VISIBLE sphericalCoordinates( + std::optional GZ_GAZEBO_VISIBLE sphericalCoordinates( Entity _entity, const EntityComponentManager &_ecm); /// \brief Environment variable holding resource paths. diff --git a/include/gz/sim/World.hh b/include/gz/sim/World.hh index 8de195532d..93d29f26db 100644 --- a/include/gz/sim/World.hh +++ b/include/gz/sim/World.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_WORLD_HH_ -#define GZ_GAZEBO_WORLD_HH_ +#ifndef GZ_SIM_WORLD_HH_ +#define GZ_SIM_WORLD_HH_ #include #include @@ -31,14 +31,14 @@ #include "gz/sim/Export.hh" #include "gz/sim/Types.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { // Forward declarations. - class IGNITION_GAZEBO_HIDDEN WorldPrivate; + class GZ_GAZEBO_HIDDEN WorldPrivate; // /// \class World World.hh gz/sim/World.hh /// \brief This class provides wrappers around entities and components @@ -58,10 +58,10 @@ namespace ignition /// /// World world(entity); /// std::string name = world.Name(ecm); - class IGNITION_GAZEBO_VISIBLE World { + class GZ_GAZEBO_VISIBLE World { /// \brief Constructor /// \param[in] _entity World entity - public: explicit World(gazebo::Entity _entity = kNullEntity); + public: explicit World(sim::Entity _entity = kNullEntity); /// \brief Copy constructor /// \param[in] _world World to copy. @@ -86,7 +86,7 @@ namespace ignition /// \brief Get the entity which this World is related to. /// \return World entity. - public: gazebo::Entity Entity() const; + public: sim::Entity Entity() const; /// \brief Check whether this world correctly refers to an entity that /// has a components::World. @@ -140,7 +140,7 @@ namespace ignition /// \param[in] _ecm Entity-component manager. /// \param[in] _name Light name. /// \return Light entity. - public: gazebo::Entity LightByName(const EntityComponentManager &_ecm, + public: 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 @@ -148,7 +148,7 @@ namespace ignition /// \param[in] _ecm Entity-component manager. /// \param[in] _name Actor name. /// \return Actor entity. - public: gazebo::Entity ActorByName(const EntityComponentManager &_ecm, + public: 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 @@ -156,25 +156,25 @@ namespace ignition /// \param[in] _ecm Entity-component manager. /// \param[in] _name Model name. /// \return Model entity. - public: gazebo::Entity ModelByName(const EntityComponentManager &_ecm, + public: 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( + 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( + 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( + public: std::vector Models( const EntityComponentManager &_ecm) const; /// \brief Get the number of lights which are immediate children of this diff --git a/include/gz/sim/comms/Broker.hh b/include/gz/sim/comms/Broker.hh index f8825a29a6..512e40eaef 100644 --- a/include/gz/sim/comms/Broker.hh +++ b/include/gz/sim/comms/Broker.hh @@ -15,8 +15,8 @@ * */ -#ifndef GZ_GAZEBO_BROKER_HH_ -#define GZ_GAZEBO_BROKER_HH_ +#ifndef GZ_SIM_BROKER_HH_ +#define GZ_SIM_BROKER_HH_ #include @@ -25,7 +25,7 @@ #include "gz/sim/comms/MsgManager.hh" #include "gz/sim/config.hh" -namespace ignition +namespace gz { namespace msgs { @@ -34,10 +34,10 @@ namespace msgs class Dataframe; class StringMsg_V; } -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace comms { // Forward declarations. @@ -75,14 +75,14 @@ namespace comms /// Here's an example: /// + /// name="gz::sim::systems::PerfectComms"> /// /// /broker/inbound /// /broker/bind_address /// /broker/unbind_address /// /// - class IGNITION_GAZEBO_VISIBLE Broker + class GZ_GAZEBO_VISIBLE Broker { /// \brief Constructor. public: Broker(); @@ -114,20 +114,20 @@ namespace comms /// _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); + public: bool OnBind(const gz::msgs::StringMsg_V &_req, + gz::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); + public: void OnUnbind(const gz::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); + public: void OnMsg(const gz::msgs::Dataframe &_msg); /// \brief Process all the messages in the inbound queue and deliver them /// to the destination clients. diff --git a/include/gz/sim/comms/ICommsModel.hh b/include/gz/sim/comms/ICommsModel.hh index add9811a3f..f1199835da 100644 --- a/include/gz/sim/comms/ICommsModel.hh +++ b/include/gz/sim/comms/ICommsModel.hh @@ -15,8 +15,8 @@ * */ -#ifndef GZ_GAZEBO_ICOMMSMODEL_HH_ -#define GZ_GAZEBO_ICOMMSMODEL_HH_ +#ifndef GZ_SIM_ICOMMSMODEL_HH_ +#define GZ_SIM_ICOMMSMODEL_HH_ #include @@ -26,12 +26,12 @@ #include "gz/sim/config.hh" #include "gz/sim/System.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { // Forward declarations class EntityComponentManager; @@ -61,10 +61,10 @@ namespace comms /// /// + /// name="gz::sim::systems::PerfectComms"> /// 1 /// - class IGNITION_GAZEBO_VISIBLE ICommsModel: + class GZ_GAZEBO_VISIBLE ICommsModel: #ifdef _MSC_VER #pragma warning(push) #pragma warning(disable:4275) @@ -87,13 +87,13 @@ namespace comms // 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 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. + /// \param[in] _ecm - Gazebo Sim's ECM. public: virtual void StepImpl(const UpdateInfo &_info, EntityComponentManager &_ecm); @@ -118,7 +118,7 @@ namespace comms /// \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. + /// \param[in] _ecm - Gazebo Sim's ECM. public: virtual void Step(const UpdateInfo &_info, const Registry &_currentRegistry, Registry &_newRegistry, diff --git a/include/gz/sim/comms/MsgManager.hh b/include/gz/sim/comms/MsgManager.hh index 8b50a33f06..da29e56c6a 100644 --- a/include/gz/sim/comms/MsgManager.hh +++ b/include/gz/sim/comms/MsgManager.hh @@ -15,8 +15,8 @@ * */ -#ifndef GZ_GAZEBO_MSGMANAGER_HH_ -#define GZ_GAZEBO_MSGMANAGER_HH_ +#ifndef GZ_SIM_MSGMANAGER_HH_ +#define GZ_SIM_MSGMANAGER_HH_ #include #include @@ -29,17 +29,17 @@ #include "gz/sim/Entity.hh" #include "gz/sim/System.hh" -namespace ignition +namespace gz { namespace msgs { // Forward declarations. class Dataframe; } -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace comms { @@ -67,7 +67,7 @@ struct AddressContent public: std::string modelName; /// \brief Entity of the model associated to this address. - public: gazebo::Entity entity; + public: sim::Entity entity; }; /// \brief A map where the key is an address and the value is all the @@ -75,7 +75,7 @@ struct AddressContent using Registry = std::unordered_map; /// \brief Class to handle messages and subscriptions. -class IGNITION_GAZEBO_VISIBLE MsgManager +class GZ_GAZEBO_VISIBLE MsgManager { /// \brief Default constructor. public: MsgManager(); diff --git a/include/gz/sim/components/Actor.hh b/include/gz/sim/components/Actor.hh index 056a38d0fb..f4176efc10 100644 --- a/include/gz/sim/components/Actor.hh +++ b/include/gz/sim/components/Actor.hh @@ -31,12 +31,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace serializers { using ActorSerializer = diff --git a/include/gz/sim/components/Actuators.hh b/include/gz/sim/components/Actuators.hh index dd719f8507..572f02bfc3 100644 --- a/include/gz/sim/components/Actuators.hh +++ b/include/gz/sim/components/Actuators.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains a msgs::Actuators message. This is diff --git a/include/gz/sim/components/AirPressureSensor.hh b/include/gz/sim/components/AirPressureSensor.hh index bd5619dcb5..c8b730e9ea 100644 --- a/include/gz/sim/components/AirPressureSensor.hh +++ b/include/gz/sim/components/AirPressureSensor.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains an air pressure sensor, diff --git a/include/gz/sim/components/Altimeter.hh b/include/gz/sim/components/Altimeter.hh index 453262e65a..0e04093a77 100644 --- a/include/gz/sim/components/Altimeter.hh +++ b/include/gz/sim/components/Altimeter.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains an altimeter sensor, diff --git a/include/gz/sim/components/AngularAcceleration.hh b/include/gz/sim/components/AngularAcceleration.hh index 7f736203c2..f229ce09fa 100644 --- a/include/gz/sim/components/AngularAcceleration.hh +++ b/include/gz/sim/components/AngularAcceleration.hh @@ -25,23 +25,23 @@ #include #include "gz/sim/components/Component.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains angular acceleration of an entity - /// represented by ignition::math::Vector3d. + /// represented by gz::math::Vector3d. using AngularAcceleration = Component; IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.AngularAcceleration", AngularAcceleration) /// \brief A component type that contains angular acceleration of an entity in - /// the world frame represented by ignition::math::Vector3d. + /// the world frame represented by gz::math::Vector3d. using WorldAngularAcceleration = Component; IGN_GAZEBO_REGISTER_COMPONENT( diff --git a/include/gz/sim/components/AngularVelocity.hh b/include/gz/sim/components/AngularVelocity.hh index 05fab4422d..1283dd8d10 100644 --- a/include/gz/sim/components/AngularVelocity.hh +++ b/include/gz/sim/components/AngularVelocity.hh @@ -25,23 +25,23 @@ #include #include "gz/sim/components/Component.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains angular velocity of an entity - /// represented by ignition::math::Vector3d. + /// represented by gz::math::Vector3d. using AngularVelocity = Component; IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.AngularVelocity", AngularVelocity) /// \brief A component type that contains angular velocity of an entity in the - /// world frame represented by ignition::math::Vector3d. + /// world frame represented by gz::math::Vector3d. using WorldAngularVelocity = Component; IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.WorldAngularVelocity", diff --git a/include/gz/sim/components/AngularVelocityCmd.hh b/include/gz/sim/components/AngularVelocityCmd.hh index 1e6e4eb5de..8e7733c20a 100644 --- a/include/gz/sim/components/AngularVelocityCmd.hh +++ b/include/gz/sim/components/AngularVelocityCmd.hh @@ -24,23 +24,23 @@ #include #include "gz/sim/components/Component.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_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. + /// an entity, in its own frame, represented by gz::math::Vector3d. using AngularVelocityCmd = Component; IGN_GAZEBO_REGISTER_COMPONENT( "gz_sim_components.AngularVelocityCmd", AngularVelocityCmd) /// \brief A component type that contains the commanded angular velocity - /// of an entity in the world frame represented by ignition::math::Vector3d. + /// of an entity in the world frame represented by gz::math::Vector3d. using WorldAngularVelocityCmd = Component; IGN_GAZEBO_REGISTER_COMPONENT( diff --git a/include/gz/sim/components/Atmosphere.hh b/include/gz/sim/components/Atmosphere.hh index 7af0fdbe85..1374452c14 100644 --- a/include/gz/sim/components/Atmosphere.hh +++ b/include/gz/sim/components/Atmosphere.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace serializers { using AtmosphereSerializer = diff --git a/include/gz/sim/components/AxisAlignedBox.hh b/include/gz/sim/components/AxisAlignedBox.hh index cf61b6f22d..50c3146016 100644 --- a/include/gz/sim/components/AxisAlignedBox.hh +++ b/include/gz/sim/components/AxisAlignedBox.hh @@ -25,12 +25,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace serializers { using AxisAlignedBoxSerializer = @@ -41,9 +41,9 @@ namespace serializers namespace components { /// \brief A component type that contains axis aligned box, - /// ignition::math::AxisAlignedBox, information. + /// gz::math::AxisAlignedBox, information. /// The axis aligned box is created from collisions in the entity - using AxisAlignedBox = Component; IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.AxisAlignedBox", AxisAlignedBox) diff --git a/include/gz/sim/components/BatterySoC.hh b/include/gz/sim/components/BatterySoC.hh index c8efdf4455..be95bfef3b 100644 --- a/include/gz/sim/components/BatterySoC.hh +++ b/include/gz/sim/components/BatterySoC.hh @@ -21,12 +21,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// A component that identifies an entity as being a battery. diff --git a/include/gz/sim/components/Camera.hh b/include/gz/sim/components/Camera.hh index f8d22a7af1..bcc40ef8c1 100644 --- a/include/gz/sim/components/Camera.hh +++ b/include/gz/sim/components/Camera.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains a camera sensor, diff --git a/include/gz/sim/components/CanonicalLink.hh b/include/gz/sim/components/CanonicalLink.hh index 0087ad6ca1..a2293e0571 100644 --- a/include/gz/sim/components/CanonicalLink.hh +++ b/include/gz/sim/components/CanonicalLink.hh @@ -22,12 +22,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component that identifies an entity as being a canonical link. diff --git a/include/gz/sim/components/CastShadows.hh b/include/gz/sim/components/CastShadows.hh index 5d9a0a48ae..99f0f82930 100644 --- a/include/gz/sim/components/CastShadows.hh +++ b/include/gz/sim/components/CastShadows.hh @@ -21,12 +21,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component used to indicate that an entity casts shadows diff --git a/include/gz/sim/components/CenterOfVolume.hh b/include/gz/sim/components/CenterOfVolume.hh index 92770e6402..4a9653ebab 100644 --- a/include/gz/sim/components/CenterOfVolume.hh +++ b/include/gz/sim/components/CenterOfVolume.hh @@ -22,12 +22,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component for an entity's center of volume. Units are in meters. diff --git a/include/gz/sim/components/ChildLinkName.hh b/include/gz/sim/components/ChildLinkName.hh index b099140b96..9fad777c92 100644 --- a/include/gz/sim/components/ChildLinkName.hh +++ b/include/gz/sim/components/ChildLinkName.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component used to indicate that a model is childlinkname (i.e. diff --git a/include/gz/sim/components/Collision.hh b/include/gz/sim/components/Collision.hh index f38cd1e355..4a7335d4e4 100644 --- a/include/gz/sim/components/Collision.hh +++ b/include/gz/sim/components/Collision.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace serializers { using CollisionElementSerializer = diff --git a/include/gz/sim/components/Component.hh b/include/gz/sim/components/Component.hh index 2414f4b1c6..48289178fa 100644 --- a/include/gz/sim/components/Component.hh +++ b/include/gz/sim/components/Component.hh @@ -29,13 +29,13 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { -// namespace ignition +// namespace gz // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace traits { /// \brief Helper trait to determine if a type is shared_ptr or not @@ -124,7 +124,7 @@ namespace serializers static bool warned{false}; if (!warned) { - ignwarn << "Trying to serialize component with data type [" + gzwarn << "Trying to serialize component with data type [" << typeid(DataType).name() << "], which doesn't have " << "`operator<<`. Component will not be serialized." << std::endl; @@ -141,7 +141,7 @@ namespace serializers static bool warned{false}; if (!warned) { - ignwarn << "Trying to serialize component with data type [" + gzwarn << "Trying to serialize component with data type [" << typeid(DataType).name() << "], which doesn't have " << "`operator<<`. Component will not be serialized." << std::endl; @@ -169,7 +169,7 @@ namespace serializers static bool warned{false}; if (!warned) { - ignwarn << "Trying to deserialize component with data type [" + gzwarn << "Trying to deserialize component with data type [" << typeid(DataType).name() << "], which doesn't have " << "`operator>>`. Component will not be deserialized." << std::endl; @@ -186,7 +186,7 @@ namespace serializers static bool warned{false}; if (!warned) { - ignwarn << "Trying to deserialize component with data type [" + gzwarn << "Trying to deserialize component with data type [" << typeid(DataType).name() << "], which doesn't have " << "`operator>>`. Component will not be deserialized." << std::endl; @@ -247,7 +247,7 @@ namespace components static bool warned{false}; if (!warned) { - ignwarn << "Trying to serialize component of type [" << this->TypeId() + gzwarn << "Trying to serialize component of type [" << this->TypeId() << "], which hasn't implemented the `Serialize` function. " << "Component will not be serialized." << std::endl; warned = true; @@ -266,7 +266,7 @@ namespace components static bool warned{false}; if (!warned) { - ignwarn << "Trying to deserialize component of type [" + gzwarn << "Trying to deserialize component of type [" << this->TypeId() << "], which hasn't implemented the " << "`Deserialize` function. Component will not be deserialized." << std::endl; diff --git a/include/gz/sim/components/ContactSensor.hh b/include/gz/sim/components/ContactSensor.hh index 0599324456..6822be99c3 100644 --- a/include/gz/sim/components/ContactSensor.hh +++ b/include/gz/sim/components/ContactSensor.hh @@ -22,12 +22,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief TODO(anyone) Substitute with sdf::Contact once that exists? diff --git a/include/gz/sim/components/ContactSensorData.hh b/include/gz/sim/components/ContactSensorData.hh index a3321a4a48..40a6ad598f 100644 --- a/include/gz/sim/components/ContactSensorData.hh +++ b/include/gz/sim/components/ContactSensorData.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains a list of contacts. diff --git a/include/gz/sim/components/CustomSensor.hh b/include/gz/sim/components/CustomSensor.hh index 47e01bb81c..3c2162d052 100644 --- a/include/gz/sim/components/CustomSensor.hh +++ b/include/gz/sim/components/CustomSensor.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains a custom sensor's information. diff --git a/include/gz/sim/components/DepthCamera.hh b/include/gz/sim/components/DepthCamera.hh index e47a6416fb..20e2b67e16 100644 --- a/include/gz/sim/components/DepthCamera.hh +++ b/include/gz/sim/components/DepthCamera.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains a depth camera sensor, diff --git a/include/gz/sim/components/DetachableJoint.hh b/include/gz/sim/components/DetachableJoint.hh index d7c438cfb8..d486f9a523 100644 --- a/include/gz/sim/components/DetachableJoint.hh +++ b/include/gz/sim/components/DetachableJoint.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief Data structure to hold information about the parent and child links diff --git a/include/gz/sim/components/ExternalWorldWrenchCmd.hh b/include/gz/sim/components/ExternalWorldWrenchCmd.hh index 9394e18392..4a3363c4f3 100644 --- a/include/gz/sim/components/ExternalWorldWrenchCmd.hh +++ b/include/gz/sim/components/ExternalWorldWrenchCmd.hh @@ -23,17 +23,17 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_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. + /// 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. diff --git a/include/gz/sim/components/Factory.hh b/include/gz/sim/components/Factory.hh index e7c249d665..722693be8a 100644 --- a/include/gz/sim/components/Factory.hh +++ b/include/gz/sim/components/Factory.hh @@ -32,12 +32,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A base class for an object responsible for creating components. @@ -82,7 +82,7 @@ namespace components class StorageDescriptorBase { /// \brief Constructor - public: IGN_DEPRECATED(6) StorageDescriptorBase() = default; + public: GZ_DEPRECATED(6) StorageDescriptorBase() = default; /// \brief Destructor public: virtual ~StorageDescriptorBase() = default; @@ -99,7 +99,7 @@ namespace components : public StorageDescriptorBase { /// \brief Constructor - public: IGN_DEPRECATED(6) StorageDescriptor() = default; + public: GZ_DEPRECATED(6) StorageDescriptor() = default; /// \brief Create an instance of a storage that holds ComponentTypeT /// components. @@ -112,7 +112,7 @@ namespace components /// \brief A factory that generates a component based on a string type. class Factory - : public ignition::common::SingletonT + : 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. @@ -123,7 +123,7 @@ namespace components /// \tparam ComponentTypeT Type of component to register. /// \deprecated See function that doesn't accept a storage public: template - void IGN_DEPRECATED(6) Register(const std::string &_type, + void GZ_DEPRECATED(6) Register(const std::string &_type, ComponentDescriptorBase *_compDesc, StorageDescriptorBase * /*_storageDesc*/) { @@ -146,7 +146,7 @@ namespace components return; } - 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 @@ -176,7 +176,7 @@ namespace components // This happens at static initialization time, so we can't use common // console std::string debugEnv; - ignition::common::env("IGN_DEBUG_COMPONENT_FACTORY", debugEnv); + gz::common::env("IGN_DEBUG_COMPONENT_FACTORY", debugEnv); if (debugEnv == "true") { std::cout << "Registering [" << ComponentTypeT::typeName << "]" @@ -280,12 +280,12 @@ namespace components if (nullptr == _data) { - ignerr << "Requested to create a new component instance with null " + gzerr << "Requested to create a new component instance with null " << "data." << std::endl; } else if (_type != _data->TypeId()) { - ignerr << "The typeID of _type [" << _type << "] does not match the " + gzerr << "The typeID of _type [" << _type << "] does not match the " << "typeID of _data [" << _data->TypeId() << "]." << std::endl; } else @@ -302,7 +302,7 @@ namespace components /// \param[in] _typeId Type of component which the storage will hold. /// \return Always returns nullptr. /// \deprecated Storages aren't necessary anymore. - public: std::unique_ptr IGN_DEPRECATED(6) NewStorage( + public: std::unique_ptr GZ_DEPRECATED(6) NewStorage( const ComponentTypeId & /*_typeId*/) { return nullptr; @@ -377,9 +377,9 @@ namespace components { \ if (_classname::typeId != 0) \ return; \ - using namespace ignition;\ - using Desc = gazebo::components::ComponentDescriptor<_classname>; \ - gazebo::components::Factory::Instance()->Register<_classname>(\ + using namespace gz;\ + using Desc = sim::components::ComponentDescriptor<_classname>; \ + sim::components::Factory::Instance()->Register<_classname>(\ _compType, new Desc());\ } \ }; \ diff --git a/include/gz/sim/components/ForceTorque.hh b/include/gz/sim/components/ForceTorque.hh index 3b7433101d..344b7cba0a 100644 --- a/include/gz/sim/components/ForceTorque.hh +++ b/include/gz/sim/components/ForceTorque.hh @@ -26,12 +26,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains an FT sensor, diff --git a/include/gz/sim/components/Geometry.hh b/include/gz/sim/components/Geometry.hh index 7bf5cf3fe0..e027e6a400 100644 --- a/include/gz/sim/components/Geometry.hh +++ b/include/gz/sim/components/Geometry.hh @@ -27,12 +27,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace serializers { using GeometrySerializer = diff --git a/include/gz/sim/components/GpuLidar.hh b/include/gz/sim/components/GpuLidar.hh index 007e1e4caf..0e77d27afe 100644 --- a/include/gz/sim/components/GpuLidar.hh +++ b/include/gz/sim/components/GpuLidar.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains a GPU Lidar sensor, diff --git a/include/gz/sim/components/Gravity.hh b/include/gz/sim/components/Gravity.hh index 222339259c..dcc60f0910 100644 --- a/include/gz/sim/components/Gravity.hh +++ b/include/gz/sim/components/Gravity.hh @@ -25,12 +25,12 @@ #include #include "gz/sim/components/Component.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief Store the gravity acceleration. diff --git a/include/gz/sim/components/HaltMotion.hh b/include/gz/sim/components/HaltMotion.hh index 2d2a191bfb..03296cd2f1 100644 --- a/include/gz/sim/components/HaltMotion.hh +++ b/include/gz/sim/components/HaltMotion.hh @@ -21,12 +21,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component used to turn off a model's joint's movement. diff --git a/include/gz/sim/components/Imu.hh b/include/gz/sim/components/Imu.hh index 25474a3d1a..bdcac604f2 100644 --- a/include/gz/sim/components/Imu.hh +++ b/include/gz/sim/components/Imu.hh @@ -26,12 +26,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains an IMU sensor, diff --git a/include/gz/sim/components/Inertial.hh b/include/gz/sim/components/Inertial.hh index df2cba2556..8bbe7353e5 100644 --- a/include/gz/sim/components/Inertial.hh +++ b/include/gz/sim/components/Inertial.hh @@ -25,12 +25,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace serializers { using InertialSerializer = diff --git a/include/gz/sim/components/Joint.hh b/include/gz/sim/components/Joint.hh index 7d87cc9628..d0b76220e7 100644 --- a/include/gz/sim/components/Joint.hh +++ b/include/gz/sim/components/Joint.hh @@ -21,12 +21,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component that identifies an entity as being a joint. diff --git a/include/gz/sim/components/JointAxis.hh b/include/gz/sim/components/JointAxis.hh index a72949dd78..ecaab0baa9 100644 --- a/include/gz/sim/components/JointAxis.hh +++ b/include/gz/sim/components/JointAxis.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace serializers { using JointAxisSerializer = diff --git a/include/gz/sim/components/JointEffortLimitsCmd.hh b/include/gz/sim/components/JointEffortLimitsCmd.hh index 124f3711f6..fb5bfc5410 100644 --- a/include/gz/sim/components/JointEffortLimitsCmd.hh +++ b/include/gz/sim/components/JointEffortLimitsCmd.hh @@ -26,12 +26,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { @@ -44,9 +44,9 @@ namespace components /// 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, + std::vector, class JointEffortLimitsCmdTag, - serializers::VectorSerializer + serializers::VectorSerializer >; IGN_GAZEBO_REGISTER_COMPONENT( diff --git a/include/gz/sim/components/JointForce.hh b/include/gz/sim/components/JointForce.hh index 76074670ea..74e6de9612 100644 --- a/include/gz/sim/components/JointForce.hh +++ b/include/gz/sim/components/JointForce.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief Force applied to a joint in SI units (Nm for revolute, N for diff --git a/include/gz/sim/components/JointForceCmd.hh b/include/gz/sim/components/JointForceCmd.hh index 42afcc9b8f..7178982061 100644 --- a/include/gz/sim/components/JointForceCmd.hh +++ b/include/gz/sim/components/JointForceCmd.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief Commanded joint forces (or torques) to be applied to a joint diff --git a/include/gz/sim/components/JointPosition.hh b/include/gz/sim/components/JointPosition.hh index ae5dd5b79d..90fef6ad77 100644 --- a/include/gz/sim/components/JointPosition.hh +++ b/include/gz/sim/components/JointPosition.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief Joint positions in SI units (rad for revolute, m for prismatic). diff --git a/include/gz/sim/components/JointPositionLimitsCmd.hh b/include/gz/sim/components/JointPositionLimitsCmd.hh index 59d3639050..d11edf9741 100644 --- a/include/gz/sim/components/JointPositionLimitsCmd.hh +++ b/include/gz/sim/components/JointPositionLimitsCmd.hh @@ -26,12 +26,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { @@ -43,9 +43,9 @@ namespace components /// 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, + std::vector, class JointPositionLimitsCmdTag, - serializers::VectorSerializer + serializers::VectorSerializer >; IGN_GAZEBO_REGISTER_COMPONENT( diff --git a/include/gz/sim/components/JointPositionReset.hh b/include/gz/sim/components/JointPositionReset.hh index c178424c9f..aaf2cf3ae6 100644 --- a/include/gz/sim/components/JointPositionReset.hh +++ b/include/gz/sim/components/JointPositionReset.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief Joint positions in SI units (rad for revolute, m for prismatic). diff --git a/include/gz/sim/components/JointTransmittedWrench.hh b/include/gz/sim/components/JointTransmittedWrench.hh index 9265b4157d..f315392280 100644 --- a/include/gz/sim/components/JointTransmittedWrench.hh +++ b/include/gz/sim/components/JointTransmittedWrench.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { diff --git a/include/gz/sim/components/JointType.hh b/include/gz/sim/components/JointType.hh index ab1a6c61fa..ed3a1ed719 100644 --- a/include/gz/sim/components/JointType.hh +++ b/include/gz/sim/components/JointType.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace serializers { class JointTypeSerializer diff --git a/include/gz/sim/components/JointVelocity.hh b/include/gz/sim/components/JointVelocity.hh index 65b58e4e0f..bc19fe520f 100644 --- a/include/gz/sim/components/JointVelocity.hh +++ b/include/gz/sim/components/JointVelocity.hh @@ -25,12 +25,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief Base class which can be extended to add serialization diff --git a/include/gz/sim/components/JointVelocityCmd.hh b/include/gz/sim/components/JointVelocityCmd.hh index 9c373d35e3..6ff5238b6d 100644 --- a/include/gz/sim/components/JointVelocityCmd.hh +++ b/include/gz/sim/components/JointVelocityCmd.hh @@ -25,12 +25,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief Base class which can be extended to add serialization diff --git a/include/gz/sim/components/JointVelocityLimitsCmd.hh b/include/gz/sim/components/JointVelocityLimitsCmd.hh index 8470a74a6e..f75656e3e0 100644 --- a/include/gz/sim/components/JointVelocityLimitsCmd.hh +++ b/include/gz/sim/components/JointVelocityLimitsCmd.hh @@ -26,12 +26,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { @@ -43,9 +43,9 @@ namespace components /// 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, + std::vector, class JointVelocityLimitsCmdTag, - serializers::VectorSerializer + serializers::VectorSerializer >; IGN_GAZEBO_REGISTER_COMPONENT( diff --git a/include/gz/sim/components/JointVelocityReset.hh b/include/gz/sim/components/JointVelocityReset.hh index 16d335cb7a..f98b89b096 100644 --- a/include/gz/sim/components/JointVelocityReset.hh +++ b/include/gz/sim/components/JointVelocityReset.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief Joint velocities in SI units diff --git a/include/gz/sim/components/LaserRetro.hh b/include/gz/sim/components/LaserRetro.hh index a78e2a2766..2832c3e3ca 100644 --- a/include/gz/sim/components/LaserRetro.hh +++ b/include/gz/sim/components/LaserRetro.hh @@ -21,12 +21,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component used to indicate an lidar reflective value diff --git a/include/gz/sim/components/Level.hh b/include/gz/sim/components/Level.hh index d7e60ab4f1..50863d1c42 100644 --- a/include/gz/sim/components/Level.hh +++ b/include/gz/sim/components/Level.hh @@ -23,12 +23,12 @@ #include "gz/sim/components/Factory.hh" #include "gz/sim/components/Component.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief This component identifies an entity as being a level. diff --git a/include/gz/sim/components/LevelBuffer.hh b/include/gz/sim/components/LevelBuffer.hh index a8198ac4c2..5ab0b412d7 100644 --- a/include/gz/sim/components/LevelBuffer.hh +++ b/include/gz/sim/components/LevelBuffer.hh @@ -23,12 +23,12 @@ #include "gz/sim/components/Factory.hh" #include "gz/sim/components/Component.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component that holds the buffer setting of a level's geometry diff --git a/include/gz/sim/components/LevelEntityNames.hh b/include/gz/sim/components/LevelEntityNames.hh index 65fb8c74c6..01e84288c0 100644 --- a/include/gz/sim/components/LevelEntityNames.hh +++ b/include/gz/sim/components/LevelEntityNames.hh @@ -26,12 +26,12 @@ #include "gz/sim/components/Factory.hh" #include "gz/sim/components/Component.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace serializers { class LevelEntityNamesSerializer diff --git a/include/gz/sim/components/Lidar.hh b/include/gz/sim/components/Lidar.hh index 5835d890a8..6b0568b815 100644 --- a/include/gz/sim/components/Lidar.hh +++ b/include/gz/sim/components/Lidar.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains a Lidar sensor, diff --git a/include/gz/sim/components/Light.hh b/include/gz/sim/components/Light.hh index b55a31bd0f..b8d1fc7a9d 100644 --- a/include/gz/sim/components/Light.hh +++ b/include/gz/sim/components/Light.hh @@ -27,12 +27,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace serializers { using LightSerializer = diff --git a/include/gz/sim/components/LightCmd.hh b/include/gz/sim/components/LightCmd.hh index a3bab15c58..fa9028cfcd 100644 --- a/include/gz/sim/components/LightCmd.hh +++ b/include/gz/sim/components/LightCmd.hh @@ -27,17 +27,17 @@ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_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("gz_sim_components.LightCmd", LightCmd) diff --git a/include/gz/sim/components/LightType.hh b/include/gz/sim/components/LightType.hh index d193ac7c33..ddcefe77d5 100644 --- a/include/gz/sim/components/LightType.hh +++ b/include/gz/sim/components/LightType.hh @@ -25,12 +25,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component that contains the light type. This is a simple wrapper diff --git a/include/gz/sim/components/LinearAcceleration.hh b/include/gz/sim/components/LinearAcceleration.hh index 386c7b5363..23254a21d2 100644 --- a/include/gz/sim/components/LinearAcceleration.hh +++ b/include/gz/sim/components/LinearAcceleration.hh @@ -25,23 +25,23 @@ #include #include "gz/sim/components/Component.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains linear acceleration of an entity - /// represented by ignition::math::Vector3d. + /// represented by gz::math::Vector3d. using LinearAcceleration = Component; IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.LinearAcceleration", LinearAcceleration) /// \brief A component type that contains linear acceleration of an entity - /// in the world frame represented by ignition::math::Vector3d. + /// in the world frame represented by gz::math::Vector3d. using WorldLinearAcceleration = Component; IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.WorldLinearAcceleration", diff --git a/include/gz/sim/components/LinearVelocity.hh b/include/gz/sim/components/LinearVelocity.hh index 7f0671ecc9..916c33c89f 100644 --- a/include/gz/sim/components/LinearVelocity.hh +++ b/include/gz/sim/components/LinearVelocity.hh @@ -22,22 +22,22 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains linear velocity of an entity - /// represented by ignition::math::Vector3d. + /// represented by gz::math::Vector3d. using LinearVelocity = Component; IGN_GAZEBO_REGISTER_COMPONENT( "gz_sim_components.LinearVelocity", LinearVelocity) /// \brief A component type that contains linear velocity of an entity in the - /// world frame represented by ignition::math::Vector3d. + /// world frame represented by gz::math::Vector3d. using WorldLinearVelocity = Component; IGN_GAZEBO_REGISTER_COMPONENT( diff --git a/include/gz/sim/components/LinearVelocityCmd.hh b/include/gz/sim/components/LinearVelocityCmd.hh index 4636e234bf..9ef0d486c0 100644 --- a/include/gz/sim/components/LinearVelocityCmd.hh +++ b/include/gz/sim/components/LinearVelocityCmd.hh @@ -24,16 +24,16 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_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 + /// entity represented by gz::math::Vector3d, expressed in the entity's /// frame. using LinearVelocityCmd = Component< math::Vector3d, class LinearVelocityCmdTag>; @@ -41,7 +41,7 @@ namespace components "gz_sim_components.LinearVelocityCmd", LinearVelocityCmd) /// \brief A component type that contains the commanded linear velocity of an - /// entity represented by ignition::math::Vector3d, expressed in the world + /// entity represented by gz::math::Vector3d, expressed in the world /// frame. using WorldLinearVelocityCmd = Component; diff --git a/include/gz/sim/components/LinearVelocitySeed.hh b/include/gz/sim/components/LinearVelocitySeed.hh index b60cbf7216..143e93c4c0 100644 --- a/include/gz/sim/components/LinearVelocitySeed.hh +++ b/include/gz/sim/components/LinearVelocitySeed.hh @@ -22,17 +22,17 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_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 + /// gz::math::Vector3d. This seed can used to generate linear velocities /// by applying transformations and adding noise. using LinearVelocitySeed = Component; @@ -40,7 +40,7 @@ namespace components 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 + /// the world frame represented by gz::math::Vector3d. This seed can /// used to generate linear velocities by applying transformations and adding /// noise. using WorldLinearVelocitySeed = diff --git a/include/gz/sim/components/Link.hh b/include/gz/sim/components/Link.hh index ce9b76c544..29b9b5e487 100644 --- a/include/gz/sim/components/Link.hh +++ b/include/gz/sim/components/Link.hh @@ -21,12 +21,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component that identifies an entity as being a link. diff --git a/include/gz/sim/components/LogPlaybackStatistics.hh b/include/gz/sim/components/LogPlaybackStatistics.hh index 8d84f9deea..e17b262766 100644 --- a/include/gz/sim/components/LogPlaybackStatistics.hh +++ b/include/gz/sim/components/LogPlaybackStatistics.hh @@ -24,19 +24,19 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_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("gz_sim_components.LogPlaybackStatistics", LogPlaybackStatistics) diff --git a/include/gz/sim/components/LogicalAudio.hh b/include/gz/sim/components/LogicalAudio.hh index 58bc69cd50..3dd84d15ff 100644 --- a/include/gz/sim/components/LogicalAudio.hh +++ b/include/gz/sim/components/LogicalAudio.hh @@ -27,12 +27,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace logical_audio { /// \brief Audio source attenuation functions. @@ -47,7 +47,7 @@ namespace logical_audio /// \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 + /// source entity via gz::sim::components::Pose struct Source { /// \brief The source's id @@ -115,7 +115,7 @@ namespace logical_audio /// \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 + /// microphone entity via gz::sim::components::Pose struct Microphone { /// \brief The microphone's id diff --git a/include/gz/sim/components/LogicalCamera.hh b/include/gz/sim/components/LogicalCamera.hh index 47eccd29ee..7ee9f9f27a 100644 --- a/include/gz/sim/components/LogicalCamera.hh +++ b/include/gz/sim/components/LogicalCamera.hh @@ -22,12 +22,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief TODO(anyone) Substitute with sdf::LogicalCamera once that exists? diff --git a/include/gz/sim/components/MagneticField.hh b/include/gz/sim/components/MagneticField.hh index 0bd27f232c..df80493b8b 100644 --- a/include/gz/sim/components/MagneticField.hh +++ b/include/gz/sim/components/MagneticField.hh @@ -25,12 +25,12 @@ #include #include "gz/sim/components/Component.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief Stores the 3D magnetic field in teslas. diff --git a/include/gz/sim/components/Magnetometer.hh b/include/gz/sim/components/Magnetometer.hh index 59dc9fab1f..6fbcf6d588 100644 --- a/include/gz/sim/components/Magnetometer.hh +++ b/include/gz/sim/components/Magnetometer.hh @@ -26,12 +26,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains a magnetometer sensor, diff --git a/include/gz/sim/components/Material.hh b/include/gz/sim/components/Material.hh index c3d2661c43..85a5f076e8 100644 --- a/include/gz/sim/components/Material.hh +++ b/include/gz/sim/components/Material.hh @@ -26,12 +26,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace serializers { using MaterialSerializer = diff --git a/include/gz/sim/components/Model.hh b/include/gz/sim/components/Model.hh index 84fec11d37..403b40aa5d 100644 --- a/include/gz/sim/components/Model.hh +++ b/include/gz/sim/components/Model.hh @@ -26,12 +26,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace serializers { class SdfModelSerializer @@ -46,7 +46,7 @@ namespace serializers sdf::ElementPtr modelElem = _model.Element(); if (!modelElem) { - ignerr << "Unable to serialize sdf::Model" << std::endl; + gzerr << "Unable to serialize sdf::Model" << std::endl; return _out; } @@ -70,7 +70,7 @@ namespace serializers sdf::Errors errors = root.LoadSdfString(sdf); if (!root.Model()) { - ignerr << "Unable to unserialize sdf::Model" << std::endl; + gzerr << "Unable to unserialize sdf::Model" << std::endl; return _in; } diff --git a/include/gz/sim/components/Name.hh b/include/gz/sim/components/Name.hh index a543832029..5b498d4ddc 100644 --- a/include/gz/sim/components/Name.hh +++ b/include/gz/sim/components/Name.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief This component holds an entity's name. The component has no concept diff --git a/include/gz/sim/components/NavSat.hh b/include/gz/sim/components/NavSat.hh index 4f4209676e..d147cb20e1 100644 --- a/include/gz/sim/components/NavSat.hh +++ b/include/gz/sim/components/NavSat.hh @@ -26,12 +26,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains an NavSat sensor, diff --git a/include/gz/sim/components/ParentEntity.hh b/include/gz/sim/components/ParentEntity.hh index bb3a3ec773..75dcdde6d9 100644 --- a/include/gz/sim/components/ParentEntity.hh +++ b/include/gz/sim/components/ParentEntity.hh @@ -22,12 +22,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief This component holds an entity's parent entity. @@ -37,7 +37,7 @@ namespace components /// 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. + /// the `sim::SdfEntityCreator` class. using ParentEntity = Component; IGN_GAZEBO_REGISTER_COMPONENT( "gz_sim_components.ParentEntity", ParentEntity) diff --git a/include/gz/sim/components/ParentLinkName.hh b/include/gz/sim/components/ParentLinkName.hh index 67b7a4cb07..191f5bbb2a 100644 --- a/include/gz/sim/components/ParentLinkName.hh +++ b/include/gz/sim/components/ParentLinkName.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief Holds the name of the entity's parent link. diff --git a/include/gz/sim/components/ParticleEmitter.hh b/include/gz/sim/components/ParticleEmitter.hh index 52eb838cdd..81a18dcadc 100644 --- a/include/gz/sim/components/ParticleEmitter.hh +++ b/include/gz/sim/components/ParticleEmitter.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component that contains a particle emitter. diff --git a/include/gz/sim/components/Performer.hh b/include/gz/sim/components/Performer.hh index cfa8a74f60..ea6466a689 100644 --- a/include/gz/sim/components/Performer.hh +++ b/include/gz/sim/components/Performer.hh @@ -23,12 +23,12 @@ #include "gz/sim/components/Factory.hh" #include "gz/sim/components/Component.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief This component identifies an entity as being a performer. diff --git a/include/gz/sim/components/PerformerAffinity.hh b/include/gz/sim/components/PerformerAffinity.hh index 0936adc416..64dd150cec 100644 --- a/include/gz/sim/components/PerformerAffinity.hh +++ b/include/gz/sim/components/PerformerAffinity.hh @@ -26,12 +26,12 @@ #include "gz/sim/components/Factory.hh" #include "gz/sim/components/Serialization.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief This component holds the address of the distributed secondary that diff --git a/include/gz/sim/components/PerformerLevels.hh b/include/gz/sim/components/PerformerLevels.hh index 556eeadb8f..52f8ed52a3 100644 --- a/include/gz/sim/components/PerformerLevels.hh +++ b/include/gz/sim/components/PerformerLevels.hh @@ -25,12 +25,12 @@ #include "gz/sim/components/Factory.hh" #include "gz/sim/components/Component.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace serializers { class PerformerLevelsSerializer diff --git a/include/gz/sim/components/Physics.hh b/include/gz/sim/components/Physics.hh index 640c3b62e4..c4fd8d3d12 100644 --- a/include/gz/sim/components/Physics.hh +++ b/include/gz/sim/components/Physics.hh @@ -31,12 +31,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace serializers { using PhysicsSerializer = diff --git a/include/gz/sim/components/PhysicsCmd.hh b/include/gz/sim/components/PhysicsCmd.hh index bcfd403fb1..56b9210d41 100644 --- a/include/gz/sim/components/PhysicsCmd.hh +++ b/include/gz/sim/components/PhysicsCmd.hh @@ -25,12 +25,12 @@ #include #include "gz/sim/components/Component.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains the physics properties of diff --git a/include/gz/sim/components/PhysicsEnginePlugin.hh b/include/gz/sim/components/PhysicsEnginePlugin.hh index 97db12a254..8c4312f09b 100644 --- a/include/gz/sim/components/PhysicsEnginePlugin.hh +++ b/include/gz/sim/components/PhysicsEnginePlugin.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief Holds the physics engine shared library. diff --git a/include/gz/sim/components/Pose.hh b/include/gz/sim/components/Pose.hh index fc029048e5..75cd9a5bc7 100644 --- a/include/gz/sim/components/Pose.hh +++ b/include/gz/sim/components/Pose.hh @@ -22,29 +22,29 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { - /// \brief A component type that contains pose, ignition::math::Pose3d, + /// \brief A component type that contains pose, gz::math::Pose3d, /// information. - using Pose = Component; + using Pose = Component; IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.Pose", Pose) - /// \brief A component type that contains pose, ignition::math::Pose3d, + /// \brief A component type that contains pose, gz::math::Pose3d, /// information in world frame. - using WorldPose = Component; + using WorldPose = Component; IGN_GAZEBO_REGISTER_COMPONENT( "gz_sim_components.WorldPose", WorldPose) - /// \brief A component type that contains pose, ignition::math::Pose3d, + /// \brief A component type that contains pose, gz::math::Pose3d, /// information within a trajectory. using TrajectoryPose = - Component; + Component; IGN_GAZEBO_REGISTER_COMPONENT( "gz_sim_components.TrajectoryPose", TrajectoryPose) } diff --git a/include/gz/sim/components/PoseCmd.hh b/include/gz/sim/components/PoseCmd.hh index 53957457d6..5ee3b6f3ac 100644 --- a/include/gz/sim/components/PoseCmd.hh +++ b/include/gz/sim/components/PoseCmd.hh @@ -25,16 +25,16 @@ #include #include "gz/sim/components/Component.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains commanded pose of an - /// entity in the world frame represented by ignition::math::Pose3d. + /// entity in the world frame represented by gz::math::Pose3d. using WorldPoseCmd = Component; IGN_GAZEBO_REGISTER_COMPONENT("gz_sim_components.WorldPoseCmd", WorldPoseCmd) diff --git a/include/gz/sim/components/Recreate.hh b/include/gz/sim/components/Recreate.hh index d58aa6af10..e211054768 100644 --- a/include/gz/sim/components/Recreate.hh +++ b/include/gz/sim/components/Recreate.hh @@ -21,12 +21,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component that identifies an entity needs to be recreated. diff --git a/include/gz/sim/components/RenderEngineGuiPlugin.hh b/include/gz/sim/components/RenderEngineGuiPlugin.hh index 79b75006b0..951d501918 100644 --- a/include/gz/sim/components/RenderEngineGuiPlugin.hh +++ b/include/gz/sim/components/RenderEngineGuiPlugin.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief Holds the render engine gui shared library. diff --git a/include/gz/sim/components/RenderEngineServerHeadless.hh b/include/gz/sim/components/RenderEngineServerHeadless.hh index 006be7ad4e..929c7c9d1a 100644 --- a/include/gz/sim/components/RenderEngineServerHeadless.hh +++ b/include/gz/sim/components/RenderEngineServerHeadless.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief Holds the headless mode. diff --git a/include/gz/sim/components/RenderEngineServerPlugin.hh b/include/gz/sim/components/RenderEngineServerPlugin.hh index d894ef47a6..829c3d7576 100644 --- a/include/gz/sim/components/RenderEngineServerPlugin.hh +++ b/include/gz/sim/components/RenderEngineServerPlugin.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief Holds the render engine server shared library. diff --git a/include/gz/sim/components/RgbdCamera.hh b/include/gz/sim/components/RgbdCamera.hh index 7f6c69e109..5ec5d1e1db 100644 --- a/include/gz/sim/components/RgbdCamera.hh +++ b/include/gz/sim/components/RgbdCamera.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains a RGBD camera sensor, diff --git a/include/gz/sim/components/Scene.hh b/include/gz/sim/components/Scene.hh index 9cad199576..953bccb4d6 100644 --- a/include/gz/sim/components/Scene.hh +++ b/include/gz/sim/components/Scene.hh @@ -26,12 +26,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace serializers { using SceneSerializer = diff --git a/include/gz/sim/components/SegmentationCamera.hh b/include/gz/sim/components/SegmentationCamera.hh index 2b8efd1092..cade71b82e 100644 --- a/include/gz/sim/components/SegmentationCamera.hh +++ b/include/gz/sim/components/SegmentationCamera.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains a Segmentation camera sensor, diff --git a/include/gz/sim/components/SelfCollide.hh b/include/gz/sim/components/SelfCollide.hh index 18949baece..2299f62fff 100644 --- a/include/gz/sim/components/SelfCollide.hh +++ b/include/gz/sim/components/SelfCollide.hh @@ -21,12 +21,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component used to hold a model's self collide property. diff --git a/include/gz/sim/components/SemanticLabel.hh b/include/gz/sim/components/SemanticLabel.hh index 13bf80704c..9e8d7acec7 100644 --- a/include/gz/sim/components/SemanticLabel.hh +++ b/include/gz/sim/components/SemanticLabel.hh @@ -22,12 +22,12 @@ #include "gz/sim/components/Factory.hh" #include "gz/sim/config.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component that holds the label of an entity. One example use diff --git a/include/gz/sim/components/Sensor.hh b/include/gz/sim/components/Sensor.hh index 9ff9228172..39225d680c 100644 --- a/include/gz/sim/components/Sensor.hh +++ b/include/gz/sim/components/Sensor.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component that identifies an entity as being a sensor. diff --git a/include/gz/sim/components/Serialization.hh b/include/gz/sim/components/Serialization.hh index 6edd2b1beb..eb7a095a6a 100644 --- a/include/gz/sim/components/Serialization.hh +++ b/include/gz/sim/components/Serialization.hh @@ -30,15 +30,15 @@ // This header holds serialization operators which are shared among several // components -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace traits { - /// \brief Type trait that determines if an ignition::gazebo::convert from In + /// \brief Type trait that determines if an gz::sim::convert from In /// to Out is defined. /// Usage: /// \code @@ -51,7 +51,7 @@ namespace traits private: template static auto Test(int _test) -> decltype(std::declval() = - ignition::gazebo::convert(std::declval()), + gz::sim::convert(std::declval()), std::true_type()); private: template @@ -83,12 +83,12 @@ namespace traits namespace serializers { /// \brief Serialization for that converts components data types to - /// ignition::msgs. This assumes that ignition::gazebo::convert is + /// 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 ignition::msg - /// types via ignition::gazebo::convert. For example sdf::Geometry can be + /// 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::value) { - msg = ignition::gazebo::convert(_data); + msg = gz::sim::convert(_data); } else { - msg = ignition::msgs::Convert(_data); + msg = gz::msgs::Convert(_data); } msg.SerializeToOstream(&_out); @@ -131,11 +131,11 @@ namespace serializers if constexpr (traits::HasGazeboConvert::value) { - _data = ignition::gazebo::convert(msg); + _data = gz::sim::convert(msg); } else { - _data = ignition::msgs::Convert(msg); + _data = gz::msgs::Convert(msg); } return _in; } @@ -154,7 +154,7 @@ namespace serializers public: static std::ostream &Serialize(std::ostream &_out, const std::vector &_vec) { - ignition::msgs::Double_V msg; + gz::msgs::Double_V msg; *msg.mutable_data() = {_vec.begin(), _vec.end()}; msg.SerializeToOstream(&_out); return _out; @@ -167,7 +167,7 @@ namespace serializers public: static std::istream &Deserialize(std::istream &_in, std::vector &_vec) { - ignition::msgs::Double_V msg; + gz::msgs::Double_V msg; msg.ParseFromIstream(&_in); _vec = {msg.data().begin(), msg.data().end()}; diff --git a/include/gz/sim/components/SlipComplianceCmd.hh b/include/gz/sim/components/SlipComplianceCmd.hh index 4e72a78696..dad272ef44 100644 --- a/include/gz/sim/components/SlipComplianceCmd.hh +++ b/include/gz/sim/components/SlipComplianceCmd.hh @@ -26,12 +26,12 @@ #include #include "gz/sim/components/Component.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains the slip compliance parameters to be diff --git a/include/gz/sim/components/SourceFilePath.hh b/include/gz/sim/components/SourceFilePath.hh index 70f748d62c..c23c43a209 100644 --- a/include/gz/sim/components/SourceFilePath.hh +++ b/include/gz/sim/components/SourceFilePath.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief This component holds the filepath to the source from which an diff --git a/include/gz/sim/components/SphericalCoordinates.hh b/include/gz/sim/components/SphericalCoordinates.hh index b97fef7e63..9a69a47bce 100644 --- a/include/gz/sim/components/SphericalCoordinates.hh +++ b/include/gz/sim/components/SphericalCoordinates.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace serializers { using SphericalCoordinatesSerializer = diff --git a/include/gz/sim/components/Static.hh b/include/gz/sim/components/Static.hh index c65976d52a..7d6ca8ecf6 100644 --- a/include/gz/sim/components/Static.hh +++ b/include/gz/sim/components/Static.hh @@ -21,12 +21,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component used to indicate that a model is static (i.e. not diff --git a/include/gz/sim/components/Temperature.hh b/include/gz/sim/components/Temperature.hh index 5b5381505a..f59e8754d6 100644 --- a/include/gz/sim/components/Temperature.hh +++ b/include/gz/sim/components/Temperature.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component that stores temperature data in Kelvin diff --git a/include/gz/sim/components/TemperatureRange.hh b/include/gz/sim/components/TemperatureRange.hh index b56d938dae..7861b551f9 100644 --- a/include/gz/sim/components/TemperatureRange.hh +++ b/include/gz/sim/components/TemperatureRange.hh @@ -26,12 +26,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief Data structure to hold a temperature range, in kelvin diff --git a/include/gz/sim/components/ThermalCamera.hh b/include/gz/sim/components/ThermalCamera.hh index b636123287..a9aeead5a0 100644 --- a/include/gz/sim/components/ThermalCamera.hh +++ b/include/gz/sim/components/ThermalCamera.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains a Thermal camera sensor, diff --git a/include/gz/sim/components/ThreadPitch.hh b/include/gz/sim/components/ThreadPitch.hh index 3a29a94e93..23a6907b1d 100644 --- a/include/gz/sim/components/ThreadPitch.hh +++ b/include/gz/sim/components/ThreadPitch.hh @@ -21,12 +21,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component used to store the thread pitch of a screw joint diff --git a/include/gz/sim/components/Transparency.hh b/include/gz/sim/components/Transparency.hh index abb3dafe46..45d2c8555e 100644 --- a/include/gz/sim/components/Transparency.hh +++ b/include/gz/sim/components/Transparency.hh @@ -21,12 +21,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component used to indicate an entity's transparency value diff --git a/include/gz/sim/components/Visibility.hh b/include/gz/sim/components/Visibility.hh index c4056ea87e..b11e3f7a09 100644 --- a/include/gz/sim/components/Visibility.hh +++ b/include/gz/sim/components/Visibility.hh @@ -22,12 +22,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief This component holds an entity's visibility flags (visual entities) diff --git a/include/gz/sim/components/Visual.hh b/include/gz/sim/components/Visual.hh index 6336117d8b..0c555433e7 100644 --- a/include/gz/sim/components/Visual.hh +++ b/include/gz/sim/components/Visual.hh @@ -26,12 +26,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace serializers { class SdfElementSerializer @@ -64,7 +64,7 @@ namespace serializers bool result = sdf::readString(sdfStr, sdfParsed); if (!result) { - ignerr << "Unable to deserialize sdf::ElementPtr" << std::endl; + gzerr << "Unable to deserialize sdf::ElementPtr" << std::endl; return _in; } diff --git a/include/gz/sim/components/VisualCmd.hh b/include/gz/sim/components/VisualCmd.hh index 7d1cc2a937..88e5cecc33 100644 --- a/include/gz/sim/components/VisualCmd.hh +++ b/include/gz/sim/components/VisualCmd.hh @@ -27,17 +27,17 @@ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_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("gz_sim_components.VisualCmd", VisualCmd) diff --git a/include/gz/sim/components/Volume.hh b/include/gz/sim/components/Volume.hh index e70c9d69a5..018797368e 100644 --- a/include/gz/sim/components/Volume.hh +++ b/include/gz/sim/components/Volume.hh @@ -21,12 +21,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A volume component where the units are m^3. diff --git a/include/gz/sim/components/WheelSlipCmd.hh b/include/gz/sim/components/WheelSlipCmd.hh index 10be1a4614..fd3f7be269 100644 --- a/include/gz/sim/components/WheelSlipCmd.hh +++ b/include/gz/sim/components/WheelSlipCmd.hh @@ -25,17 +25,17 @@ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_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("gz_sim_components.WheelSlipCmd", WheelSlipCmd) diff --git a/include/gz/sim/components/WideAngleCamera.hh b/include/gz/sim/components/WideAngleCamera.hh index ec2b8d8145..3ed9a27fad 100644 --- a/include/gz/sim/components/WideAngleCamera.hh +++ b/include/gz/sim/components/WideAngleCamera.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component type that contains a wide angle camera sensor, diff --git a/include/gz/sim/components/Wind.hh b/include/gz/sim/components/Wind.hh index 310fb3e28d..1ef026020d 100644 --- a/include/gz/sim/components/Wind.hh +++ b/include/gz/sim/components/Wind.hh @@ -21,12 +21,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component that identifies an entity as being a wind. diff --git a/include/gz/sim/components/WindMode.hh b/include/gz/sim/components/WindMode.hh index 0d17ee365d..d7288fe062 100644 --- a/include/gz/sim/components/WindMode.hh +++ b/include/gz/sim/components/WindMode.hh @@ -21,12 +21,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component used to indicate whether an entity is affected by wind. diff --git a/include/gz/sim/components/World.hh b/include/gz/sim/components/World.hh index 48501e0664..469799aa89 100644 --- a/include/gz/sim/components/World.hh +++ b/include/gz/sim/components/World.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { /// \brief A component that identifies an entity as being a world. diff --git a/include/gz/sim/components/components.hh.in b/include/gz/sim/components/components.hh.in index b08e73fb89..05effcee01 100644 --- a/include/gz/sim/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_SIM_COMPONENTS_COMPONENTS_HH_ +#define GZ_SIM_COMPONENTS_COMPONENTS_HH_ // Automatically generated ${component_includes} diff --git a/include/gz/sim/config.hh.in b/include/gz/sim/config.hh.in index 050a0304a4..320bf2af6a 100644 --- a/include/gz/sim/config.hh.in +++ b/include/gz/sim/config.hh.in @@ -1,25 +1,43 @@ +/* + * 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 IGNITION_GAZEBO_MAJOR_VERSION ${PROJECT_VERSION_MAJOR} -#define IGNITION_GAZEBO_MINOR_VERSION ${PROJECT_VERSION_MINOR} -#define IGNITION_GAZEBO_PATCH_VERSION ${PROJECT_VERSION_PATCH} +#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 IGNITION_GAZEBO_VERSION "${PROJECT_VERSION}" -#define IGNITION_GAZEBO_VERSION_FULL "${PROJECT_VERSION_FULL}" -#define IGNITION_GAZEBO_MAJOR_VERSION_STR "${PROJECT_VERSION_MAJOR}" +#define GZ_SIM_VERSION "${PROJECT_VERSION}" +#define GZ_SIM_VERSION_FULL "${PROJECT_VERSION_FULL}" +#define GZ_SIM_MAJOR_VERSION_STR "${PROJECT_VERSION_MAJOR}" -#define IGNITION_GAZEBO_VERSION_NAMESPACE v${PROJECT_VERSION_MAJOR} +#define GZ_SIM_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 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 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" -#define IGNITION_GAZEBO_SERVER_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${IGN_DATA_INSTALL_DIR}" -#define IGN_GAZEBO_PLUGIN_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${IGN_LIB_INSTALL_DIR}/ign-${IGN_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins" -#define IGN_GAZEBO_GUI_PLUGIN_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${IGN_LIB_INSTALL_DIR}/ign-${IGN_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins/gui" -#define IGN_GAZEBO_WORLD_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${IGN_DATA_INSTALL_DIR}/worlds" +#define GZ_SIM_GUI_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${IGN_DATA_INSTALL_DIR}/gui" +#define GZ_SIM_SYSTEM_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${IGN_DATA_INSTALL_DIR}/systems" +#define GZ_SIM_SERVER_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${IGN_DATA_INSTALL_DIR}" +#define GZ_SIM_PLUGIN_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${IGN_LIB_INSTALL_DIR}/ign-${IGN_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins" +#define GZ_SIM_GUI_PLUGIN_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${IGN_LIB_INSTALL_DIR}/ign-${IGN_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins/gui" +#define GZ_SIM_WORLD_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${IGN_DATA_INSTALL_DIR}/worlds" -#cmakedefine IGNITION_GAZEBO_BUILD_TYPE_PROFILE 1 -#cmakedefine IGNITION_GAZEBO_BUILD_TYPE_DEBUG 1 -#cmakedefine IGNITION_GAZEBO_BUILD_TYPE_RELEASE 1 +#endif diff --git a/include/gz/sim/detail/BaseView.hh b/include/gz/sim/detail/BaseView.hh index 3fc53d4453..75aab68a2e 100644 --- a/include/gz/sim/detail/BaseView.hh +++ b/include/gz/sim/detail/BaseView.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_DETAIL_BASEVIEW_HH_ -#define GZ_GAZEBO_DETAIL_BASEVIEW_HH_ +#ifndef GZ_SIM_DETAIL_BASEVIEW_HH_ +#define GZ_SIM_DETAIL_BASEVIEW_HH_ #include #include @@ -26,12 +26,12 @@ #include "gz/sim/Types.hh" #include "gz/sim/config.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace detail { /// \brief A key into the map of views @@ -62,10 +62,10 @@ struct ComponentTypeHasher /// use a cache to improve performance. /// /// Note that symbols for this class are visible because methods from this class -/// are used in templated Ignition::Gazebo::EntityComponentManager methods. +/// are used in templated Gz::Sim::EntityComponentManager methods. /// However, users should not use this class (or anything else in namespace -/// ignition::gazebo::detail) directly. -class IGNITION_GAZEBO_VISIBLE BaseView +/// gz::sim::detail) directly. +class GZ_GAZEBO_VISIBLE BaseView { /// \brief Destructor public: virtual ~BaseView(); @@ -214,6 +214,6 @@ class IGNITION_GAZEBO_VISIBLE BaseView }; } // namespace detail } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz #endif diff --git a/include/gz/sim/detail/ComponentStorageBase.hh b/include/gz/sim/detail/ComponentStorageBase.hh index 78e7cf9dc5..490ba5b5b6 100644 --- a/include/gz/sim/detail/ComponentStorageBase.hh +++ b/include/gz/sim/detail/ComponentStorageBase.hh @@ -14,25 +14,25 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_DETAIL_COMPONENTSTORAGEBASE_HH_ -#define GZ_GAZEBO_DETAIL_COMPONENTSTORAGEBASE_HH_ +#ifndef GZ_SIM_DETAIL_COMPONENTSTORAGEBASE_HH_ +#define GZ_SIM_DETAIL_COMPONENTSTORAGEBASE_HH_ #include "gz/sim/Export.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { // /// \brief All component instances of the same type are stored /// sequentially in memory. This is a base class for storing components /// of a particular type. - class IGNITION_GAZEBO_HIDDEN ComponentStorageBase + class GZ_GAZEBO_HIDDEN ComponentStorageBase { /// \brief Constructor - public: IGN_DEPRECATED(6) ComponentStorageBase() = default; + public: GZ_DEPRECATED(6) ComponentStorageBase() = default; /// \brief Destructor public: virtual ~ComponentStorageBase() = default; @@ -40,10 +40,10 @@ namespace ignition /// \brief Templated implementation of component storage. template - class IGNITION_GAZEBO_HIDDEN ComponentStorage : public ComponentStorageBase + class GZ_GAZEBO_HIDDEN ComponentStorage : public ComponentStorageBase { /// \brief Constructor - public: explicit IGN_DEPRECATED(6) ComponentStorage() + public: explicit GZ_DEPRECATED(6) ComponentStorage() : ComponentStorageBase() { } diff --git a/include/gz/sim/detail/EntityComponentManager.hh b/include/gz/sim/detail/EntityComponentManager.hh index 9fa09d06e2..9c5c14cf78 100644 --- a/include/gz/sim/detail/EntityComponentManager.hh +++ b/include/gz/sim/detail/EntityComponentManager.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_DETAIL_ENTITYCOMPONENTMANAGER_HH_ -#define GZ_GAZEBO_DETAIL_ENTITYCOMPONENTMANAGER_HH_ +#ifndef GZ_SIM_DETAIL_ENTITYCOMPONENTMANAGER_HH_ +#define GZ_SIM_DETAIL_ENTITYCOMPONENTMANAGER_HH_ #include #include @@ -32,12 +32,12 @@ #include "gz/sim/EntityComponentManager.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { ////////////////////////////////////////////////// namespace traits { @@ -65,7 +65,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 { @@ -94,7 +94,7 @@ ComponentTypeT *EntityComponentManager::CreateComponent(const Entity _entity, { if (!comp) { - ignerr << "Internal error. Failure to create a component of type " + gzerr << "Internal error. Failure to create a component of type " << ComponentTypeT::typeId << " for entity " << _entity << ". This should never happen!\n"; return comp; @@ -190,7 +190,7 @@ bool EntityComponentManager::SetComponentData(const Entity _entity, template const ComponentTypeT *EntityComponentManager::First() const { - ignwarn << "EntityComponentManager::First is now deprecated and will always " + gzwarn << "EntityComponentManager::First is now deprecated and will always " << "return nullptr.\n"; return nullptr; } @@ -199,7 +199,7 @@ const ComponentTypeT *EntityComponentManager::First() const template ComponentTypeT *EntityComponentManager::First() { - ignwarn << "EntityComponentManager::First is now deprecated and will always " + gzwarn << "EntityComponentManager::First is now deprecated and will always " << "return nullptr.\n"; return nullptr; } @@ -554,7 +554,7 @@ detail::View *EntityComponentManager::FindView() const auto mutexPtr = baseViewMutexPair.second; if (nullptr == mutexPtr) { - ignerr << "Internal error: requested to lock a view, but no mutex " + gzerr << "Internal error: requested to lock a view, but no mutex " << "exists for this view. This should never happen!" << std::endl; return view; } diff --git a/include/gz/sim/detail/View.hh b/include/gz/sim/detail/View.hh index 05c541bc45..5fe4e7840f 100644 --- a/include/gz/sim/detail/View.hh +++ b/include/gz/sim/detail/View.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_DETAIL_VIEW_HH_ -#define GZ_GAZEBO_DETAIL_VIEW_HH_ +#ifndef GZ_SIM_DETAIL_VIEW_HH_ +#define GZ_SIM_DETAIL_VIEW_HH_ #include #include @@ -31,21 +31,21 @@ #include "gz/sim/config.hh" #include "gz/sim/detail/BaseView.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace detail { /// \brief A view that caches a particular set of component type data. /// /// Note that symbols for this class are visible because methods from this class -/// are used in templated Ignition::Gazebo::EntityComponentManager methods. +/// are used in templated Gz::Sim::EntityComponentManager methods. /// However, users should not use this class (or anything else in namespace -/// ignition::gazebo::detail) directly. -class IGNITION_GAZEBO_VISIBLE View : public BaseView +/// gz::sim::detail) directly. +class GZ_GAZEBO_VISIBLE View : public BaseView { /// \brief Alias for containers that hold and entity and its component data. /// The component types held in this container match the component types that @@ -185,6 +185,6 @@ void View::AddEntityWithComps(const Entity &_entity, const bool _new, } } // namespace detail } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz #endif diff --git a/include/gz/sim/gui/Gui.hh b/include/gz/sim/gui/Gui.hh index 75f265afed..cb820d5d7a 100644 --- a/include/gz/sim/gui/Gui.hh +++ b/include/gz/sim/gui/Gui.hh @@ -15,8 +15,8 @@ * */ -#ifndef GZ_GAZEBO_GUI_GUI_HH_ -#define GZ_GAZEBO_GUI_GUI_HH_ +#ifndef GZ_SIM_GUI_GUI_HH_ +#define GZ_SIM_GUI_GUI_HH_ #include #include @@ -24,12 +24,12 @@ #include "gz/sim/config.hh" #include "gz/sim/gui/Export.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace gui { /// \brief Run GUI application @@ -43,7 +43,7 @@ namespace gui /// configuration from IGN_HOMEDIR/.gz/sim/gui.config will be used. /// \param[in] _renderEngineGui --render-engine-gui option /// \return -1 on failure, 0 on success - IGNITION_GAZEBO_GUI_VISIBLE int runGui(int &_argc, + GZ_GAZEBO_GUI_VISIBLE int runGui(int &_argc, char **_argv, const char *_guiConfig, const char * _renderEngine = nullptr); /// \brief Create a Gazebo GUI application @@ -64,15 +64,15 @@ namespace gui /// SDFormat file will get loaded. /// \param[in] _renderEngineGui --render-engine-gui option /// \return Newly created application. - IGNITION_GAZEBO_GUI_VISIBLE - std::unique_ptr createGui( + GZ_GAZEBO_GUI_VISIBLE + std::unique_ptr createGui( int &_argc, char **_argv, const char *_guiConfig, const char *_defaultGuiConfig = nullptr, bool _loadPluginsFromSdf = true, const char *_renderEngine = nullptr); } // namespace gui } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz #endif diff --git a/include/gz/sim/gui/GuiEvents.hh b/include/gz/sim/gui/GuiEvents.hh index 27b2002037..5333667bfa 100644 --- a/include/gz/sim/gui/GuiEvents.hh +++ b/include/gz/sim/gui/GuiEvents.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_GUI_GUIEVENTS_HH_ -#define GZ_GAZEBO_GUI_GUIEVENTS_HH_ +#ifndef GZ_SIM_GUI_GUIEVENTS_HH_ +#define GZ_SIM_GUI_GUIEVENTS_HH_ #include #include @@ -34,19 +34,19 @@ #include "gz/sim/Entity.hh" #include "gz/sim/config.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace gui { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { /// \brief Namespace for all events. Refer to the EventManager class for /// more information about events. namespace events { /// \brief Event that notifies when new entities have been selected. - class IGNITION_GAZEBO_GUI_VISIBLE EntitiesSelected : public QEvent + class GZ_GAZEBO_GUI_VISIBLE EntitiesSelected : public QEvent { /// \brief Constructor /// \param[in] _entities All the selected entities @@ -84,7 +84,7 @@ namespace events }; /// \brief Event that notifies when all entities have been deselected. - class IGNITION_GAZEBO_GUI_VISIBLE DeselectAllEntities : public QEvent + class GZ_GAZEBO_GUI_VISIBLE DeselectAllEntities : public QEvent { /// \brief Constructor /// \param[in] _fromUser True if the event was directly generated by the @@ -111,7 +111,7 @@ namespace events /// \brief Event that contains entities newly created or removed from the /// GUI, but that aren't present on the server yet. /// \sa NewRemovedEntities - class IGNITION_GAZEBO_GUI_VISIBLE GuiNewRemovedEntities : public QEvent + class GZ_GAZEBO_GUI_VISIBLE GuiNewRemovedEntities : public QEvent { /// \brief Constructor /// \param[in] _newEntities Set of newly created entities @@ -137,7 +137,7 @@ namespace events /// on the server. This is a duplication of what `GuiSystem`s would get from /// `EachNew` / `EachRemoved` ECM calls. /// \sa GuiNewRemovedEntities - class IGNITION_GAZEBO_GUI_VISIBLE NewRemovedEntities : public QEvent + class GZ_GAZEBO_GUI_VISIBLE NewRemovedEntities : public QEvent { /// \brief Constructor /// \param[in] _newEntities Set of newly created entities @@ -161,7 +161,7 @@ namespace events /// \brief True if a transform control is currently active (translate / /// rotate / scale). False if we're in selection mode. - class IGNITION_GAZEBO_GUI_VISIBLE TransformControlModeActive : public QEvent + class GZ_GAZEBO_GUI_VISIBLE TransformControlModeActive : public QEvent { /// \brief Constructor /// \param[in] _tranformModeActive is the transform control mode active @@ -184,14 +184,14 @@ namespace events }; /// \brief Event that notifies an entity is to be added to the model editor - class IGNITION_GAZEBO_GUI_VISIBLE ModelEditorAddEntity : public QEvent + class GZ_GAZEBO_GUI_VISIBLE ModelEditorAddEntity : public QEvent { /// \brief Constructor /// \param[in] _entity Entity added /// \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; @@ -201,7 +201,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. @@ -215,16 +215,16 @@ namespace events }; /// \brief Event that notifies a visual plugin is to be loaded - class IGNITION_GAZEBO_GUI_VISIBLE VisualPlugin: public QEvent + class GZ_GAZEBO_GUI_VISIBLE VisualPlugin: public QEvent { /// \brief Constructor /// \param[in] _entity Visual entity id /// \param[in] _elem Visual plugin SDF element - public: explicit VisualPlugin(ignition::gazebo::Entity _entity, + public: explicit VisualPlugin(gz::sim::Entity _entity, const sdf::ElementPtr &_elem); /// \brief Get the entity to load the visual plugin for - public: ignition::gazebo::Entity Entity() const; + public: gz::sim::Entity Entity() const; /// \brief Get the sdf element of the visual plugin public: sdf::ElementPtr Element() const; @@ -238,7 +238,7 @@ namespace events } // namespace events } } // namespace gui -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz -#endif // GZ_GAZEBO_GUI_GUIEVENTS_HH_ +#endif // GZ_SIM_GUI_GUIEVENTS_HH_ diff --git a/include/gz/sim/gui/GuiSystem.hh b/include/gz/sim/gui/GuiSystem.hh index eb4db4ac9d..b5269b4335 100644 --- a/include/gz/sim/gui/GuiSystem.hh +++ b/include/gz/sim/gui/GuiSystem.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_GUI_GUISYSTEM_HH_ -#define GZ_GAZEBO_GUI_GUISYSTEM_HH_ +#ifndef GZ_SIM_GUI_GUISYSTEM_HH_ +#define GZ_SIM_GUI_GUISYSTEM_HH_ #include @@ -26,22 +26,22 @@ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_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 + /// 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_GUI_VISIBLE GuiSystem : public ignition::gui::Plugin + class GZ_GAZEBO_GUI_VISIBLE GuiSystem : public gz::gui::Plugin { Q_OBJECT diff --git a/include/gz/sim/physics/Events.hh b/include/gz/sim/physics/Events.hh index c49f39f13c..633cad5441 100644 --- a/include/gz/sim/physics/Events.hh +++ b/include/gz/sim/physics/Events.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_PHYSICS_EVENTS_HH_ -#define GZ_GAZEBO_PHYSICS_EVENTS_HH_ +#ifndef GZ_SIM_PHYSICS_EVENTS_HH_ +#define GZ_SIM_PHYSICS_EVENTS_HH_ #include @@ -28,12 +28,12 @@ #include -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { namespace events { @@ -44,7 +44,7 @@ namespace ignition /// 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< + using CollectContactSurfaceProperties = gz::common::EventT< void( const Entity& /* collision1 */, const Entity& /* collision2 */, @@ -59,7 +59,7 @@ namespace ignition struct CollectContactSurfacePropertiesTag>; } } // namespace events - } // namespace gazebo -} // namespace ignition + } // namespace sim +} // namespace gz -#endif // GZ_GAZEBO_PHYSICS_EVENTS_HH_ +#endif // GZ_SIM_PHYSICS_EVENTS_HH_ diff --git a/include/gz/sim/playback_server.config b/include/gz/sim/playback_server.config index 2551fda3ea..9a88489385 100644 --- a/include/gz/sim/playback_server.config +++ b/include/gz/sim/playback_server.config @@ -3,12 +3,12 @@ + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/include/gz/sim/rendering/Events.hh b/include/gz/sim/rendering/Events.hh index a2db9a7e82..18ea194118 100644 --- a/include/gz/sim/rendering/Events.hh +++ b/include/gz/sim/rendering/Events.hh @@ -14,20 +14,20 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_RENDERING_EVENTS_HH_ -#define GZ_GAZEBO_RENDERING_EVENTS_HH_ +#ifndef GZ_SIM_RENDERING_EVENTS_HH_ +#define GZ_SIM_RENDERING_EVENTS_HH_ #include #include "gz/sim/config.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { /// \brief Namespace for all events. Refer to the EventManager class for /// more information about events. namespace events @@ -39,9 +39,9 @@ namespace ignition /// /// For example: /// \code - /// eventManager.Emit(); + /// eventManager.Emit(); /// \endcode - using SceneUpdate = ignition::common::EventT; /// \brief The render event is emitted before rendering updates. @@ -50,9 +50,9 @@ namespace ignition /// /// For example: /// \code - /// eventManager.Emit(); + /// eventManager.Emit(); /// \endcode - using PreRender = ignition::common::EventT; /// \brief The render event is emitted after rendering updates. @@ -61,13 +61,13 @@ namespace ignition /// /// For example: /// \code - /// eventManager.Emit(); + /// eventManager.Emit(); /// \endcode - using PostRender = ignition::common::EventT; } } // namespace events - } // namespace gazebo -} // namespace ignition + } // namespace sim +} // namespace gz -#endif // GZ_GAZEBO_RENDEREVENTS_HH_ +#endif // GZ_SIM_RENDEREVENTS_HH_ diff --git a/include/gz/sim/rendering/MarkerManager.hh b/include/gz/sim/rendering/MarkerManager.hh index 18f4fbe643..de79aed885 100644 --- a/include/gz/sim/rendering/MarkerManager.hh +++ b/include/gz/sim/rendering/MarkerManager.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_MARKERMANAGER_HH_ -#define GZ_GAZEBO_MARKERMANAGER_HH_ +#ifndef GZ_SIM_MARKERMANAGER_HH_ +#define GZ_SIM_MARKERMANAGER_HH_ #include #include @@ -24,17 +24,17 @@ #include "gz/rendering/RenderTypes.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_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 +class GZ_GAZEBO_RENDERING_VISIBLE MarkerManager { /// \brief Constructor public: MarkerManager(); @@ -60,7 +60,7 @@ class IGNITION_GAZEBO_RENDERING_VISIBLE MarkerManager /// \brief Initialize the marker manager. /// \param[in] _scene Reference to the scene. /// \return True on success - public: bool Init(const ignition::rendering::ScenePtr &_scene); + public: bool Init(const gz::rendering::ScenePtr &_scene); /// \brief Set the marker service topic name. /// \param[in] _name Name of service diff --git a/include/gz/sim/rendering/RenderUtil.hh b/include/gz/sim/rendering/RenderUtil.hh index 2fd68e7169..f3ac8fbcf2 100644 --- a/include/gz/sim/rendering/RenderUtil.hh +++ b/include/gz/sim/rendering/RenderUtil.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef GZ_GAZEBO_RENDERUTIL_HH_ -#define GZ_GAZEBO_RENDERUTIL_HH_ +#ifndef GZ_SIM_RENDERUTIL_HH_ +#define GZ_SIM_RENDERUTIL_HH_ #include #include @@ -32,17 +32,17 @@ #include "gz/sim/rendering/MarkerManager.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { // forward declaration class RenderUtilPrivate; /// \class RenderUtil RenderUtil.hh gz/sim/gui/plugins/RenderUtil.hh - class IGNITION_GAZEBO_RENDERING_VISIBLE RenderUtil + class GZ_GAZEBO_RENDERING_VISIBLE RenderUtil { /// \brief Constructor public: explicit RenderUtil(); @@ -144,14 +144,14 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// The callback function args are: sensor entity, sensor sdf /// and parent name, it returns the name of the rendering sensor created. public: void SetEnableSensors(bool _enable, std::function< - std::string(const gazebo::Entity &, const sdf::Sensor &, + std::string(const sim::Entity &, const sdf::Sensor &, const std::string &)> _createSensorCb = {}); /// \brief Set the callback function for removing the sensors /// \param[in] _removeSensorCb Callback function for removing the sensors /// The callback function arg is the sensor entity to remove public : void SetRemoveSensorCb( - std::function _removeSensorCb); + std::function _removeSensorCb); /// \brief View an entity as transparent /// \param[in] _entity Entity to view as transparent diff --git a/include/gz/sim/rendering/SceneManager.hh b/include/gz/sim/rendering/SceneManager.hh index 31524aaaad..4feb3d06d1 100644 --- a/include/gz/sim/rendering/SceneManager.hh +++ b/include/gz/sim/rendering/SceneManager.hh @@ -15,8 +15,8 @@ * */ -#ifndef GZ_GAZEBO_SCENEMANAGER_HH_ -#define GZ_GAZEBO_SCENEMANAGER_HH_ +#ifndef GZ_SIM_SCENEMANAGER_HH_ +#define GZ_SIM_SCENEMANAGER_HH_ #include #include @@ -45,12 +45,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { // Forward declaration class SceneManagerPrivate; @@ -89,7 +89,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { }; /// \brief Scene manager class for loading and managing objects in the scene - class IGNITION_GAZEBO_RENDERING_VISIBLE SceneManager + class GZ_GAZEBO_RENDERING_VISIBLE SceneManager { /// \brief Constructor public: SceneManager(); @@ -247,7 +247,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// 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] _sensorName Name of sensor node in Gazebo Rendering. /// \param[in] _parentGazeboId Parent Id on Gazebo. /// \return True if sensor is successfully handled public: bool AddSensor(Entity _gazeboId, const std::string &_sensorName, diff --git a/include/gz/sim/server.config b/include/gz/sim/server.config index 5de18a66fc..3a26dac6d6 100644 --- a/include/gz/sim/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/gazebo/Conversions.hh b/include/ignition/gazebo/Conversions.hh index d5e0f5b151..f0d023823d 100644 --- a/include/ignition/gazebo/Conversions.hh +++ b/include/ignition/gazebo/Conversions.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/Entity.hh b/include/ignition/gazebo/Entity.hh index c04d4ba854..780e6d2917 100644 --- a/include/ignition/gazebo/Entity.hh +++ b/include/ignition/gazebo/Entity.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/EntityComponentManager.hh b/include/ignition/gazebo/EntityComponentManager.hh index 9aaa4353f3..8a6884b0b1 100644 --- a/include/ignition/gazebo/EntityComponentManager.hh +++ b/include/ignition/gazebo/EntityComponentManager.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/EventManager.hh b/include/ignition/gazebo/EventManager.hh index 7bd1352bcb..639c7fa450 100644 --- a/include/ignition/gazebo/EventManager.hh +++ b/include/ignition/gazebo/EventManager.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/Events.hh b/include/ignition/gazebo/Events.hh index ba203e8d5d..7589873d10 100644 --- a/include/ignition/gazebo/Events.hh +++ b/include/ignition/gazebo/Events.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/Export.hh b/include/ignition/gazebo/Export.hh index 4de3e2029a..290d7e16bd 100644 --- a/include/ignition/gazebo/Export.hh +++ b/include/ignition/gazebo/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/Link.hh b/include/ignition/gazebo/Link.hh index bc72d5eedc..956ecc8127 100644 --- a/include/ignition/gazebo/Link.hh +++ b/include/ignition/gazebo/Link.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/Model.hh b/include/ignition/gazebo/Model.hh index 045d507523..66304aab1d 100644 --- a/include/ignition/gazebo/Model.hh +++ b/include/ignition/gazebo/Model.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/Primitives.hh b/include/ignition/gazebo/Primitives.hh index 2da4ce3886..8b30ab930f 100644 --- a/include/ignition/gazebo/Primitives.hh +++ b/include/ignition/gazebo/Primitives.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/SdfEntityCreator.hh b/include/ignition/gazebo/SdfEntityCreator.hh index 92d1ed19f2..e010ac689b 100644 --- a/include/ignition/gazebo/SdfEntityCreator.hh +++ b/include/ignition/gazebo/SdfEntityCreator.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/Server.hh b/include/ignition/gazebo/Server.hh index 945bcfc0e5..a289f98d48 100644 --- a/include/ignition/gazebo/Server.hh +++ b/include/ignition/gazebo/Server.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/ServerConfig.hh b/include/ignition/gazebo/ServerConfig.hh index 1e1b47b980..4011c28bd0 100644 --- a/include/ignition/gazebo/ServerConfig.hh +++ b/include/ignition/gazebo/ServerConfig.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/System.hh b/include/ignition/gazebo/System.hh index ae233c72ca..825c3c312a 100644 --- a/include/ignition/gazebo/System.hh +++ b/include/ignition/gazebo/System.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/SystemLoader.hh b/include/ignition/gazebo/SystemLoader.hh index 2d0b6d5f33..d4d40447da 100644 --- a/include/ignition/gazebo/SystemLoader.hh +++ b/include/ignition/gazebo/SystemLoader.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/SystemPluginPtr.hh b/include/ignition/gazebo/SystemPluginPtr.hh index fb6e222711..17a1324b96 100644 --- a/include/ignition/gazebo/SystemPluginPtr.hh +++ b/include/ignition/gazebo/SystemPluginPtr.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/TestFixture.hh b/include/ignition/gazebo/TestFixture.hh index af891c07d1..6864e9a4a7 100644 --- a/include/ignition/gazebo/TestFixture.hh +++ b/include/ignition/gazebo/TestFixture.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/Types.hh b/include/ignition/gazebo/Types.hh index 2dd931cf9b..91a47264f5 100644 --- a/include/ignition/gazebo/Types.hh +++ b/include/ignition/gazebo/Types.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/Util.hh b/include/ignition/gazebo/Util.hh index 7cd0930952..59e66bc714 100644 --- a/include/ignition/gazebo/Util.hh +++ b/include/ignition/gazebo/Util.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/World.hh b/include/ignition/gazebo/World.hh index 46537d5874..0f96dae7c6 100644 --- a/include/ignition/gazebo/World.hh +++ b/include/ignition/gazebo/World.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/ackermann-steering-system/Export.hh b/include/ignition/gazebo/ackermann-steering-system/Export.hh index d5949cec03..94aa7daaca 100644 --- a/include/ignition/gazebo/ackermann-steering-system/Export.hh +++ b/include/ignition/gazebo/ackermann-steering-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/air-pressure-system/Export.hh b/include/ignition/gazebo/air-pressure-system/Export.hh index 56cac075a3..1f404f8f37 100644 --- a/include/ignition/gazebo/air-pressure-system/Export.hh +++ b/include/ignition/gazebo/air-pressure-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/altimeter-system/Export.hh b/include/ignition/gazebo/altimeter-system/Export.hh index 4134ca65e4..c276900862 100644 --- a/include/ignition/gazebo/altimeter-system/Export.hh +++ b/include/ignition/gazebo/altimeter-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/apply-joint-force-system/Export.hh b/include/ignition/gazebo/apply-joint-force-system/Export.hh index 0623c11d40..f572c7f3c1 100644 --- a/include/ignition/gazebo/apply-joint-force-system/Export.hh +++ b/include/ignition/gazebo/apply-joint-force-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/breadcrumbs-system/Export.hh b/include/ignition/gazebo/breadcrumbs-system/Export.hh index 86d948961a..62736ea5ee 100644 --- a/include/ignition/gazebo/breadcrumbs-system/Export.hh +++ b/include/ignition/gazebo/breadcrumbs-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/buoyancy-engine-system/Export.hh b/include/ignition/gazebo/buoyancy-engine-system/Export.hh index e924c1fd2e..0867a485b0 100644 --- a/include/ignition/gazebo/buoyancy-engine-system/Export.hh +++ b/include/ignition/gazebo/buoyancy-engine-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/buoyancy-system/Export.hh b/include/ignition/gazebo/buoyancy-system/Export.hh index d77f22b136..bcb60f30ef 100644 --- a/include/ignition/gazebo/buoyancy-system/Export.hh +++ b/include/ignition/gazebo/buoyancy-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/camera-video-recorder-system/Export.hh b/include/ignition/gazebo/camera-video-recorder-system/Export.hh index 1aabe72b65..3796fbf62e 100644 --- a/include/ignition/gazebo/camera-video-recorder-system/Export.hh +++ b/include/ignition/gazebo/camera-video-recorder-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/collada-world-exporter-system/Export.hh b/include/ignition/gazebo/collada-world-exporter-system/Export.hh index f0667451f1..6f24741d53 100644 --- a/include/ignition/gazebo/collada-world-exporter-system/Export.hh +++ b/include/ignition/gazebo/collada-world-exporter-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/comms-endpoint-system/Export.hh b/include/ignition/gazebo/comms-endpoint-system/Export.hh index 28a8d222e4..49f5367525 100644 --- a/include/ignition/gazebo/comms-endpoint-system/Export.hh +++ b/include/ignition/gazebo/comms-endpoint-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/comms/Broker.hh b/include/ignition/gazebo/comms/Broker.hh index 2899418e68..c4294d7b00 100644 --- a/include/ignition/gazebo/comms/Broker.hh +++ b/include/ignition/gazebo/comms/Broker.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/comms/ICommsModel.hh b/include/ignition/gazebo/comms/ICommsModel.hh index 52f374d754..a87073e68a 100644 --- a/include/ignition/gazebo/comms/ICommsModel.hh +++ b/include/ignition/gazebo/comms/ICommsModel.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/comms/MsgManager.hh b/include/ignition/gazebo/comms/MsgManager.hh index f2f4dedd69..c11f4d7e4f 100644 --- a/include/ignition/gazebo/comms/MsgManager.hh +++ b/include/ignition/gazebo/comms/MsgManager.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components.hh b/include/ignition/gazebo/components.hh index 1fa43ba294..1efacbd975 100644 --- a/include/ignition/gazebo/components.hh +++ b/include/ignition/gazebo/components.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Actor.hh b/include/ignition/gazebo/components/Actor.hh index e75b2bca67..5dd47b643c 100644 --- a/include/ignition/gazebo/components/Actor.hh +++ b/include/ignition/gazebo/components/Actor.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Actuators.hh b/include/ignition/gazebo/components/Actuators.hh index b23ce86f6a..4365a764eb 100644 --- a/include/ignition/gazebo/components/Actuators.hh +++ b/include/ignition/gazebo/components/Actuators.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/AirPressureSensor.hh b/include/ignition/gazebo/components/AirPressureSensor.hh index 655f3b63bc..1c8318cee8 100644 --- a/include/ignition/gazebo/components/AirPressureSensor.hh +++ b/include/ignition/gazebo/components/AirPressureSensor.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Altimeter.hh b/include/ignition/gazebo/components/Altimeter.hh index c334456b68..155b513e0a 100644 --- a/include/ignition/gazebo/components/Altimeter.hh +++ b/include/ignition/gazebo/components/Altimeter.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/AngularAcceleration.hh b/include/ignition/gazebo/components/AngularAcceleration.hh index ee93231d43..f17971d84c 100644 --- a/include/ignition/gazebo/components/AngularAcceleration.hh +++ b/include/ignition/gazebo/components/AngularAcceleration.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/AngularVelocity.hh b/include/ignition/gazebo/components/AngularVelocity.hh index f48f6f2508..f22762fb8d 100644 --- a/include/ignition/gazebo/components/AngularVelocity.hh +++ b/include/ignition/gazebo/components/AngularVelocity.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/AngularVelocityCmd.hh b/include/ignition/gazebo/components/AngularVelocityCmd.hh index 34fc210c6c..2b683475e6 100644 --- a/include/ignition/gazebo/components/AngularVelocityCmd.hh +++ b/include/ignition/gazebo/components/AngularVelocityCmd.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Atmosphere.hh b/include/ignition/gazebo/components/Atmosphere.hh index e3cf51103e..544f4d495f 100644 --- a/include/ignition/gazebo/components/Atmosphere.hh +++ b/include/ignition/gazebo/components/Atmosphere.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/AxisAlignedBox.hh b/include/ignition/gazebo/components/AxisAlignedBox.hh index d3145dff3f..039aa31584 100644 --- a/include/ignition/gazebo/components/AxisAlignedBox.hh +++ b/include/ignition/gazebo/components/AxisAlignedBox.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/BatterySoC.hh b/include/ignition/gazebo/components/BatterySoC.hh index 03c051b019..e6eaf398dd 100644 --- a/include/ignition/gazebo/components/BatterySoC.hh +++ b/include/ignition/gazebo/components/BatterySoC.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Camera.hh b/include/ignition/gazebo/components/Camera.hh index fcb80e5f51..c4d7bd9928 100644 --- a/include/ignition/gazebo/components/Camera.hh +++ b/include/ignition/gazebo/components/Camera.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/CanonicalLink.hh b/include/ignition/gazebo/components/CanonicalLink.hh index 498033dc27..d948ce335a 100644 --- a/include/ignition/gazebo/components/CanonicalLink.hh +++ b/include/ignition/gazebo/components/CanonicalLink.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/CastShadows.hh b/include/ignition/gazebo/components/CastShadows.hh index 2bd9ac74ae..b7903aa094 100644 --- a/include/ignition/gazebo/components/CastShadows.hh +++ b/include/ignition/gazebo/components/CastShadows.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/CenterOfVolume.hh b/include/ignition/gazebo/components/CenterOfVolume.hh index 2533d59afa..2ff7fe2486 100644 --- a/include/ignition/gazebo/components/CenterOfVolume.hh +++ b/include/ignition/gazebo/components/CenterOfVolume.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/ChildLinkName.hh b/include/ignition/gazebo/components/ChildLinkName.hh index 499eacfebc..91661856a7 100644 --- a/include/ignition/gazebo/components/ChildLinkName.hh +++ b/include/ignition/gazebo/components/ChildLinkName.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Collision.hh b/include/ignition/gazebo/components/Collision.hh index 1eef38ab97..4c4164bcbf 100644 --- a/include/ignition/gazebo/components/Collision.hh +++ b/include/ignition/gazebo/components/Collision.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Component.hh b/include/ignition/gazebo/components/Component.hh index 99090eae54..16934b7446 100644 --- a/include/ignition/gazebo/components/Component.hh +++ b/include/ignition/gazebo/components/Component.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/ContactSensor.hh b/include/ignition/gazebo/components/ContactSensor.hh index 249d90d782..4228636d9a 100644 --- a/include/ignition/gazebo/components/ContactSensor.hh +++ b/include/ignition/gazebo/components/ContactSensor.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/ContactSensorData.hh b/include/ignition/gazebo/components/ContactSensorData.hh index 35dd57e308..49a683749c 100644 --- a/include/ignition/gazebo/components/ContactSensorData.hh +++ b/include/ignition/gazebo/components/ContactSensorData.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/CustomSensor.hh b/include/ignition/gazebo/components/CustomSensor.hh index 92eb76ca68..491a66d342 100644 --- a/include/ignition/gazebo/components/CustomSensor.hh +++ b/include/ignition/gazebo/components/CustomSensor.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/DepthCamera.hh b/include/ignition/gazebo/components/DepthCamera.hh index 40f898213f..87a98b1c97 100644 --- a/include/ignition/gazebo/components/DepthCamera.hh +++ b/include/ignition/gazebo/components/DepthCamera.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/DetachableJoint.hh b/include/ignition/gazebo/components/DetachableJoint.hh index a4543de9e8..8bdd78b6e0 100644 --- a/include/ignition/gazebo/components/DetachableJoint.hh +++ b/include/ignition/gazebo/components/DetachableJoint.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/ExternalWorldWrenchCmd.hh b/include/ignition/gazebo/components/ExternalWorldWrenchCmd.hh index b5b81cdf4d..cf9325774b 100644 --- a/include/ignition/gazebo/components/ExternalWorldWrenchCmd.hh +++ b/include/ignition/gazebo/components/ExternalWorldWrenchCmd.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Factory.hh b/include/ignition/gazebo/components/Factory.hh index 70960ff936..f1bdcf3c51 100644 --- a/include/ignition/gazebo/components/Factory.hh +++ b/include/ignition/gazebo/components/Factory.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/ForceTorque.hh b/include/ignition/gazebo/components/ForceTorque.hh index 9d4fb543f2..9fb7a234c8 100644 --- a/include/ignition/gazebo/components/ForceTorque.hh +++ b/include/ignition/gazebo/components/ForceTorque.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Geometry.hh b/include/ignition/gazebo/components/Geometry.hh index a41545a1fe..a0e90aa3fd 100644 --- a/include/ignition/gazebo/components/Geometry.hh +++ b/include/ignition/gazebo/components/Geometry.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/GpuLidar.hh b/include/ignition/gazebo/components/GpuLidar.hh index 29a9e0a644..99ea4910ea 100644 --- a/include/ignition/gazebo/components/GpuLidar.hh +++ b/include/ignition/gazebo/components/GpuLidar.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Gravity.hh b/include/ignition/gazebo/components/Gravity.hh index 641a967b2b..a30dba52bd 100644 --- a/include/ignition/gazebo/components/Gravity.hh +++ b/include/ignition/gazebo/components/Gravity.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/HaltMotion.hh b/include/ignition/gazebo/components/HaltMotion.hh index 971639b7c8..20dc4123d7 100644 --- a/include/ignition/gazebo/components/HaltMotion.hh +++ b/include/ignition/gazebo/components/HaltMotion.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Imu.hh b/include/ignition/gazebo/components/Imu.hh index 3f13d7e458..9f467becf5 100644 --- a/include/ignition/gazebo/components/Imu.hh +++ b/include/ignition/gazebo/components/Imu.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Inertial.hh b/include/ignition/gazebo/components/Inertial.hh index c3540fa6a0..4f3af29e9a 100644 --- a/include/ignition/gazebo/components/Inertial.hh +++ b/include/ignition/gazebo/components/Inertial.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Joint.hh b/include/ignition/gazebo/components/Joint.hh index a47f7eacec..70bcf2bdb6 100644 --- a/include/ignition/gazebo/components/Joint.hh +++ b/include/ignition/gazebo/components/Joint.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/JointAxis.hh b/include/ignition/gazebo/components/JointAxis.hh index 74db1880de..71e4b2d511 100644 --- a/include/ignition/gazebo/components/JointAxis.hh +++ b/include/ignition/gazebo/components/JointAxis.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/JointEffortLimitsCmd.hh b/include/ignition/gazebo/components/JointEffortLimitsCmd.hh index 15f3ba828b..931e242a98 100644 --- a/include/ignition/gazebo/components/JointEffortLimitsCmd.hh +++ b/include/ignition/gazebo/components/JointEffortLimitsCmd.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/JointForce.hh b/include/ignition/gazebo/components/JointForce.hh index 77228ead23..64d7d27a11 100644 --- a/include/ignition/gazebo/components/JointForce.hh +++ b/include/ignition/gazebo/components/JointForce.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/JointForceCmd.hh b/include/ignition/gazebo/components/JointForceCmd.hh index 6a09320625..2aaa329f42 100644 --- a/include/ignition/gazebo/components/JointForceCmd.hh +++ b/include/ignition/gazebo/components/JointForceCmd.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/JointPosition.hh b/include/ignition/gazebo/components/JointPosition.hh index 44b59c413f..385453a611 100644 --- a/include/ignition/gazebo/components/JointPosition.hh +++ b/include/ignition/gazebo/components/JointPosition.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/JointPositionLimitsCmd.hh b/include/ignition/gazebo/components/JointPositionLimitsCmd.hh index a473233bb3..b53a973a39 100644 --- a/include/ignition/gazebo/components/JointPositionLimitsCmd.hh +++ b/include/ignition/gazebo/components/JointPositionLimitsCmd.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/JointPositionReset.hh b/include/ignition/gazebo/components/JointPositionReset.hh index 18980270e2..6d5424b734 100644 --- a/include/ignition/gazebo/components/JointPositionReset.hh +++ b/include/ignition/gazebo/components/JointPositionReset.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/JointTransmittedWrench.hh b/include/ignition/gazebo/components/JointTransmittedWrench.hh index 2e3ca027a6..a002b650ed 100644 --- a/include/ignition/gazebo/components/JointTransmittedWrench.hh +++ b/include/ignition/gazebo/components/JointTransmittedWrench.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/JointType.hh b/include/ignition/gazebo/components/JointType.hh index 5726dbb164..485b450997 100644 --- a/include/ignition/gazebo/components/JointType.hh +++ b/include/ignition/gazebo/components/JointType.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/JointVelocity.hh b/include/ignition/gazebo/components/JointVelocity.hh index ed796d58b2..4d819c179c 100644 --- a/include/ignition/gazebo/components/JointVelocity.hh +++ b/include/ignition/gazebo/components/JointVelocity.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/JointVelocityCmd.hh b/include/ignition/gazebo/components/JointVelocityCmd.hh index e32439e454..ba0303010b 100644 --- a/include/ignition/gazebo/components/JointVelocityCmd.hh +++ b/include/ignition/gazebo/components/JointVelocityCmd.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/JointVelocityLimitsCmd.hh b/include/ignition/gazebo/components/JointVelocityLimitsCmd.hh index 47857c6f57..3c4846a200 100644 --- a/include/ignition/gazebo/components/JointVelocityLimitsCmd.hh +++ b/include/ignition/gazebo/components/JointVelocityLimitsCmd.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/JointVelocityReset.hh b/include/ignition/gazebo/components/JointVelocityReset.hh index 1a0dca2f1d..f188695787 100644 --- a/include/ignition/gazebo/components/JointVelocityReset.hh +++ b/include/ignition/gazebo/components/JointVelocityReset.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/LaserRetro.hh b/include/ignition/gazebo/components/LaserRetro.hh index a3f2e9b340..8cb6c6f03a 100644 --- a/include/ignition/gazebo/components/LaserRetro.hh +++ b/include/ignition/gazebo/components/LaserRetro.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Level.hh b/include/ignition/gazebo/components/Level.hh index fb6e198180..819141af37 100644 --- a/include/ignition/gazebo/components/Level.hh +++ b/include/ignition/gazebo/components/Level.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/LevelBuffer.hh b/include/ignition/gazebo/components/LevelBuffer.hh index 754116636d..6ad245dad6 100644 --- a/include/ignition/gazebo/components/LevelBuffer.hh +++ b/include/ignition/gazebo/components/LevelBuffer.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/LevelEntityNames.hh b/include/ignition/gazebo/components/LevelEntityNames.hh index 49843dda03..2e5eeaad68 100644 --- a/include/ignition/gazebo/components/LevelEntityNames.hh +++ b/include/ignition/gazebo/components/LevelEntityNames.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Lidar.hh b/include/ignition/gazebo/components/Lidar.hh index 25c7e0f4df..aa9339bbb7 100644 --- a/include/ignition/gazebo/components/Lidar.hh +++ b/include/ignition/gazebo/components/Lidar.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Light.hh b/include/ignition/gazebo/components/Light.hh index c00abe16ee..a0a62df91f 100644 --- a/include/ignition/gazebo/components/Light.hh +++ b/include/ignition/gazebo/components/Light.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/LightCmd.hh b/include/ignition/gazebo/components/LightCmd.hh index 3a2b2a08d0..c2cb26dff6 100644 --- a/include/ignition/gazebo/components/LightCmd.hh +++ b/include/ignition/gazebo/components/LightCmd.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/LightType.hh b/include/ignition/gazebo/components/LightType.hh index 251014747a..cb56882847 100644 --- a/include/ignition/gazebo/components/LightType.hh +++ b/include/ignition/gazebo/components/LightType.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/LinearAcceleration.hh b/include/ignition/gazebo/components/LinearAcceleration.hh index d2a0c1283b..01563a7de5 100644 --- a/include/ignition/gazebo/components/LinearAcceleration.hh +++ b/include/ignition/gazebo/components/LinearAcceleration.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/LinearVelocity.hh b/include/ignition/gazebo/components/LinearVelocity.hh index 563dfa827b..fd7bd5a263 100644 --- a/include/ignition/gazebo/components/LinearVelocity.hh +++ b/include/ignition/gazebo/components/LinearVelocity.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/LinearVelocityCmd.hh b/include/ignition/gazebo/components/LinearVelocityCmd.hh index 210351f0e0..6ac97c57a4 100644 --- a/include/ignition/gazebo/components/LinearVelocityCmd.hh +++ b/include/ignition/gazebo/components/LinearVelocityCmd.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/LinearVelocitySeed.hh b/include/ignition/gazebo/components/LinearVelocitySeed.hh index 48aa591af7..3786c3d347 100644 --- a/include/ignition/gazebo/components/LinearVelocitySeed.hh +++ b/include/ignition/gazebo/components/LinearVelocitySeed.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Link.hh b/include/ignition/gazebo/components/Link.hh index 3c170d1622..81d6cd6bd9 100644 --- a/include/ignition/gazebo/components/Link.hh +++ b/include/ignition/gazebo/components/Link.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/LogPlaybackStatistics.hh b/include/ignition/gazebo/components/LogPlaybackStatistics.hh index abce6139f3..3dd3132115 100644 --- a/include/ignition/gazebo/components/LogPlaybackStatistics.hh +++ b/include/ignition/gazebo/components/LogPlaybackStatistics.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/LogicalAudio.hh b/include/ignition/gazebo/components/LogicalAudio.hh index d78788e8d8..24d5d30680 100644 --- a/include/ignition/gazebo/components/LogicalAudio.hh +++ b/include/ignition/gazebo/components/LogicalAudio.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/LogicalCamera.hh b/include/ignition/gazebo/components/LogicalCamera.hh index aa58cd305f..4e05761b85 100644 --- a/include/ignition/gazebo/components/LogicalCamera.hh +++ b/include/ignition/gazebo/components/LogicalCamera.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/MagneticField.hh b/include/ignition/gazebo/components/MagneticField.hh index ed0563b2f3..fdf16c71f1 100644 --- a/include/ignition/gazebo/components/MagneticField.hh +++ b/include/ignition/gazebo/components/MagneticField.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Magnetometer.hh b/include/ignition/gazebo/components/Magnetometer.hh index c169f80c0f..3b133ec48e 100644 --- a/include/ignition/gazebo/components/Magnetometer.hh +++ b/include/ignition/gazebo/components/Magnetometer.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Material.hh b/include/ignition/gazebo/components/Material.hh index d5a8e3b3bd..7e88bbeed9 100644 --- a/include/ignition/gazebo/components/Material.hh +++ b/include/ignition/gazebo/components/Material.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Model.hh b/include/ignition/gazebo/components/Model.hh index d407ef8f43..bd7383fbe0 100644 --- a/include/ignition/gazebo/components/Model.hh +++ b/include/ignition/gazebo/components/Model.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Name.hh b/include/ignition/gazebo/components/Name.hh index c6b774c39a..f75e3015ce 100644 --- a/include/ignition/gazebo/components/Name.hh +++ b/include/ignition/gazebo/components/Name.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/NavSat.hh b/include/ignition/gazebo/components/NavSat.hh index 30f3a2b57e..b35ee01d70 100644 --- a/include/ignition/gazebo/components/NavSat.hh +++ b/include/ignition/gazebo/components/NavSat.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/ParentEntity.hh b/include/ignition/gazebo/components/ParentEntity.hh index f3e7578a93..79173905eb 100644 --- a/include/ignition/gazebo/components/ParentEntity.hh +++ b/include/ignition/gazebo/components/ParentEntity.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/ParentLinkName.hh b/include/ignition/gazebo/components/ParentLinkName.hh index 9424dea870..cbab2f081f 100644 --- a/include/ignition/gazebo/components/ParentLinkName.hh +++ b/include/ignition/gazebo/components/ParentLinkName.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/ParticleEmitter.hh b/include/ignition/gazebo/components/ParticleEmitter.hh index e484e7a80e..368bfe1f9d 100644 --- a/include/ignition/gazebo/components/ParticleEmitter.hh +++ b/include/ignition/gazebo/components/ParticleEmitter.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Performer.hh b/include/ignition/gazebo/components/Performer.hh index b592b4243b..dc60e61613 100644 --- a/include/ignition/gazebo/components/Performer.hh +++ b/include/ignition/gazebo/components/Performer.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/PerformerAffinity.hh b/include/ignition/gazebo/components/PerformerAffinity.hh index e84799069b..186b834b83 100644 --- a/include/ignition/gazebo/components/PerformerAffinity.hh +++ b/include/ignition/gazebo/components/PerformerAffinity.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/PerformerLevels.hh b/include/ignition/gazebo/components/PerformerLevels.hh index d60eb9f76c..03648c0bd3 100644 --- a/include/ignition/gazebo/components/PerformerLevels.hh +++ b/include/ignition/gazebo/components/PerformerLevels.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Physics.hh b/include/ignition/gazebo/components/Physics.hh index 63c9f46108..faec6b62b9 100644 --- a/include/ignition/gazebo/components/Physics.hh +++ b/include/ignition/gazebo/components/Physics.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/PhysicsCmd.hh b/include/ignition/gazebo/components/PhysicsCmd.hh index 1597853b7e..cf27eb0671 100644 --- a/include/ignition/gazebo/components/PhysicsCmd.hh +++ b/include/ignition/gazebo/components/PhysicsCmd.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/PhysicsEnginePlugin.hh b/include/ignition/gazebo/components/PhysicsEnginePlugin.hh index 983133652a..26bffcc5da 100644 --- a/include/ignition/gazebo/components/PhysicsEnginePlugin.hh +++ b/include/ignition/gazebo/components/PhysicsEnginePlugin.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Pose.hh b/include/ignition/gazebo/components/Pose.hh index 892b3d0fda..70ead7afa2 100644 --- a/include/ignition/gazebo/components/Pose.hh +++ b/include/ignition/gazebo/components/Pose.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/PoseCmd.hh b/include/ignition/gazebo/components/PoseCmd.hh index 76ef1e5368..98bec934cc 100644 --- a/include/ignition/gazebo/components/PoseCmd.hh +++ b/include/ignition/gazebo/components/PoseCmd.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Recreate.hh b/include/ignition/gazebo/components/Recreate.hh index 7025f6dc55..e9d2ddd421 100644 --- a/include/ignition/gazebo/components/Recreate.hh +++ b/include/ignition/gazebo/components/Recreate.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/RenderEngineGuiPlugin.hh b/include/ignition/gazebo/components/RenderEngineGuiPlugin.hh index 73327aec12..8aa737d4be 100644 --- a/include/ignition/gazebo/components/RenderEngineGuiPlugin.hh +++ b/include/ignition/gazebo/components/RenderEngineGuiPlugin.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/RenderEngineServerHeadless.hh b/include/ignition/gazebo/components/RenderEngineServerHeadless.hh index 6dcd1f2c20..ae0bd6adba 100644 --- a/include/ignition/gazebo/components/RenderEngineServerHeadless.hh +++ b/include/ignition/gazebo/components/RenderEngineServerHeadless.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/RenderEngineServerPlugin.hh b/include/ignition/gazebo/components/RenderEngineServerPlugin.hh index 9654cd2163..a733729949 100644 --- a/include/ignition/gazebo/components/RenderEngineServerPlugin.hh +++ b/include/ignition/gazebo/components/RenderEngineServerPlugin.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/RgbdCamera.hh b/include/ignition/gazebo/components/RgbdCamera.hh index dd6da98046..8d790d5da9 100644 --- a/include/ignition/gazebo/components/RgbdCamera.hh +++ b/include/ignition/gazebo/components/RgbdCamera.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Scene.hh b/include/ignition/gazebo/components/Scene.hh index c1b674f3ef..89b6bb02f1 100644 --- a/include/ignition/gazebo/components/Scene.hh +++ b/include/ignition/gazebo/components/Scene.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/SegmentationCamera.hh b/include/ignition/gazebo/components/SegmentationCamera.hh index 41f42e5c2a..4769aa70b3 100644 --- a/include/ignition/gazebo/components/SegmentationCamera.hh +++ b/include/ignition/gazebo/components/SegmentationCamera.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/SelfCollide.hh b/include/ignition/gazebo/components/SelfCollide.hh index 717e89d6b3..4e59d3ac83 100644 --- a/include/ignition/gazebo/components/SelfCollide.hh +++ b/include/ignition/gazebo/components/SelfCollide.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/SemanticLabel.hh b/include/ignition/gazebo/components/SemanticLabel.hh index 32544cf4a4..271d5e9e74 100644 --- a/include/ignition/gazebo/components/SemanticLabel.hh +++ b/include/ignition/gazebo/components/SemanticLabel.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Sensor.hh b/include/ignition/gazebo/components/Sensor.hh index e2653e464d..b847682495 100644 --- a/include/ignition/gazebo/components/Sensor.hh +++ b/include/ignition/gazebo/components/Sensor.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Serialization.hh b/include/ignition/gazebo/components/Serialization.hh index 569ad6b854..7543a9176f 100644 --- a/include/ignition/gazebo/components/Serialization.hh +++ b/include/ignition/gazebo/components/Serialization.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/SlipComplianceCmd.hh b/include/ignition/gazebo/components/SlipComplianceCmd.hh index f511bd66f4..088abd3466 100644 --- a/include/ignition/gazebo/components/SlipComplianceCmd.hh +++ b/include/ignition/gazebo/components/SlipComplianceCmd.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/SourceFilePath.hh b/include/ignition/gazebo/components/SourceFilePath.hh index d9695770fc..83618aa260 100644 --- a/include/ignition/gazebo/components/SourceFilePath.hh +++ b/include/ignition/gazebo/components/SourceFilePath.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/SphericalCoordinates.hh b/include/ignition/gazebo/components/SphericalCoordinates.hh index b3311d0bce..410e62b829 100644 --- a/include/ignition/gazebo/components/SphericalCoordinates.hh +++ b/include/ignition/gazebo/components/SphericalCoordinates.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Static.hh b/include/ignition/gazebo/components/Static.hh index 0d1d15e05e..e6d09eb770 100644 --- a/include/ignition/gazebo/components/Static.hh +++ b/include/ignition/gazebo/components/Static.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Temperature.hh b/include/ignition/gazebo/components/Temperature.hh index 3c59e36f1e..a13434f982 100644 --- a/include/ignition/gazebo/components/Temperature.hh +++ b/include/ignition/gazebo/components/Temperature.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/TemperatureRange.hh b/include/ignition/gazebo/components/TemperatureRange.hh index 649f12632c..ba2c074805 100644 --- a/include/ignition/gazebo/components/TemperatureRange.hh +++ b/include/ignition/gazebo/components/TemperatureRange.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/ThermalCamera.hh b/include/ignition/gazebo/components/ThermalCamera.hh index 5ccac3b89c..57750ef889 100644 --- a/include/ignition/gazebo/components/ThermalCamera.hh +++ b/include/ignition/gazebo/components/ThermalCamera.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/ThreadPitch.hh b/include/ignition/gazebo/components/ThreadPitch.hh index 090d8166fb..8dc7773f39 100644 --- a/include/ignition/gazebo/components/ThreadPitch.hh +++ b/include/ignition/gazebo/components/ThreadPitch.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Transparency.hh b/include/ignition/gazebo/components/Transparency.hh index c216c6a3e3..8338de8d8b 100644 --- a/include/ignition/gazebo/components/Transparency.hh +++ b/include/ignition/gazebo/components/Transparency.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Visibility.hh b/include/ignition/gazebo/components/Visibility.hh index bafe2c811d..8ec5e83e4b 100644 --- a/include/ignition/gazebo/components/Visibility.hh +++ b/include/ignition/gazebo/components/Visibility.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Visual.hh b/include/ignition/gazebo/components/Visual.hh index 515bf9b3b7..43b659d732 100644 --- a/include/ignition/gazebo/components/Visual.hh +++ b/include/ignition/gazebo/components/Visual.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/VisualCmd.hh b/include/ignition/gazebo/components/VisualCmd.hh index 15273e1b8b..405abc6501 100644 --- a/include/ignition/gazebo/components/VisualCmd.hh +++ b/include/ignition/gazebo/components/VisualCmd.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Volume.hh b/include/ignition/gazebo/components/Volume.hh index 25c9a9e084..fb205c1ed4 100644 --- a/include/ignition/gazebo/components/Volume.hh +++ b/include/ignition/gazebo/components/Volume.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/WheelSlipCmd.hh b/include/ignition/gazebo/components/WheelSlipCmd.hh index 95eaeb3f4d..79c513ea40 100644 --- a/include/ignition/gazebo/components/WheelSlipCmd.hh +++ b/include/ignition/gazebo/components/WheelSlipCmd.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/WideAngleCamera.hh b/include/ignition/gazebo/components/WideAngleCamera.hh index 320a8bc254..33ee25c4c0 100644 --- a/include/ignition/gazebo/components/WideAngleCamera.hh +++ b/include/ignition/gazebo/components/WideAngleCamera.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/Wind.hh b/include/ignition/gazebo/components/Wind.hh index b7334c02aa..e86429df7a 100644 --- a/include/ignition/gazebo/components/Wind.hh +++ b/include/ignition/gazebo/components/Wind.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/WindMode.hh b/include/ignition/gazebo/components/WindMode.hh index 4e11890759..ff823d10a2 100644 --- a/include/ignition/gazebo/components/WindMode.hh +++ b/include/ignition/gazebo/components/WindMode.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/components/World.hh b/include/ignition/gazebo/components/World.hh index 348ffc5ad1..3a245b44d4 100644 --- a/include/ignition/gazebo/components/World.hh +++ b/include/ignition/gazebo/components/World.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/config.hh b/include/ignition/gazebo/config.hh index aac0833a39..f8085546d5 100644 --- a/include/ignition/gazebo/config.hh +++ b/include/ignition/gazebo/config.hh @@ -15,4 +15,40 @@ * */ +#ifndef IGNITION_GAZEBO__CONFIG_HH_ +#define IGNITION_GAZEBO__CONFIG_HH_ + #include + +#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 + +namespace gz +{ +} + +namespace ignition +{ + #ifndef SUPPRESS_IGNITION_HEADER_DEPRECATION + #pragma message("ignition namespace is deprecated! Use gz instead!") + #endif + using namespace gz; +} + +#endif diff --git a/include/ignition/gazebo/contact-system/Export.hh b/include/ignition/gazebo/contact-system/Export.hh index c885f03cb3..4bc5c4ba8e 100644 --- a/include/ignition/gazebo/contact-system/Export.hh +++ b/include/ignition/gazebo/contact-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/detachable-joint-system/Export.hh b/include/ignition/gazebo/detachable-joint-system/Export.hh index 325b083ae8..009e5e9485 100644 --- a/include/ignition/gazebo/detachable-joint-system/Export.hh +++ b/include/ignition/gazebo/detachable-joint-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/diff-drive-system/Export.hh b/include/ignition/gazebo/diff-drive-system/Export.hh index a8dac2ff74..c0c2c2f523 100644 --- a/include/ignition/gazebo/diff-drive-system/Export.hh +++ b/include/ignition/gazebo/diff-drive-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/elevator-system/Export.hh b/include/ignition/gazebo/elevator-system/Export.hh index 92858c38a6..4f3a767fc1 100644 --- a/include/ignition/gazebo/elevator-system/Export.hh +++ b/include/ignition/gazebo/elevator-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/follow-actor-system/Export.hh b/include/ignition/gazebo/follow-actor-system/Export.hh index cd27bebf3d..166eec005a 100644 --- a/include/ignition/gazebo/follow-actor-system/Export.hh +++ b/include/ignition/gazebo/follow-actor-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/forcetorque-system/Export.hh b/include/ignition/gazebo/forcetorque-system/Export.hh index 30611323d9..1307c72e49 100644 --- a/include/ignition/gazebo/forcetorque-system/Export.hh +++ b/include/ignition/gazebo/forcetorque-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/gui/Export.hh b/include/ignition/gazebo/gui/Export.hh index eeaaabfc20..00d93deca9 100644 --- a/include/ignition/gazebo/gui/Export.hh +++ b/include/ignition/gazebo/gui/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/gui/Gui.hh b/include/ignition/gazebo/gui/Gui.hh index b44b094822..ccbd2f30b9 100644 --- a/include/ignition/gazebo/gui/Gui.hh +++ b/include/ignition/gazebo/gui/Gui.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/gui/GuiEvents.hh b/include/ignition/gazebo/gui/GuiEvents.hh index 1743985ac2..234b78047b 100644 --- a/include/ignition/gazebo/gui/GuiEvents.hh +++ b/include/ignition/gazebo/gui/GuiEvents.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/gui/GuiSystem.hh b/include/ignition/gazebo/gui/GuiSystem.hh index d6c00d30c8..b35b81fa92 100644 --- a/include/ignition/gazebo/gui/GuiSystem.hh +++ b/include/ignition/gazebo/gui/GuiSystem.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/hydrodynamics-system/Export.hh b/include/ignition/gazebo/hydrodynamics-system/Export.hh index 89011143be..a1cc8901f4 100644 --- a/include/ignition/gazebo/hydrodynamics-system/Export.hh +++ b/include/ignition/gazebo/hydrodynamics-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/ign/Export.hh b/include/ignition/gazebo/ign/Export.hh index 5c986316d0..a54496c792 100644 --- a/include/ignition/gazebo/ign/Export.hh +++ b/include/ignition/gazebo/ign/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/imu-system/Export.hh b/include/ignition/gazebo/imu-system/Export.hh index 6e13f376ad..3297991023 100644 --- a/include/ignition/gazebo/imu-system/Export.hh +++ b/include/ignition/gazebo/imu-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/joint-controller-system/Export.hh b/include/ignition/gazebo/joint-controller-system/Export.hh index 7d518bd851..60bde96540 100644 --- a/include/ignition/gazebo/joint-controller-system/Export.hh +++ b/include/ignition/gazebo/joint-controller-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/joint-position-controller-system/Export.hh b/include/ignition/gazebo/joint-position-controller-system/Export.hh index 2d1d57229e..83b02db5b9 100644 --- a/include/ignition/gazebo/joint-position-controller-system/Export.hh +++ b/include/ignition/gazebo/joint-position-controller-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/joint-state-publisher-system/Export.hh b/include/ignition/gazebo/joint-state-publisher-system/Export.hh index 47be202fd7..0a97d304b4 100644 --- a/include/ignition/gazebo/joint-state-publisher-system/Export.hh +++ b/include/ignition/gazebo/joint-state-publisher-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/joint-trajectory-controller-system/Export.hh b/include/ignition/gazebo/joint-trajectory-controller-system/Export.hh index 99aa8f9cda..1415f26e7d 100644 --- a/include/ignition/gazebo/joint-trajectory-controller-system/Export.hh +++ b/include/ignition/gazebo/joint-trajectory-controller-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/kinetic-energy-monitor-system/Export.hh b/include/ignition/gazebo/kinetic-energy-monitor-system/Export.hh index bdbd41008d..785d8a30d6 100644 --- a/include/ignition/gazebo/kinetic-energy-monitor-system/Export.hh +++ b/include/ignition/gazebo/kinetic-energy-monitor-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/label-system/Export.hh b/include/ignition/gazebo/label-system/Export.hh index dcb2bde338..e0d31bba22 100644 --- a/include/ignition/gazebo/label-system/Export.hh +++ b/include/ignition/gazebo/label-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/lift-drag-system/Export.hh b/include/ignition/gazebo/lift-drag-system/Export.hh index ca6adba4e8..3ec1e55260 100644 --- a/include/ignition/gazebo/lift-drag-system/Export.hh +++ b/include/ignition/gazebo/lift-drag-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/linearbatteryplugin-system/Export.hh b/include/ignition/gazebo/linearbatteryplugin-system/Export.hh index 49ca52a9df..3c57ecdd44 100644 --- a/include/ignition/gazebo/linearbatteryplugin-system/Export.hh +++ b/include/ignition/gazebo/linearbatteryplugin-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/log-system/Export.hh b/include/ignition/gazebo/log-system/Export.hh index 438e6d766b..3d16d058f6 100644 --- a/include/ignition/gazebo/log-system/Export.hh +++ b/include/ignition/gazebo/log-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/log-video-recorder-system/Export.hh b/include/ignition/gazebo/log-video-recorder-system/Export.hh index 7ffdb9d99d..f9dca5ae69 100644 --- a/include/ignition/gazebo/log-video-recorder-system/Export.hh +++ b/include/ignition/gazebo/log-video-recorder-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/logical-camera-system/Export.hh b/include/ignition/gazebo/logical-camera-system/Export.hh index 8fd99ac33a..5eafafc63a 100644 --- a/include/ignition/gazebo/logical-camera-system/Export.hh +++ b/include/ignition/gazebo/logical-camera-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/logicalaudiosensorplugin-system/Export.hh b/include/ignition/gazebo/logicalaudiosensorplugin-system/Export.hh index e3d9dbbda0..43290664f1 100644 --- a/include/ignition/gazebo/logicalaudiosensorplugin-system/Export.hh +++ b/include/ignition/gazebo/logicalaudiosensorplugin-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/magnetometer-system/Export.hh b/include/ignition/gazebo/magnetometer-system/Export.hh index 6afb987649..83bed9d98c 100644 --- a/include/ignition/gazebo/magnetometer-system/Export.hh +++ b/include/ignition/gazebo/magnetometer-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/mecanum-drive-system/Export.hh b/include/ignition/gazebo/mecanum-drive-system/Export.hh index 904dd2362f..dc11b72559 100644 --- a/include/ignition/gazebo/mecanum-drive-system/Export.hh +++ b/include/ignition/gazebo/mecanum-drive-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/model-photo-shoot-system/Export.hh b/include/ignition/gazebo/model-photo-shoot-system/Export.hh index b1ba881618..867b534e95 100644 --- a/include/ignition/gazebo/model-photo-shoot-system/Export.hh +++ b/include/ignition/gazebo/model-photo-shoot-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/multicopter-control-system/Export.hh b/include/ignition/gazebo/multicopter-control-system/Export.hh index 816a30c54a..5d36126af1 100644 --- a/include/ignition/gazebo/multicopter-control-system/Export.hh +++ b/include/ignition/gazebo/multicopter-control-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/multicopter-motor-model-system/Export.hh b/include/ignition/gazebo/multicopter-motor-model-system/Export.hh index 4a7356321b..247da7a23b 100644 --- a/include/ignition/gazebo/multicopter-motor-model-system/Export.hh +++ b/include/ignition/gazebo/multicopter-motor-model-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/navsat-system/Export.hh b/include/ignition/gazebo/navsat-system/Export.hh index 673a88d047..60a891a16d 100644 --- a/include/ignition/gazebo/navsat-system/Export.hh +++ b/include/ignition/gazebo/navsat-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/odometry-publisher-system/Export.hh b/include/ignition/gazebo/odometry-publisher-system/Export.hh index 073971ad16..27558e10f4 100644 --- a/include/ignition/gazebo/odometry-publisher-system/Export.hh +++ b/include/ignition/gazebo/odometry-publisher-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/opticaltactileplugin-system/Export.hh b/include/ignition/gazebo/opticaltactileplugin-system/Export.hh index 8e0c40055f..5ee38429f1 100644 --- a/include/ignition/gazebo/opticaltactileplugin-system/Export.hh +++ b/include/ignition/gazebo/opticaltactileplugin-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/particle-emitter-system/Export.hh b/include/ignition/gazebo/particle-emitter-system/Export.hh index ceda31a777..65dc30f9e1 100644 --- a/include/ignition/gazebo/particle-emitter-system/Export.hh +++ b/include/ignition/gazebo/particle-emitter-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/particle-emitter2-system/Export.hh b/include/ignition/gazebo/particle-emitter2-system/Export.hh index 7f2248edf5..4cf655fbe3 100644 --- a/include/ignition/gazebo/particle-emitter2-system/Export.hh +++ b/include/ignition/gazebo/particle-emitter2-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/perfect-comms-system/Export.hh b/include/ignition/gazebo/perfect-comms-system/Export.hh index 071b92b49f..90548adf00 100644 --- a/include/ignition/gazebo/perfect-comms-system/Export.hh +++ b/include/ignition/gazebo/perfect-comms-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/performer-detector-system/Export.hh b/include/ignition/gazebo/performer-detector-system/Export.hh index e011667885..baeea5cacc 100644 --- a/include/ignition/gazebo/performer-detector-system/Export.hh +++ b/include/ignition/gazebo/performer-detector-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/physics-system/Export.hh b/include/ignition/gazebo/physics-system/Export.hh index b4923f32fd..89de9ac8a1 100644 --- a/include/ignition/gazebo/physics-system/Export.hh +++ b/include/ignition/gazebo/physics-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/physics/Events.hh b/include/ignition/gazebo/physics/Events.hh index a9113fcf9b..a808f19f2f 100644 --- a/include/ignition/gazebo/physics/Events.hh +++ b/include/ignition/gazebo/physics/Events.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/pose-publisher-system/Export.hh b/include/ignition/gazebo/pose-publisher-system/Export.hh index 948fd76e04..9c39026656 100644 --- a/include/ignition/gazebo/pose-publisher-system/Export.hh +++ b/include/ignition/gazebo/pose-publisher-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/rendering/Events.hh b/include/ignition/gazebo/rendering/Events.hh index 574e322854..5f6e8ed387 100644 --- a/include/ignition/gazebo/rendering/Events.hh +++ b/include/ignition/gazebo/rendering/Events.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/rendering/Export.hh b/include/ignition/gazebo/rendering/Export.hh index f2cd7f0185..9c591e1842 100644 --- a/include/ignition/gazebo/rendering/Export.hh +++ b/include/ignition/gazebo/rendering/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/rendering/MarkerManager.hh b/include/ignition/gazebo/rendering/MarkerManager.hh index 2be5ad5724..2397f7bc86 100644 --- a/include/ignition/gazebo/rendering/MarkerManager.hh +++ b/include/ignition/gazebo/rendering/MarkerManager.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/rendering/RenderUtil.hh b/include/ignition/gazebo/rendering/RenderUtil.hh index 7632c22932..781d156d79 100644 --- a/include/ignition/gazebo/rendering/RenderUtil.hh +++ b/include/ignition/gazebo/rendering/RenderUtil.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/rendering/SceneManager.hh b/include/ignition/gazebo/rendering/SceneManager.hh index ee33ec1e10..e2bb50a68a 100644 --- a/include/ignition/gazebo/rendering/SceneManager.hh +++ b/include/ignition/gazebo/rendering/SceneManager.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/rf-comms-system/Export.hh b/include/ignition/gazebo/rf-comms-system/Export.hh index 99d69d7d19..a4af14e09d 100644 --- a/include/ignition/gazebo/rf-comms-system/Export.hh +++ b/include/ignition/gazebo/rf-comms-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/scene-broadcaster-system/Export.hh b/include/ignition/gazebo/scene-broadcaster-system/Export.hh index 7bcd22f2ed..292963308c 100644 --- a/include/ignition/gazebo/scene-broadcaster-system/Export.hh +++ b/include/ignition/gazebo/scene-broadcaster-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/sensors-system/Export.hh b/include/ignition/gazebo/sensors-system/Export.hh index 0b0b660814..eab1c2b6ea 100644 --- a/include/ignition/gazebo/sensors-system/Export.hh +++ b/include/ignition/gazebo/sensors-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/shader-param-system/Export.hh b/include/ignition/gazebo/shader-param-system/Export.hh index 8947c25e2e..237c661875 100644 --- a/include/ignition/gazebo/shader-param-system/Export.hh +++ b/include/ignition/gazebo/shader-param-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/thermal-sensor-system-system/Export.hh b/include/ignition/gazebo/thermal-sensor-system-system/Export.hh index 535a42edd4..85e3294da5 100644 --- a/include/ignition/gazebo/thermal-sensor-system-system/Export.hh +++ b/include/ignition/gazebo/thermal-sensor-system-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/thermal-system/Export.hh b/include/ignition/gazebo/thermal-system/Export.hh index e4e6882761..cfaf2c966c 100644 --- a/include/ignition/gazebo/thermal-system/Export.hh +++ b/include/ignition/gazebo/thermal-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/thruster-system/Export.hh b/include/ignition/gazebo/thruster-system/Export.hh index 90839b80a4..e20b8d200f 100644 --- a/include/ignition/gazebo/thruster-system/Export.hh +++ b/include/ignition/gazebo/thruster-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/touchplugin-system/Export.hh b/include/ignition/gazebo/touchplugin-system/Export.hh index 84d0d161c0..dc607b58e5 100644 --- a/include/ignition/gazebo/touchplugin-system/Export.hh +++ b/include/ignition/gazebo/touchplugin-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/track-controller-system/Export.hh b/include/ignition/gazebo/track-controller-system/Export.hh index 589b590295..8d889cede5 100644 --- a/include/ignition/gazebo/track-controller-system/Export.hh +++ b/include/ignition/gazebo/track-controller-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/tracked-vehicle-system/Export.hh b/include/ignition/gazebo/tracked-vehicle-system/Export.hh index 19cc13cde0..23e09e029c 100644 --- a/include/ignition/gazebo/tracked-vehicle-system/Export.hh +++ b/include/ignition/gazebo/tracked-vehicle-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/trajectory-follower-system/Export.hh b/include/ignition/gazebo/trajectory-follower-system/Export.hh index 68ab970957..081a94f180 100644 --- a/include/ignition/gazebo/trajectory-follower-system/Export.hh +++ b/include/ignition/gazebo/trajectory-follower-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/triggered-publisher-system/Export.hh b/include/ignition/gazebo/triggered-publisher-system/Export.hh index bd1a400fe2..81b88be375 100644 --- a/include/ignition/gazebo/triggered-publisher-system/Export.hh +++ b/include/ignition/gazebo/triggered-publisher-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/user-commands-system/Export.hh b/include/ignition/gazebo/user-commands-system/Export.hh index 1dde646a7b..607ca54f5a 100644 --- a/include/ignition/gazebo/user-commands-system/Export.hh +++ b/include/ignition/gazebo/user-commands-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/velocity-control-system/Export.hh b/include/ignition/gazebo/velocity-control-system/Export.hh index be8d755d17..cf1402da98 100644 --- a/include/ignition/gazebo/velocity-control-system/Export.hh +++ b/include/ignition/gazebo/velocity-control-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/wheel-slip-system/Export.hh b/include/ignition/gazebo/wheel-slip-system/Export.hh index bd7574f521..49a3579b0e 100644 --- a/include/ignition/gazebo/wheel-slip-system/Export.hh +++ b/include/ignition/gazebo/wheel-slip-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/gazebo/wind-effects-system/Export.hh b/include/ignition/gazebo/wind-effects-system/Export.hh index becc087e7a..310dd4e596 100644 --- a/include/ignition/gazebo/wind-effects-system/Export.hh +++ b/include/ignition/gazebo/wind-effects-system/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/python/src/gz/common/Console.cc b/python/src/gz/common/Console.cc index 8d904a4487..e07d490f07 100644 --- a/python/src/gz/common/Console.cc +++ b/python/src/gz/common/Console.cc @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include "Console.hh" -namespace ignition +namespace gz { namespace common { @@ -24,7 +24,7 @@ namespace ignition { void SetVerbosity(int _verbosity) { - ignition::common::Console::SetVerbosity(_verbosity); + gz::common::Console::SetVerbosity(_verbosity); } } } diff --git a/python/src/gz/common/Console.hh b/python/src/gz/common/Console.hh index 4b84fbf514..c1193318dd 100644 --- a/python/src/gz/common/Console.hh +++ b/python/src/gz/common/Console.hh @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef IGNITION_GAZEBO_PYTHON__CONSOLE_HH_ -#define IGNITION_GAZEBO_PYTHON__CONSOLE_HH_ +#ifndef GZ_SIM_PYTHON__CONSOLE_HH_ +#define GZ_SIM_PYTHON__CONSOLE_HH_ #include -namespace ignition +namespace gz { namespace common { diff --git a/python/src/gz/common/_gz_common_pybind11.cc b/python/src/gz/common/_gz_common_pybind11.cc index 12a67670fc..194e4a11da 100644 --- a/python/src/gz/common/_gz_common_pybind11.cc +++ b/python/src/gz/common/_gz_common_pybind11.cc @@ -17,9 +17,9 @@ #include "Console.hh" PYBIND11_MODULE(common, m) { - m.doc() = "Ignition Common Python Library."; + m.doc() = "Gazebo Common Python Library."; m.def( - "set_verbosity", &ignition::common::python::SetVerbosity, + "set_verbosity", &gz::common::python::SetVerbosity, "Set verbosity level."); } diff --git a/python/src/gz/sim/EntityComponentManager.cc b/python/src/gz/sim/EntityComponentManager.cc index 1786ba387c..506c837957 100644 --- a/python/src/gz/sim/EntityComponentManager.cc +++ b/python/src/gz/sim/EntityComponentManager.cc @@ -17,19 +17,19 @@ #include "EntityComponentManager.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace python { ///////////////////////////////////////////////// void defineGazeboEntityComponentManager(pybind11::object module) { - pybind11::class_( + pybind11::class_( module, "EntityComponentManager") .def(pybind11::init<>()); } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/python/src/gz/sim/EntityComponentManager.hh b/python/src/gz/sim/EntityComponentManager.hh index b982483631..d0c0cb145c 100644 --- a/python/src/gz/sim/EntityComponentManager.hh +++ b/python/src/gz/sim/EntityComponentManager.hh @@ -14,27 +14,27 @@ * limitations under the License. */ -#ifndef IGNITION_GAZEBO_PYTHON__ENTITY_COMPONENT_MANAGER_HH_ -#define IGNITION_GAZEBO_PYTHON__ENTITY_COMPONENT_MANAGER_HH_ +#ifndef GZ_SIM_PYTHON__ENTITY_COMPONENT_MANAGER_HH_ +#define GZ_SIM_PYTHON__ENTITY_COMPONENT_MANAGER_HH_ #include -#include "ignition/gazebo/EntityComponentManager.hh" +#include "gz/sim/EntityComponentManager.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace python { -/// Define a pybind11 wrapper for an ignition::gazebo::EntityComponentManager +/// Define a pybind11 wrapper for an gz::sim::EntityComponentManager /** * \param[in] module a pybind11 module to add the definition to */ void defineGazeboEntityComponentManager(pybind11::object module); } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_PYTHON__ENTITY_COMPONENT_MANAGER_HH_ +#endif // GZ_SIM_PYTHON__ENTITY_COMPONENT_MANAGER_HH_ diff --git a/python/src/gz/sim/EventManager.cc b/python/src/gz/sim/EventManager.cc index 39ecbfb8b5..3203893839 100644 --- a/python/src/gz/sim/EventManager.cc +++ b/python/src/gz/sim/EventManager.cc @@ -16,22 +16,22 @@ #include -#include "ignition/gazebo/EventManager.hh" +#include "gz/sim/EventManager.hh" #include "EventManager.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace python { ///////////////////////////////////////////////// void defineGazeboEventManager(pybind11::object module) { - pybind11::class_(module, "EventManager") + pybind11::class_(module, "EventManager") .def(pybind11::init<>()); } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/python/src/gz/sim/EventManager.hh b/python/src/gz/sim/EventManager.hh index bcd177edcb..96bc83c8c6 100644 --- a/python/src/gz/sim/EventManager.hh +++ b/python/src/gz/sim/EventManager.hh @@ -15,25 +15,25 @@ */ -#ifndef IGNITION_GAZEBO_PYTHON__EVENT_MANAGER_HH_ -#define IGNITION_GAZEBO_PYTHON__EVENT_MANAGER_HH_ +#ifndef GZ_SIM_PYTHON__EVENT_MANAGER_HH_ +#define GZ_SIM_PYTHON__EVENT_MANAGER_HH_ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace python { -/// Define a pybind11 wrapper for an ignition::gazebo::EventManager +/// Define a pybind11 wrapper for an gz::sim::EventManager /** * \param[in] module a pybind11 module to add the definition to */ void defineGazeboEventManager(pybind11::object module); } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_PYTHON__EVENT_MANAGER_HH_ +#endif // GZ_SIM_PYTHON__EVENT_MANAGER_HH_ diff --git a/python/src/gz/sim/Server.cc b/python/src/gz/sim/Server.cc index 917560a8ae..1b84654a98 100644 --- a/python/src/gz/sim/Server.cc +++ b/python/src/gz/sim/Server.cc @@ -17,36 +17,36 @@ #include -#include -#include +#include +#include #include "Server.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace python { void defineGazeboServer(pybind11::object module) { - pybind11::class_>(module, "Server") - .def(pybind11::init()) + pybind11::class_>(module, "Server") + .def(pybind11::init()) .def( - "run", &ignition::gazebo::Server::Run, + "run", &gz::sim::Server::Run, "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.") .def( - "has_entity", &ignition::gazebo::Server::HasEntity, + "has_entity", &gz::sim::Server::HasEntity, "Return true if the specified world has an entity with the provided name.") .def( "is_running", - pybind11::overload_cast<>(&ignition::gazebo::Server::Running, pybind11::const_), + pybind11::overload_cast<>(&gz::sim::Server::Running, pybind11::const_), "Get whether the server is running."); } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/python/src/gz/sim/Server.hh b/python/src/gz/sim/Server.hh index 6e969a035b..a46c955cf2 100644 --- a/python/src/gz/sim/Server.hh +++ b/python/src/gz/sim/Server.hh @@ -15,25 +15,25 @@ */ -#ifndef IGNITION_GAZEBO_PYTHON__SERVER_HH_ -#define IGNITION_GAZEBO_PYTHON__SERVER_HH_ +#ifndef GZ_SIM_PYTHON__SERVER_HH_ +#define GZ_SIM_PYTHON__SERVER_HH_ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace python { -/// Define a pybind11 wrapper for an ignition::gazebo::Server +/// Define a pybind11 wrapper for an gz::sim::Server /** * \param[in] module a pybind11 module to add the definition to */ void defineGazeboServer(pybind11::object module); } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_PYTHON__SERVER_HH_ +#endif // GZ_SIM_PYTHON__SERVER_HH_ diff --git a/python/src/gz/sim/ServerConfig.cc b/python/src/gz/sim/ServerConfig.cc index d8b650aff1..c18d3b068d 100644 --- a/python/src/gz/sim/ServerConfig.cc +++ b/python/src/gz/sim/ServerConfig.cc @@ -17,24 +17,24 @@ #include -#include +#include #include "ServerConfig.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace python { void defineGazeboServerConfig(pybind11::object module) { - pybind11::class_(module, "ServerConfig") + pybind11::class_(module, "ServerConfig") .def(pybind11::init<>()) .def( - "set_sdf_file", &ignition::gazebo::ServerConfig::SetSdfFile, + "set_sdf_file", &gz::sim::ServerConfig::SetSdfFile, "Set an SDF file to be used with the server."); } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/python/src/gz/sim/ServerConfig.hh b/python/src/gz/sim/ServerConfig.hh index d955bd5f49..8a75fb2997 100644 --- a/python/src/gz/sim/ServerConfig.hh +++ b/python/src/gz/sim/ServerConfig.hh @@ -15,25 +15,25 @@ */ -#ifndef IGNITION_GAZEBO_PYTHON__SERVER_CONFIG_HH_ -#define IGNITION_GAZEBO_PYTHON__SERVER_CONFIG_HH_ +#ifndef GZ_SIM_PYTHON__SERVER_CONFIG_HH_ +#define GZ_SIM_PYTHON__SERVER_CONFIG_HH_ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace python { -/// Define a pybind11 wrapper for an ignition::gazebo::ServerConfig +/// Define a pybind11 wrapper for an gz::sim::ServerConfig /** * \param[in] module a pybind11 module to add the definition to */ void defineGazeboServerConfig(pybind11::object module); } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_PYTHON__SERVER_CONFIG_HH_ +#endif // GZ_SIM_PYTHON__SERVER_CONFIG_HH_ diff --git a/python/src/gz/sim/TestFixture.cc b/python/src/gz/sim/TestFixture.cc index 7be546716a..4bcd54d45f 100644 --- a/python/src/gz/sim/TestFixture.cc +++ b/python/src/gz/sim/TestFixture.cc @@ -19,13 +19,13 @@ #include "TestFixture.hh" -#include "ignition/gazebo/TestFixture.hh" +#include "gz/sim/TestFixture.hh" #include "wrap_functions.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace python { diff --git a/python/src/gz/sim/TestFixture.hh b/python/src/gz/sim/TestFixture.hh index b355521943..01d29f4104 100644 --- a/python/src/gz/sim/TestFixture.hh +++ b/python/src/gz/sim/TestFixture.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_PYTHON__TEST_FIXTURE_HH_ -#define IGNITION_GAZEBO_PYTHON__TEST_FIXTURE_HH_ +#ifndef GZ_SIM_PYTHON__TEST_FIXTURE_HH_ +#define GZ_SIM_PYTHON__TEST_FIXTURE_HH_ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace python { -/// Define a pybind11 wrapper for an ignition::gazebo::TestFixture +/// Define a pybind11 wrapper for an gz::sim::TestFixture /** * \param[in] module a pybind11 module to add the definition to */ @@ -35,4 +35,4 @@ defineGazeboTestFixture(pybind11::object module); } } -#endif // IGNITION_GAZEBO_PYTHON__TEST_FIXTURE_HH_ +#endif // GZ_SIM_PYTHON__TEST_FIXTURE_HH_ diff --git a/python/src/gz/sim/UpdateInfo.cc b/python/src/gz/sim/UpdateInfo.cc index e31dc7cb92..11462a6111 100644 --- a/python/src/gz/sim/UpdateInfo.cc +++ b/python/src/gz/sim/UpdateInfo.cc @@ -18,26 +18,26 @@ #include #include -#include +#include #include "UpdateInfo.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace python { void defineGazeboUpdateInfo(pybind11::object module) { - pybind11::class_(module, "UpdateInfo") + pybind11::class_(module, "UpdateInfo") .def(pybind11::init<>()) - .def_readwrite("sim_time", &ignition::gazebo::UpdateInfo::simTime) - .def_readwrite("real_time", &ignition::gazebo::UpdateInfo::realTime) - .def_readwrite("dt", &ignition::gazebo::UpdateInfo::dt) - .def_readwrite("paused", &ignition::gazebo::UpdateInfo::paused) - .def_readwrite("iterations", &ignition::gazebo::UpdateInfo::iterations); + .def_readwrite("sim_time", &gz::sim::UpdateInfo::simTime) + .def_readwrite("real_time", &gz::sim::UpdateInfo::realTime) + .def_readwrite("dt", &gz::sim::UpdateInfo::dt) + .def_readwrite("paused", &gz::sim::UpdateInfo::paused) + .def_readwrite("iterations", &gz::sim::UpdateInfo::iterations); } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/python/src/gz/sim/UpdateInfo.hh b/python/src/gz/sim/UpdateInfo.hh index f2ec4e910d..d9462514f5 100644 --- a/python/src/gz/sim/UpdateInfo.hh +++ b/python/src/gz/sim/UpdateInfo.hh @@ -15,25 +15,25 @@ */ -#ifndef IGNITION_GAZEBO_PYTHON__UPDATE_INFO_HH_ -#define IGNITION_GAZEBO_PYTHON__UPDATE_INFO_HH_ +#ifndef GZ_SIM_PYTHON__UPDATE_INFO_HH_ +#define GZ_SIM_PYTHON__UPDATE_INFO_HH_ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace python { -/// Define a pybind11 wrapper for an ignition::gazebo::UpdateInfo +/// Define a pybind11 wrapper for an gz::sim::UpdateInfo /** * \param[in] module a pybind11 module to add the definition to */ void defineGazeboUpdateInfo(pybind11::object module); } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_PYTHON__UPDATE_INFO_HH_ +#endif // GZ_SIM_PYTHON__UPDATE_INFO_HH_ diff --git a/python/src/gz/sim/Util.cc b/python/src/gz/sim/Util.cc index 3dd225f8a7..a502f8b40b 100644 --- a/python/src/gz/sim/Util.cc +++ b/python/src/gz/sim/Util.cc @@ -20,12 +20,12 @@ #include -#include +#include #include "Util.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace python { @@ -33,9 +33,9 @@ void defineGazeboUtil(pybind11::module &_module) { _module.def("world_entity", pybind11::overload_cast( - &ignition::gazebo::worldEntity), + &gz::sim::worldEntity), "Get the first world entity that's found."); } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/python/src/gz/sim/Util.hh b/python/src/gz/sim/Util.hh index 34db116688..519db28ed4 100644 --- a/python/src/gz/sim/Util.hh +++ b/python/src/gz/sim/Util.hh @@ -14,24 +14,24 @@ * limitations under the License. */ -#ifndef IGNITION_GAZEBO_PYTHON__UTIL_HH_ -#define IGNITION_GAZEBO_PYTHON__UTIL_HH_ +#ifndef GZ_SIM_PYTHON__UTIL_HH_ +#define GZ_SIM_PYTHON__UTIL_HH_ #include -#include +#include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace python { -/// Define a pybind11 wrapper for a ignition::gazebo::Util +/// Define a pybind11 wrapper for a gz::sim::Util /// \param[in] _module a pybind11 module to add the definition to void defineGazeboUtil(pybind11::module &_module); } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_PYTHON__WORLD_HH_ +#endif // GZ_SIM_PYTHON__WORLD_HH_ diff --git a/python/src/gz/sim/World.cc b/python/src/gz/sim/World.cc index 6822c12f8f..c2cb5c7a9d 100644 --- a/python/src/gz/sim/World.cc +++ b/python/src/gz/sim/World.cc @@ -22,24 +22,24 @@ #include "World.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace python { void defineGazeboWorld(pybind11::object module) { - pybind11::class_(module, "World") - .def(pybind11::init()) + pybind11::class_(module, "World") + .def(pybind11::init()) .def( - "model_by_name", &ignition::gazebo::World::ModelByName, + "model_by_name", &gz::sim::World::ModelByName, "Get the ID of a model entity which is an immediate child of " " this world.") .def( - "gravity", &ignition::gazebo::World::Gravity, + "gravity", &gz::sim::World::Gravity, "Get the gravity in m/s^2."); } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/python/src/gz/sim/World.hh b/python/src/gz/sim/World.hh index e77e42b4b6..894fad79db 100644 --- a/python/src/gz/sim/World.hh +++ b/python/src/gz/sim/World.hh @@ -14,27 +14,27 @@ * limitations under the License. */ -#ifndef IGNITION_GAZEBO_PYTHON__WORLD_HH_ -#define IGNITION_GAZEBO_PYTHON__WORLD_HH_ +#ifndef GZ_SIM_PYTHON__WORLD_HH_ +#define GZ_SIM_PYTHON__WORLD_HH_ #include -#include +#include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace python { -/// Define a pybind11 wrapper for an ignition::gazebo::World +/// Define a pybind11 wrapper for an gz::sim::World /** * \param[in] module a pybind11 module to add the definition to */ void defineGazeboWorld(pybind11::object module); } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_PYTHON__WORLD_HH_ +#endif // GZ_SIM_PYTHON__WORLD_HH_ diff --git a/python/src/gz/sim/_gz_sim_pybind11.cc b/python/src/gz/sim/_gz_sim_pybind11.cc index 2444a16f02..8a5b62339b 100644 --- a/python/src/gz/sim/_gz_sim_pybind11.cc +++ b/python/src/gz/sim/_gz_sim_pybind11.cc @@ -26,14 +26,14 @@ #include "World.hh" PYBIND11_MODULE(gazebo, m) { - m.doc() = "Ignition Gazebo Python Library."; + m.doc() = "Gazebo Python Library."; - ignition::gazebo::python::defineGazeboEntityComponentManager(m); - ignition::gazebo::python::defineGazeboEventManager(m); - ignition::gazebo::python::defineGazeboServer(m); - ignition::gazebo::python::defineGazeboServerConfig(m); - ignition::gazebo::python::defineGazeboTestFixture(m); - ignition::gazebo::python::defineGazeboUpdateInfo(m); - ignition::gazebo::python::defineGazeboWorld(m); - ignition::gazebo::python::defineGazeboUtil(m); + gz::sim::python::defineGazeboEntityComponentManager(m); + gz::sim::python::defineGazeboEventManager(m); + gz::sim::python::defineGazeboServer(m); + gz::sim::python::defineGazeboServerConfig(m); + gz::sim::python::defineGazeboTestFixture(m); + gz::sim::python::defineGazeboUpdateInfo(m); + gz::sim::python::defineGazeboWorld(m); + gz::sim::python::defineGazeboUtil(m); } diff --git a/python/test/gravity.sdf b/python/test/gravity.sdf index ee1161fa5f..43d46db809 100644 --- a/python/test/gravity.sdf +++ b/python/test/gravity.sdf @@ -3,7 +3,7 @@ + name="gz::sim::systems::Physics"> diff --git a/src/Barrier.cc b/src/Barrier.cc index 97dc9f7b36..eeb2380944 100644 --- a/src/Barrier.cc +++ b/src/Barrier.cc @@ -17,7 +17,7 @@ #include "Barrier.hh" -class ignition::gazebo::BarrierPrivate +class gz::sim::BarrierPrivate { /// \brief Mutex for syncronization public: std::mutex mutex; @@ -38,7 +38,7 @@ class ignition::gazebo::BarrierPrivate public: unsigned int generation{0}; }; -using namespace ignition::gazebo; +using namespace gz::sim; ////////////////////////////////////////////////// Barrier::Barrier(unsigned int _threadCount) diff --git a/src/Barrier.hh b/src/Barrier.hh index 5b9792b722..ac9e738b4a 100644 --- a/src/Barrier.hh +++ b/src/Barrier.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_BARRIER_HH_ -#define IGNITION_GAZEBO_BARRIER_HH_ +#ifndef GZ_SIM_BARRIER_HH_ +#define GZ_SIM_BARRIER_HH_ #include #include @@ -26,12 +26,12 @@ #include #include -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { // Forward declarations. class BarrierPrivate; @@ -44,7 +44,7 @@ namespace ignition /// /// Note that this can likely be replaced once the C++ concurrency TS /// is ratified: https://en.cppreference.com/w/cpp/experimental/barrier - class IGNITION_GAZEBO_VISIBLE Barrier + class GZ_GAZEBO_VISIBLE Barrier { /// \brief Constructor /// \param[in] _threadCount Number of threads to syncronize @@ -89,7 +89,7 @@ namespace ignition private: std::unique_ptr dataPtr; }; } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE - } // namespace gazebo -} // namespace ignition + } // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_BARRIER_HH_ +#endif // GZ_SIM_BARRIER_HH_ diff --git a/src/Barrier_TEST.cc b/src/Barrier_TEST.cc index 8f57127851..1af0c73f8b 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 sim::Barrier::ExitStatus &_ret) { - return _ret == gazebo::Barrier::ExitStatus::CANCELLED; + return _ret == 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); + 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(), 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/BaseView.cc b/src/BaseView.cc index d366d946c7..1128cd854b 100644 --- a/src/BaseView.cc +++ b/src/BaseView.cc @@ -19,8 +19,8 @@ #include "gz/sim/Entity.hh" #include "gz/sim/Types.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace detail; ////////////////////////////////////////////////// diff --git a/src/BaseView_TEST.cc b/src/BaseView_TEST.cc index 0a29c8b58f..e8fd69f865 100644 --- a/src/BaseView_TEST.cc +++ b/src/BaseView_TEST.cc @@ -29,8 +29,8 @@ #include "../test/helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; class BaseViewTest : public InternalFixture<::testing::Test> { diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index a2a39c966e..01ab3b4516 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -166,7 +166,7 @@ add_dependencies(${PROJECT_LIBRARY_TARGET_NAME} gz-sim_private_msgs ) -set(IGNITION_GAZEBO_PLUGIN_INSTALL_DIR +set(GZ_SIM_PLUGIN_INSTALL_DIR ${CMAKE_INSTALL_PREFIX}/${IGN_LIB_INSTALL_DIR}/ign-${IGN_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins ) @@ -209,10 +209,10 @@ foreach(CMD_TEST "BREW_RUBY=\"${BREW_RUBY} \"") target_compile_definitions(${CMD_TEST} PRIVATE - "IGN_PATH=\"${IGNITION-TOOLS2_BINARY_DIRS}\"") + "GZ_PATH=\"${IGNITION-TOOLS2_BINARY_DIRS}\"") set(_env_vars) - list(APPEND _env_vars "IGN_CONFIG_PATH=${CMAKE_BINARY_DIR}/test/conf") + list(APPEND _env_vars "GZ_CONFIG_PATH=${CMAKE_BINARY_DIR}/test/conf") list(APPEND _env_vars "IGN_GAZEBO_SYSTEM_PLUGIN_PATH=$") set_tests_properties(${CMD_TEST} PROPERTIES diff --git a/src/ComponentFactory_TEST.cc b/src/ComponentFactory_TEST.cc index 5d8e1285b8..b1d8f402b5 100644 --- a/src/ComponentFactory_TEST.cc +++ b/src/ComponentFactory_TEST.cc @@ -24,8 +24,8 @@ #include "../test/helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// class ComponentFactoryTest : public InternalFixture<::testing::Test> @@ -123,7 +123,7 @@ TEST_F(ComponentFactoryTest, New) // Test constructing a component with pre-defined data // Test a valid pre-defined component - ignition::math::Pose3d pose(1, 2, 3, 4, 5, 6); + gz::math::Pose3d pose(1, 2, 3, 4, 5, 6); components::Pose poseComp(pose); auto comp = factory->New(components::Pose::typeId, &poseComp); ASSERT_NE(nullptr, comp); diff --git a/src/Component_TEST.cc b/src/Component_TEST.cc index 110282036b..3cbbcfeed4 100644 --- a/src/Component_TEST.cc +++ b/src/Component_TEST.cc @@ -32,8 +32,8 @@ #include "../test/helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ////////////////////////////////////////////////// class ComponentTest : public InternalFixture<::testing::Test> @@ -62,7 +62,7 @@ TEST_F(ComponentTest, ComponentCanBeCopiedAfterDefaultCtor) } ////////////////////////////////////////////////// -// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +// See https://github.com/gazebosim/gz-sim/issues/1175 TEST_F(ComponentTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(DataByMove)) { auto factory = components::Factory::Instance(); @@ -126,7 +126,7 @@ inline std::istream &operator>>(std::istream &_in, sdf::Element &_element) // ostream operator for math::Inertiald (not defined elsewhere) // Note: Must be defined in the correct namespace or clang refuses to find it. -namespace ignition +namespace gz { namespace math { @@ -332,7 +332,7 @@ TEST_F(ComponentTest, OStream) EXPECT_EQ("Mass: 0", ostr.str()); } - // Component with a ignition::msgs type that gets serialized by the default + // Component with a gz::msgs type that gets serialized by the default // serializer { using Custom = components::ComponentMassMatrix().Mass()); } - // Component with a ignition::msgs type that gets deserialized by the message + // Component with a gz::msgs type that gets deserialized by the message // deserializer { using Custom = components::Component -IGNITION_GAZEBO_VISIBLE -msgs::Entity_Type ignition::gazebo::convert(const std::string &_in) +GZ_GAZEBO_VISIBLE +msgs::Entity_Type gz::sim::convert(const std::string &_in) { msgs::Entity_Type out = msgs::Entity_Type_NONE; @@ -115,8 +115,8 @@ msgs::Entity_Type ignition::gazebo::convert(const std::string &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -math::Pose3d ignition::gazebo::convert(const msgs::Pose &_in) +GZ_GAZEBO_VISIBLE +math::Pose3d gz::sim::convert(const msgs::Pose &_in) { math::Pose3d out(_in.position().x(), _in.position().y(), @@ -132,8 +132,8 @@ math::Pose3d ignition::gazebo::convert(const msgs::Pose &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -msgs::Collision ignition::gazebo::convert(const sdf::Collision &_in) +GZ_GAZEBO_VISIBLE +msgs::Collision gz::sim::convert(const sdf::Collision &_in) { msgs::Collision out; out.set_name(_in.Name()); @@ -145,8 +145,8 @@ msgs::Collision ignition::gazebo::convert(const sdf::Collision &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -sdf::Collision ignition::gazebo::convert(const msgs::Collision &_in) +GZ_GAZEBO_VISIBLE +sdf::Collision gz::sim::convert(const msgs::Collision &_in) { sdf::Collision out; out.SetName(_in.name()); @@ -157,8 +157,8 @@ sdf::Collision ignition::gazebo::convert(const msgs::Collision &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -msgs::Geometry ignition::gazebo::convert(const sdf::Geometry &_in) +GZ_GAZEBO_VISIBLE +msgs::Geometry gz::sim::convert(const sdf::Geometry &_in) { msgs::Geometry out; if (_in.Type() == sdf::GeometryType::BOX && _in.BoxShape()) @@ -244,7 +244,7 @@ msgs::Geometry ignition::gazebo::convert(const sdf::Geometry &_in) } else { - ignerr << "Geometry type [" << static_cast(_in.Type()) + gzerr << "Geometry type [" << static_cast(_in.Type()) << "] not supported" << std::endl; } return out; @@ -252,8 +252,8 @@ msgs::Geometry ignition::gazebo::convert(const sdf::Geometry &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -sdf::Geometry ignition::gazebo::convert(const msgs::Geometry &_in) +GZ_GAZEBO_VISIBLE +sdf::Geometry gz::sim::convert(const msgs::Geometry &_in) { sdf::Geometry out; if (_in.type() == msgs::Geometry::BOX && _in.has_box()) @@ -359,7 +359,7 @@ sdf::Geometry ignition::gazebo::convert(const msgs::Geometry &_in) } else { - ignerr << "Geometry type [" << static_cast(_in.type()) + gzerr << "Geometry type [" << static_cast(_in.type()) << "] not supported" << std::endl; } return out; @@ -367,8 +367,8 @@ sdf::Geometry ignition::gazebo::convert(const msgs::Geometry &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -msgs::Material ignition::gazebo::convert(const sdf::Material &_in) +GZ_GAZEBO_VISIBLE +msgs::Material gz::sim::convert(const sdf::Material &_in) { msgs::Material out; msgs::Set(out.mutable_ambient(), _in.Ambient()); @@ -426,8 +426,8 @@ msgs::Material ignition::gazebo::convert(const sdf::Material &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -sdf::Material ignition::gazebo::convert(const msgs::Material &_in) +GZ_GAZEBO_VISIBLE +sdf::Material gz::sim::convert(const msgs::Material &_in) { sdf::Material out; out.SetAmbient(msgs::Convert(_in.ambient())); @@ -469,8 +469,8 @@ sdf::Material ignition::gazebo::convert(const msgs::Material &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -msgs::Actor ignition::gazebo::convert(const sdf::Actor &_in) +GZ_GAZEBO_VISIBLE +msgs::Actor gz::sim::convert(const sdf::Actor &_in) { msgs::Actor out; out.mutable_entity()->set_name(_in.Name()); @@ -509,8 +509,8 @@ msgs::Actor ignition::gazebo::convert(const sdf::Actor &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -sdf::Actor ignition::gazebo::convert(const msgs::Actor &_in) +GZ_GAZEBO_VISIBLE +sdf::Actor gz::sim::convert(const msgs::Actor &_in) { sdf::Actor out; out.SetName(_in.entity().name()); @@ -552,8 +552,8 @@ sdf::Actor ignition::gazebo::convert(const msgs::Actor &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -msgs::Light ignition::gazebo::convert(const sdf::Light &_in) +GZ_GAZEBO_VISIBLE +msgs::Light gz::sim::convert(const sdf::Light &_in) { msgs::Light out; out.set_name(_in.Name()); @@ -584,8 +584,8 @@ msgs::Light ignition::gazebo::convert(const sdf::Light &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -sdf::Light ignition::gazebo::convert(const msgs::Light &_in) +GZ_GAZEBO_VISIBLE +sdf::Light gz::sim::convert(const msgs::Light &_in) { sdf::Light out; out.SetName(_in.name()); @@ -616,8 +616,8 @@ sdf::Light ignition::gazebo::convert(const msgs::Light &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -msgs::GUI ignition::gazebo::convert(const sdf::Gui &_in) +GZ_GAZEBO_VISIBLE +msgs::GUI gz::sim::convert(const sdf::Gui &_in) { msgs::GUI out; @@ -647,7 +647,7 @@ msgs::GUI ignition::gazebo::convert(const sdf::Gui &_in) if (elem->HasElement("camera")) { - ignwarn << " can't be converted yet" << std::endl; + gzwarn << " can't be converted yet" << std::endl; } return out; @@ -655,13 +655,13 @@ msgs::GUI ignition::gazebo::convert(const sdf::Gui &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -msgs::Time ignition::gazebo::convert( +GZ_GAZEBO_VISIBLE +msgs::Time gz::sim::convert( const std::chrono::steady_clock::duration &_in) { msgs::Time out; - auto secNsec = ignition::math::durationToSecNsec(_in); + auto secNsec = gz::math::durationToSecNsec(_in); out.set_sec(secNsec.first); out.set_nsec(secNsec.second); @@ -671,8 +671,8 @@ msgs::Time ignition::gazebo::convert( ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -std::chrono::steady_clock::duration ignition::gazebo::convert( +GZ_GAZEBO_VISIBLE +std::chrono::steady_clock::duration gz::sim::convert( const msgs::Time &_in) { return std::chrono::seconds(_in.sec()) + std::chrono::nanoseconds(_in.nsec()); @@ -680,8 +680,8 @@ std::chrono::steady_clock::duration ignition::gazebo::convert( ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -msgs::Inertial ignition::gazebo::convert(const math::Inertiald &_in) +GZ_GAZEBO_VISIBLE +msgs::Inertial gz::sim::convert(const math::Inertiald &_in) { msgs::Inertial out; msgs::Set(out.mutable_pose(), _in.Pose()); @@ -697,8 +697,8 @@ msgs::Inertial ignition::gazebo::convert(const math::Inertiald &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -math::Inertiald ignition::gazebo::convert(const msgs::Inertial &_in) +GZ_GAZEBO_VISIBLE +math::Inertiald gz::sim::convert(const msgs::Inertial &_in) { math::MassMatrix3d massMatrix; massMatrix.SetMass(_in.mass()); @@ -717,8 +717,8 @@ math::Inertiald ignition::gazebo::convert(const msgs::Inertial &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -msgs::Axis ignition::gazebo::convert(const sdf::JointAxis &_in) +GZ_GAZEBO_VISIBLE +msgs::Axis gz::sim::convert(const sdf::JointAxis &_in) { msgs::Axis out; msgs::Set(out.mutable_xyz(), _in.Xyz()); @@ -747,13 +747,13 @@ msgs::Axis ignition::gazebo::convert(const sdf::JointAxis &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -sdf::JointAxis ignition::gazebo::convert(const msgs::Axis &_in) +GZ_GAZEBO_VISIBLE +sdf::JointAxis gz::sim::convert(const msgs::Axis &_in) { sdf::JointAxis out; sdf::Errors errors = out.SetXyz(msgs::Convert(_in.xyz())); for (const auto &err : errors) { - ignerr << err.Message() << std::endl; + gzerr << err.Message() << std::endl; } out.SetXyzExpressedIn(_in.xyz_expressed_in()); out.SetDamping(_in.damping()); @@ -767,8 +767,8 @@ sdf::JointAxis ignition::gazebo::convert(const msgs::Axis &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -msgs::Scene ignition::gazebo::convert(const sdf::Scene &_in) +GZ_GAZEBO_VISIBLE +msgs::Scene gz::sim::convert(const sdf::Scene &_in) { msgs::Scene out; // todo(anyone) add Name to sdf::Scene? @@ -798,8 +798,8 @@ msgs::Scene ignition::gazebo::convert(const sdf::Scene &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -sdf::Scene ignition::gazebo::convert(const msgs::Scene &_in) +GZ_GAZEBO_VISIBLE +sdf::Scene gz::sim::convert(const msgs::Scene &_in) { sdf::Scene out; // todo(anyone) add SetName to sdf::Scene? @@ -828,8 +828,8 @@ sdf::Scene ignition::gazebo::convert(const msgs::Scene &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -msgs::Atmosphere ignition::gazebo::convert(const sdf::Atmosphere &_in) +GZ_GAZEBO_VISIBLE +msgs::Atmosphere gz::sim::convert(const sdf::Atmosphere &_in) { msgs::Atmosphere out; out.set_temperature(_in.Temperature().Kelvin()); @@ -846,8 +846,8 @@ msgs::Atmosphere ignition::gazebo::convert(const sdf::Atmosphere &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -sdf::Atmosphere ignition::gazebo::convert(const msgs::Atmosphere &_in) +GZ_GAZEBO_VISIBLE +sdf::Atmosphere gz::sim::convert(const msgs::Atmosphere &_in) { sdf::Atmosphere out; out.SetTemperature(math::Temperature(_in.temperature())); @@ -863,17 +863,17 @@ sdf::Atmosphere ignition::gazebo::convert(const msgs::Atmosphere &_in) } ////////////////////////////////////////////////// -void ignition::gazebo::set(msgs::Time *_msg, +void gz::sim::set(msgs::Time *_msg, const std::chrono::steady_clock::duration &_in) { - auto secNsec = ignition::math::durationToSecNsec(_in); + auto secNsec = gz::math::durationToSecNsec(_in); _msg->set_sec(secNsec.first); _msg->set_nsec(secNsec.second); } ////////////////////////////////////////////////// -void ignition::gazebo::set(msgs::WorldStatistics *_msg, - const gazebo::UpdateInfo &_in) +void gz::sim::set(msgs::WorldStatistics *_msg, + const sim::UpdateInfo &_in) { set(_msg->mutable_sim_time(), _in.simTime); set(_msg->mutable_real_time(), _in.realTime); @@ -884,8 +884,8 @@ void ignition::gazebo::set(msgs::WorldStatistics *_msg, ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -msgs::Physics ignition::gazebo::convert(const sdf::Physics &_in) +GZ_GAZEBO_VISIBLE +msgs::Physics gz::sim::convert(const sdf::Physics &_in) { msgs::Physics out; out.set_max_step_size(_in.MaxStepSize()); @@ -895,8 +895,8 @@ msgs::Physics ignition::gazebo::convert(const sdf::Physics &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -sdf::Physics ignition::gazebo::convert(const msgs::Physics &_in) +GZ_GAZEBO_VISIBLE +sdf::Physics gz::sim::convert(const msgs::Physics &_in) { sdf::Physics out; out.SetRealTimeFactor(_in.real_time_factor()); @@ -905,7 +905,7 @@ sdf::Physics ignition::gazebo::convert(const msgs::Physics &_in) } ////////////////////////////////////////////////// -void ignition::gazebo::set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf) +void gz::sim::set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf) { switch (_sdf.Type()) { @@ -932,7 +932,7 @@ void ignition::gazebo::set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf) } ////////////////////////////////////////////////// -std::string ignition::gazebo::convert(const sdf::LightType &_in) +std::string gz::sim::convert(const sdf::LightType &_in) { if (_in == sdf::LightType::POINT) { @@ -950,7 +950,7 @@ std::string ignition::gazebo::convert(const sdf::LightType &_in) } ////////////////////////////////////////////////// -sdf::LightType ignition::gazebo::convert(const std::string &_in) +sdf::LightType gz::sim::convert(const std::string &_in) { std::string inLowerCase = _in; std::transform(_in.begin(), _in.end(), inLowerCase.begin(), ::tolower); @@ -971,8 +971,8 @@ sdf::LightType ignition::gazebo::convert(const std::string &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -sdf::Noise ignition::gazebo::convert(const msgs::SensorNoise &_in) +GZ_GAZEBO_VISIBLE +sdf::Noise gz::sim::convert(const msgs::SensorNoise &_in) { sdf::Noise out; @@ -1004,8 +1004,8 @@ sdf::Noise ignition::gazebo::convert(const msgs::SensorNoise &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) +GZ_GAZEBO_VISIBLE +msgs::Sensor gz::sim::convert(const sdf::Sensor &_in) { msgs::Sensor out; out.set_name(_in.Name()); @@ -1021,23 +1021,23 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) msgs::MagnetometerSensor *sensor = out.mutable_magnetometer(); if (_in.MagnetometerSensor()->XNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_x_noise(), + gz::sim::set(sensor->mutable_x_noise(), _in.MagnetometerSensor()->XNoise()); } if (_in.MagnetometerSensor()->YNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_y_noise(), + gz::sim::set(sensor->mutable_y_noise(), _in.MagnetometerSensor()->YNoise()); } if (_in.MagnetometerSensor()->ZNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_z_noise(), + gz::sim::set(sensor->mutable_z_noise(), _in.MagnetometerSensor()->ZNoise()); } } else { - ignerr << "Attempting to convert a magnetometer SDF sensor, but the " + gzerr << "Attempting to convert a magnetometer SDF sensor, but the " << "sensor pointer is null.\n"; } } @@ -1068,7 +1068,7 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) } else { - ignerr << "Attempting to convert a camera SDF sensor, but the " + gzerr << "Attempting to convert a camera SDF sensor, but the " << "sensor pointer is null.\n"; } } @@ -1084,29 +1084,29 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) if (sdfSensor->HorizontalPositionNoise().Type() != sdf::NoiseType::NONE) { - gazebo::set(sensor->mutable_position()->mutable_horizontal_noise(), + sim::set(sensor->mutable_position()->mutable_horizontal_noise(), sdfSensor->HorizontalPositionNoise()); } if (sdfSensor->VerticalPositionNoise().Type() != sdf::NoiseType::NONE) { - gazebo::set(sensor->mutable_position()->mutable_vertical_noise(), + sim::set(sensor->mutable_position()->mutable_vertical_noise(), sdfSensor->VerticalPositionNoise()); } if (sdfSensor->HorizontalVelocityNoise().Type() != sdf::NoiseType::NONE) { - gazebo::set(sensor->mutable_velocity()->mutable_horizontal_noise(), + sim::set(sensor->mutable_velocity()->mutable_horizontal_noise(), sdfSensor->HorizontalVelocityNoise()); } if (sdfSensor->VerticalVelocityNoise().Type() != sdf::NoiseType::NONE) { - gazebo::set(sensor->mutable_velocity()->mutable_vertical_noise(), + sim::set(sensor->mutable_velocity()->mutable_vertical_noise(), sdfSensor->VerticalVelocityNoise()); } } else { - ignerr << "Attempting to convert a NavSat SDF sensor, but the " + gzerr << "Attempting to convert a NavSat SDF sensor, but the " << "sensor pointer is null.\n"; } } @@ -1119,19 +1119,19 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) if (_in.AltimeterSensor()->VerticalPositionNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_vertical_position_noise(), + gz::sim::set(sensor->mutable_vertical_position_noise(), _in.AltimeterSensor()->VerticalPositionNoise()); } if (_in.AltimeterSensor()->VerticalVelocityNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_vertical_velocity_noise(), + gz::sim::set(sensor->mutable_vertical_velocity_noise(), _in.AltimeterSensor()->VerticalVelocityNoise()); } } else { - ignerr << "Attempting to convert an altimeter SDF sensor, but the " + gzerr << "Attempting to convert an altimeter SDF sensor, but the " << "sensor pointer is null.\n"; } } @@ -1144,7 +1144,7 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) if (_in.AirPressureSensor()->PressureNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_pressure_noise(), + gz::sim::set(sensor->mutable_pressure_noise(), _in.AirPressureSensor()->PressureNoise()); } sensor->set_reference_altitude( @@ -1152,7 +1152,7 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) } else { - ignerr << "Attempting to convert an air pressure SDF sensor, but the " + gzerr << "Attempting to convert an air pressure SDF sensor, but the " << "sensor pointer is null.\n"; } } @@ -1165,38 +1165,38 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) if (sdfImu->LinearAccelerationXNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gz::sim::set( sensor->mutable_linear_acceleration()->mutable_x_noise(), sdfImu->LinearAccelerationXNoise()); } if (sdfImu->LinearAccelerationYNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gz::sim::set( sensor->mutable_linear_acceleration()->mutable_y_noise(), sdfImu->LinearAccelerationYNoise()); } if (sdfImu->LinearAccelerationZNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gz::sim::set( sensor->mutable_linear_acceleration()->mutable_z_noise(), sdfImu->LinearAccelerationZNoise()); } if (sdfImu->AngularVelocityXNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gz::sim::set( sensor->mutable_angular_velocity()->mutable_x_noise(), sdfImu->AngularVelocityXNoise()); } if (sdfImu->AngularVelocityYNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gz::sim::set( sensor->mutable_angular_velocity()->mutable_y_noise(), sdfImu->AngularVelocityYNoise()); } if (sdfImu->AngularVelocityZNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gz::sim::set( sensor->mutable_angular_velocity()->mutable_z_noise(), sdfImu->AngularVelocityZNoise()); } @@ -1216,7 +1216,7 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) } else { - ignerr << "Attempting to convert an IMU SDF sensor, but the " + gzerr << "Attempting to convert an IMU SDF sensor, but the " << "sensor pointer is null.\n"; } } @@ -1230,7 +1230,7 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) if (sdfLidar->LidarNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_noise(), sdfLidar->LidarNoise()); + gz::sim::set(sensor->mutable_noise(), sdfLidar->LidarNoise()); } sensor->set_horizontal_samples(sdfLidar->HorizontalScanSamples()); sensor->set_horizontal_resolution(sdfLidar->HorizontalScanResolution()); @@ -1250,7 +1250,7 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) } else { - ignerr << "Attempting to convert a Lidar SDF sensor, but the " + gzerr << "Attempting to convert a Lidar SDF sensor, but the " << "sensor pointer is null.\n"; } } @@ -1259,13 +1259,13 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) +GZ_GAZEBO_VISIBLE +sdf::Sensor gz::sim::convert(const msgs::Sensor &_in) { sdf::Sensor out; out.SetName(_in.name()); if (!out.SetType(_in.type())) - ignerr << "Failed to set the sensor type from [" << _in.type() << "]\n"; + gzerr << "Failed to set the sensor type from [" << _in.type() << "]\n"; out.SetUpdateRate(_in.update_rate()); out.SetTopic(_in.topic()); @@ -1277,23 +1277,23 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) { if (_in.magnetometer().has_x_noise()) { - sensor.SetXNoise(ignition::gazebo::convert( + sensor.SetXNoise(gz::sim::convert( _in.magnetometer().x_noise())); } if (_in.magnetometer().has_y_noise()) { - sensor.SetYNoise(ignition::gazebo::convert( + sensor.SetYNoise(gz::sim::convert( _in.magnetometer().y_noise())); } if (_in.magnetometer().has_z_noise()) { - sensor.SetZNoise(ignition::gazebo::convert( + sensor.SetZNoise(gz::sim::convert( _in.magnetometer().z_noise())); } } else { - ignerr << "Attempting to convert a magnetometer sensor message, but the " + gzerr << "Attempting to convert a magnetometer sensor message, but the " << "message does not have a magnetometer nested message.\n"; } @@ -1329,7 +1329,7 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) } else { - ignerr << "Attempting to convert a camera sensor message, but the " + gzerr << "Attempting to convert a camera sensor message, but the " << "message does not have a camera nested message.\n"; } @@ -1342,19 +1342,19 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) { if (_in.altimeter().has_vertical_position_noise()) { - sensor.SetVerticalPositionNoise(ignition::gazebo::convert( + sensor.SetVerticalPositionNoise(gz::sim::convert( _in.altimeter().vertical_position_noise())); } if (_in.altimeter().has_vertical_velocity_noise()) { - sensor.SetVerticalVelocityNoise(ignition::gazebo::convert( + sensor.SetVerticalVelocityNoise(gz::sim::convert( _in.altimeter().vertical_velocity_noise())); } } else { - ignerr << "Attempting to convert an altimeter sensor message, but the " + gzerr << "Attempting to convert an altimeter sensor message, but the " << "message does not have a altimeter nested message.\n"; } @@ -1367,7 +1367,7 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) { if (_in.air_pressure().has_pressure_noise()) { - sensor.SetPressureNoise(ignition::gazebo::convert( + sensor.SetPressureNoise(gz::sim::convert( _in.air_pressure().pressure_noise())); } @@ -1375,7 +1375,7 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) } else { - ignerr << "Attempting to convert an air pressure sensor message, but the " + gzerr << "Attempting to convert an air pressure sensor message, but the " << "message does not have an air pressure nested message.\n"; } @@ -1391,19 +1391,19 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) if (_in.imu().linear_acceleration().has_x_noise()) { sensor.SetLinearAccelerationXNoise( - ignition::gazebo::convert( + gz::sim::convert( _in.imu().linear_acceleration().x_noise())); } if (_in.imu().linear_acceleration().has_y_noise()) { sensor.SetLinearAccelerationYNoise( - ignition::gazebo::convert( + gz::sim::convert( _in.imu().linear_acceleration().y_noise())); } if (_in.imu().linear_acceleration().has_z_noise()) { sensor.SetLinearAccelerationZNoise( - ignition::gazebo::convert( + gz::sim::convert( _in.imu().linear_acceleration().z_noise())); } } @@ -1413,19 +1413,19 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) if (_in.imu().angular_velocity().has_x_noise()) { sensor.SetAngularVelocityXNoise( - ignition::gazebo::convert( + gz::sim::convert( _in.imu().angular_velocity().x_noise())); } if (_in.imu().angular_velocity().has_y_noise()) { sensor.SetAngularVelocityYNoise( - ignition::gazebo::convert( + gz::sim::convert( _in.imu().angular_velocity().y_noise())); } if (_in.imu().angular_velocity().has_z_noise()) { sensor.SetAngularVelocityZNoise( - ignition::gazebo::convert( + gz::sim::convert( _in.imu().angular_velocity().z_noise())); } } @@ -1454,7 +1454,7 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) } else { - ignerr << "Attempting to convert an IMU sensor message, but the " + gzerr << "Attempting to convert an IMU sensor message, but the " << "message does not have an IMU nested message.\n"; } @@ -1482,13 +1482,13 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) if (_in.lidar().has_noise()) { - sensor.SetLidarNoise(ignition::gazebo::convert( + sensor.SetLidarNoise(gz::sim::convert( _in.lidar().noise())); } } else { - ignerr << "Attempting to convert a lidar sensor message, but the " + gzerr << "Attempting to convert a lidar sensor message, but the " << "message does not have a lidar nested message.\n"; } @@ -1499,8 +1499,8 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -msgs::WorldStatistics ignition::gazebo::convert(const gazebo::UpdateInfo &_in) +GZ_GAZEBO_VISIBLE +msgs::WorldStatistics gz::sim::convert(const sim::UpdateInfo &_in) { msgs::WorldStatistics out; set(&out, _in); @@ -1509,10 +1509,10 @@ msgs::WorldStatistics ignition::gazebo::convert(const gazebo::UpdateInfo &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -gazebo::UpdateInfo ignition::gazebo::convert(const msgs::WorldStatistics &_in) +GZ_GAZEBO_VISIBLE +sim::UpdateInfo gz::sim::convert(const msgs::WorldStatistics &_in) { - gazebo::UpdateInfo out; + sim::UpdateInfo out; out.iterations = _in.iterations(); out.paused = _in.paused(); out.simTime = convert(_in.sim_time()); @@ -1523,8 +1523,8 @@ gazebo::UpdateInfo ignition::gazebo::convert(const msgs::WorldStatistics &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -msgs::AxisAlignedBox ignition::gazebo::convert(const math::AxisAlignedBox &_in) +GZ_GAZEBO_VISIBLE +msgs::AxisAlignedBox gz::sim::convert(const math::AxisAlignedBox &_in) { msgs::AxisAlignedBox out; msgs::Set(out.mutable_min_corner(), _in.Min()); @@ -1534,8 +1534,8 @@ msgs::AxisAlignedBox ignition::gazebo::convert(const math::AxisAlignedBox &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -math::AxisAlignedBox ignition::gazebo::convert(const msgs::AxisAlignedBox &_in) +GZ_GAZEBO_VISIBLE +math::AxisAlignedBox gz::sim::convert(const msgs::AxisAlignedBox &_in) { math::AxisAlignedBox out; out.Min() = msgs::Convert(_in.min_corner()); @@ -1545,8 +1545,8 @@ math::AxisAlignedBox ignition::gazebo::convert(const msgs::AxisAlignedBox &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -msgs::ParticleEmitter ignition::gazebo::convert(const sdf::ParticleEmitter &_in) +GZ_GAZEBO_VISIBLE +msgs::ParticleEmitter gz::sim::convert(const sdf::ParticleEmitter &_in) { msgs::ParticleEmitter out; out.set_name(_in.Name()); @@ -1612,8 +1612,8 @@ msgs::ParticleEmitter ignition::gazebo::convert(const sdf::ParticleEmitter &_in) ////////////////////////////////////////////////// template<> -IGNITION_GAZEBO_VISIBLE -sdf::ParticleEmitter ignition::gazebo::convert(const msgs::ParticleEmitter &_in) +GZ_GAZEBO_VISIBLE +sdf::ParticleEmitter gz::sim::convert(const msgs::ParticleEmitter &_in) { sdf::ParticleEmitter out; out.SetName(_in.name()); diff --git a/src/Conversions_TEST.cc b/src/Conversions_TEST.cc index e4b8aa42ef..d0dae828ad 100644 --- a/src/Conversions_TEST.cc +++ b/src/Conversions_TEST.cc @@ -42,8 +42,8 @@ #include "gz/sim/Conversions.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace std::chrono_literals; ///////////////////////////////////////////////// @@ -56,8 +56,8 @@ TEST(Conversions, Light) light.SetPoseRelativeTo("world"); light.SetCastShadows(true); light.SetVisualize(true); - light.SetDiffuse(ignition::math::Color(0.4f, 0.5f, 0.6f, 1.0)); - light.SetSpecular(ignition::math::Color(0.8f, 0.9f, 0.1f, 1.0)); + light.SetDiffuse(gz::math::Color(0.4f, 0.5f, 0.6f, 1.0)); + light.SetSpecular(gz::math::Color(0.8f, 0.9f, 0.1f, 1.0)); light.SetAttenuationRange(3.2); light.SetConstantAttenuationFactor(0.5); light.SetLinearAttenuationFactor(0.1); @@ -244,10 +244,10 @@ TEST(Conversions, Time) TEST(Conversions, Material) { sdf::Material material; - material.SetDiffuse(ignition::math::Color(0.1f, 0.2f, 0.3f, 0.4f)); - material.SetSpecular(ignition::math::Color(0.5f, 0.6f, 0.7f, 0.8f)); - material.SetAmbient(ignition::math::Color(0.9f, 1.0f, 1.1f, 1.2f)); - material.SetEmissive(ignition::math::Color(1.3f, 1.4f, 1.5f, 1.6f)); + material.SetDiffuse(gz::math::Color(0.1f, 0.2f, 0.3f, 0.4f)); + material.SetSpecular(gz::math::Color(0.5f, 0.6f, 0.7f, 0.8f)); + material.SetAmbient(gz::math::Color(0.9f, 1.0f, 1.1f, 1.2f)); + material.SetEmissive(gz::math::Color(1.3f, 1.4f, 1.5f, 1.6f)); material.SetLighting(true); material.SetRenderOrder(2.5); material.SetDoubleSided(true); @@ -339,7 +339,7 @@ TEST(Conversions, GeometryBox) geometry.SetType(sdf::GeometryType::BOX); sdf::Box boxShape; - boxShape.SetSize(ignition::math::Vector3d(1, 2, 3)); + boxShape.SetSize(gz::math::Vector3d(1, 2, 3)); geometry.SetBoxShape(boxShape); auto geometryMsg = convert(geometry); @@ -430,19 +430,19 @@ TEST(Conversions, GeometryEllipsoid) geometry.SetType(sdf::GeometryType::ELLIPSOID); sdf::Ellipsoid ellipsoidShape; - ellipsoidShape.SetRadii(ignition::math::Vector3d(1.2, 3.2, 2.4)); + ellipsoidShape.SetRadii(gz::math::Vector3d(1.2, 3.2, 2.4)); geometry.SetEllipsoidShape(ellipsoidShape); auto geometryMsg = convert(geometry); EXPECT_EQ(msgs::Geometry::ELLIPSOID, geometryMsg.type()); EXPECT_TRUE(geometryMsg.has_ellipsoid()); - EXPECT_EQ(ignition::math::Vector3d(1.2, 3.2, 2.4), + EXPECT_EQ(gz::math::Vector3d(1.2, 3.2, 2.4), msgs::Convert(geometryMsg.ellipsoid().radii())); auto newGeometry = convert(geometryMsg); EXPECT_EQ(sdf::GeometryType::ELLIPSOID, newGeometry.Type()); ASSERT_NE(nullptr, newGeometry.EllipsoidShape()); - EXPECT_EQ(ignition::math::Vector3d(1.2, 3.2, 2.4), + EXPECT_EQ(gz::math::Vector3d(1.2, 3.2, 2.4), newGeometry.EllipsoidShape()->Radii()); } @@ -453,7 +453,7 @@ TEST(Conversions, GeometryMesh) geometry.SetType(sdf::GeometryType::MESH); sdf::Mesh meshShape; - meshShape.SetScale(ignition::math::Vector3d(1, 2, 3)); + meshShape.SetScale(gz::math::Vector3d(1, 2, 3)); meshShape.SetUri("file://watermelon"); meshShape.SetSubmesh("grape"); meshShape.SetCenterSubmesh(true); @@ -484,8 +484,8 @@ TEST(Conversions, GeometryPlane) geometry.SetType(sdf::GeometryType::PLANE); sdf::Plane planeShape; - planeShape.SetSize(ignition::math::Vector2d(1, 2)); - planeShape.SetNormal(ignition::math::Vector3d::UnitY); + planeShape.SetSize(gz::math::Vector2d(1, 2)); + planeShape.SetNormal(gz::math::Vector3d::UnitY); geometry.SetPlaneShape(planeShape); auto geometryMsg = convert(geometry); @@ -511,8 +511,8 @@ TEST(Conversions, GeometryHeightmap) sdf::Heightmap heightmap; heightmap.SetUri("file://heights.png"); - heightmap.SetSize(ignition::math::Vector3d(1, 2, 3)); - heightmap.SetPosition(ignition::math::Vector3d(4, 5, 6)); + heightmap.SetSize(gz::math::Vector3d(1, 2, 3)); + heightmap.SetPosition(gz::math::Vector3d(4, 5, 6)); heightmap.SetUseTerrainPaging(true); heightmap.SetSampling(16u); @@ -645,8 +645,8 @@ TEST(Conversions, JointAxis) TEST(Conversions, Scene) { sdf::Scene scene; - scene.SetAmbient(ignition::math::Color(0.1f, 0.2f, 0.3f, 0.4f)); - scene.SetBackground(ignition::math::Color(0.5f, 0.6f, 0.7f, 0.8f)); + scene.SetAmbient(gz::math::Color(0.1f, 0.2f, 0.3f, 0.4f)); + scene.SetBackground(gz::math::Color(0.5f, 0.6f, 0.7f, 0.8f)); scene.SetShadows(true); scene.SetGrid(true); scene.SetOriginVisual(true); @@ -732,7 +732,7 @@ TEST(CONVERSIONS, MagnetometerSensor) sensor.SetType(sdf::SensorType::MAGNETOMETER); sensor.SetUpdateRate(12.4); sensor.SetTopic("my_topic"); - sensor.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0, 0, 0)); + sensor.SetRawPose(gz::math::Pose3d(1, 2, 3, 0, 0, 0)); sdf::Noise noise; noise.SetType(sdf::NoiseType::GAUSSIAN); @@ -772,7 +772,7 @@ TEST(CONVERSIONS, AltimeterSensor) sensor.SetType(sdf::SensorType::ALTIMETER); sensor.SetUpdateRate(12.4); sensor.SetTopic("my_topic"); - sensor.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0, 0, 0)); + sensor.SetRawPose(gz::math::Pose3d(1, 2, 3, 0, 0, 0)); sdf::Noise noise; noise.SetType(sdf::NoiseType::GAUSSIAN); diff --git a/src/EntityComponentManager.cc b/src/EntityComponentManager.cc index a51eaf014b..1401553e2a 100644 --- a/src/EntityComponentManager.cc +++ b/src/EntityComponentManager.cc @@ -43,10 +43,10 @@ #include "gz/sim/components/Recreate.hh" #include "gz/sim/components/World.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; -class ignition::gazebo::EntityComponentManagerPrivate +class gz::sim::EntityComponentManagerPrivate { /// \brief Implementation of the CreateEntity function, which takes a specific /// entity as input. @@ -346,7 +346,7 @@ Entity EntityComponentManager::CreateEntity() if (entity == std::numeric_limits::max()) { - ignwarn << "Reached maximum number of entities [" << entity << "]" + gzwarn << "Reached maximum number of entities [" << entity << "]" << std::endl; return entity; } @@ -373,7 +373,7 @@ Entity EntityComponentManagerPrivate::CreateEntityImplementation(Entity _entity) std::vector>()}); if (!result.second) { - ignwarn << "Attempted to add entity [" << _entity + gzwarn << "Attempted to add entity [" << _entity << "] to component storage, but this entity is already in component " << "storage.\n"; } @@ -382,7 +382,7 @@ Entity EntityComponentManagerPrivate::CreateEntityImplementation(Entity _entity) std::unordered_map()}); if (!result2.second) { - ignwarn << "Attempted to add entity [" << _entity + gzwarn << "Attempted to add entity [" << _entity << "] to component type index, but this entity is already in component " << "type index.\n"; } @@ -413,7 +413,7 @@ Entity EntityComponentManager::Clone(Entity _entity, Entity _parent, oldCanonicalLink); if (iter == this->dataPtr->oldToClonedCanonicalLink.end()) { - ignerr << "Error: attempted to clone model(s) with canonical link(s), " + gzerr << "Error: attempted to clone model(s) with canonical link(s), " << "but entity [" << oldCanonicalLink << "] was not cloned as a " << "canonical link." << std::endl; continue; @@ -432,7 +432,7 @@ Entity EntityComponentManager::Clone(Entity _entity, Entity _parent, if (!this->dataPtr->ClonedJointLinkName( clonedJoint, originalParentLink, this)) { - ignerr << "Error updating the cloned parent link name for cloned " + gzerr << "Error updating the cloned parent link name for cloned " << "joint [" << clonedJoint << "]\n"; continue; } @@ -441,7 +441,7 @@ Entity EntityComponentManager::Clone(Entity _entity, Entity _parent, if (!this->dataPtr->ClonedJointLinkName( clonedJoint, originalChildLink, this)) { - ignerr << "Error updating the cloned child link name for cloned " + gzerr << "Error updating the cloned child link name for cloned " << "joint [" << clonedJoint << "]\n"; continue; } @@ -462,7 +462,7 @@ Entity EntityComponentManager::CloneImpl(Entity _entity, Entity _parent, // 2. We can generate a unique name for the cloned entity if (!this->HasEntity(_entity)) { - ignerr << "Requested to clone entity [" << _entity + gzerr << "Requested to clone entity [" << _entity << "], but this entity does not exist." << std::endl; return kNullEntity; } @@ -493,7 +493,7 @@ Entity EntityComponentManager::CloneImpl(Entity _entity, Entity _parent, if (kNullEntity != ent && !hasRecreateComp) { - ignerr << "Requested to clone entity [" << _entity + gzerr << "Requested to clone entity [" << _entity << "] with a name of [" << _name << "], but another entity already " << "has this name." << std::endl; return kNullEntity; @@ -601,7 +601,7 @@ Entity EntityComponentManager::CloneImpl(Entity _entity, Entity _parent, if (!originalParentLink || !originalChildLink) { - ignerr << "The cloned joint entity [" << clonedEntity << "] was unable " + gzerr << "The cloned joint entity [" << clonedEntity << "] was unable " << "to find the original joint entity's parent and/or child link.\n"; this->RequestRemoveEntity(clonedEntity); return kNullEntity; @@ -630,7 +630,7 @@ Entity EntityComponentManager::CloneImpl(Entity _entity, Entity _parent, _allowRename); if (kNullEntity == clonedChild) { - ignerr << "Cloning child entity [" << childEntity << "] failed.\n"; + gzerr << "Cloning child entity [" << childEntity << "] failed.\n"; this->RequestRemoveEntity(clonedEntity); return kNullEntity; } @@ -1042,7 +1042,7 @@ bool EntityComponentManager::CreateComponentImplementation( // make sure the entity exists if (!this->HasEntity(_entity)) { - ignerr << "Trying to create a component of type [" << _componentTypeId + gzerr << "Trying to create a component of type [" << _componentTypeId << "] attached to entity [" << _entity << "], but this entity does not " << "exist. This create component request will be ignored." << std::endl; return false; @@ -1053,7 +1053,7 @@ bool EntityComponentManager::CreateComponentImplementation( if (!this->HasComponentType(_componentTypeId) && !components::Factory::Instance()->HasType(_componentTypeId)) { - ignerr << "Failed to create component of type [" << _componentTypeId + gzerr << "Failed to create component of type [" << _componentTypeId << "] for entity [" << _entity << "]. Type has not been properly registered." << std::endl; return false; @@ -1070,7 +1070,7 @@ bool EntityComponentManager::CreateComponentImplementation( auto typeMapIter = this->dataPtr->componentTypeIndex.find(_entity); if (typeMapIter == this->dataPtr->componentTypeIndex.end()) { - ignerr << "Attempt to create a component of type [" << _componentTypeId + gzerr << "Attempt to create a component of type [" << _componentTypeId << "] attached to entity [" << _entity << "] failed: entity not in componentTypeIndex." << std::endl; return false; @@ -1079,7 +1079,7 @@ bool EntityComponentManager::CreateComponentImplementation( auto entityCompIter = this->dataPtr->componentStorage.find(_entity); if (entityCompIter == this->dataPtr->componentStorage.end()) { - ignerr << "Attempt to create a component of type [" << _componentTypeId + gzerr << "Attempt to create a component of type [" << _componentTypeId << "] attached to entity [" << _entity << "] failed: entity not in storage." << std::endl; return false; @@ -1119,7 +1119,7 @@ bool EntityComponentManager::CreateComponentImplementation( auto existingCompPtr = entityCompIter->second.at(compIdxIter->second).get(); if (!existingCompPtr) { - ignerr << "Internal error: entity [" << _entity << "] has a component of " + gzerr << "Internal error: entity [" << _entity << "] has a component of " << "type [" << _componentTypeId << "] in the storage, but the instance " << "of this component is nullptr. This should never happen!" << std::endl; @@ -1199,7 +1199,7 @@ const components::BaseComponent const auto compVecIter = this->dataPtr->componentStorage.find(_entity); if (compVecIter == this->dataPtr->componentStorage.end()) { - ignerr << "Internal error: Entity [" << _entity + gzerr << "Internal error: Entity [" << _entity << "] is missing in storage, but is in " << "componentTypeIndex. This should never happen!" << std::endl; return nullptr; @@ -1208,7 +1208,7 @@ const components::BaseComponent auto compPtr = compVecIter->second.at(compIdxIter->second).get(); if (nullptr == compPtr) { - ignerr << "Internal error: entity [" << _entity << "] has a component of " + gzerr << "Internal error: entity [" << _entity << "] has a component of " << "type [" << _type << "] in the storage, but the instance " << "of this component is nullptr. This should never happen!" << std::endl; @@ -1545,9 +1545,9 @@ void EntityComponentManager::AddEntityToMessage(msgs::SerializedStateMap &_msg, } ////////////////////////////////////////////////// -ignition::msgs::SerializedState EntityComponentManager::ChangedState() const +gz::msgs::SerializedState EntityComponentManager::ChangedState() const { - ignition::msgs::SerializedState stateMsg; + gz::msgs::SerializedState stateMsg; // New entities for (const auto &entity : this->dataPtr->newlyCreatedEntities) @@ -1572,7 +1572,7 @@ ignition::msgs::SerializedState EntityComponentManager::ChangedState() const ////////////////////////////////////////////////// void EntityComponentManager::ChangedState( - ignition::msgs::SerializedStateMap &_state) const + gz::msgs::SerializedStateMap &_state) const { // New entities for (const auto &entity : this->dataPtr->newlyCreatedEntities) @@ -1614,7 +1614,7 @@ void EntityComponentManagerPrivate::CalculateStateThreadLoad() int entitiesPerThread = static_cast(std::ceil( static_cast(numEntities) / numThreads)); - igndbg << "Updated state thread iterators: " << numThreads + gzdbg << "Updated state thread iterators: " << numThreads << " threads processing around " << entitiesPerThread << " entities each." << std::endl; @@ -1640,11 +1640,11 @@ void EntityComponentManagerPrivate::CalculateStateThreadLoad() } ////////////////////////////////////////////////// -ignition::msgs::SerializedState EntityComponentManager::State( +gz::msgs::SerializedState EntityComponentManager::State( const std::unordered_set &_entities, const std::unordered_set &_types) const { - ignition::msgs::SerializedState stateMsg; + gz::msgs::SerializedState stateMsg; for (const auto &it : this->dataPtr->componentTypeIndex) { auto entity = it.first; @@ -1710,7 +1710,7 @@ void EntityComponentManager::State( ////////////////////////////////////////////////// void EntityComponentManager::SetState( - const ignition::msgs::SerializedState &_stateMsg) + const gz::msgs::SerializedState &_stateMsg) { IGN_PROFILE("EntityComponentManager::SetState Non-map"); // Create / remove / update entities @@ -1755,7 +1755,7 @@ void EntityComponentManager::SetState( if (printedComps.find(type) == printedComps.end()) { printedComps.insert(type); - ignwarn << "Component type [" << type << "] has not been " + gzwarn << "Component type [" << type << "] has not been " << "registered in this process, so it can't be deserialized." << std::endl; } @@ -1780,7 +1780,7 @@ void EntityComponentManager::SetState( auto newComp = components::Factory::Instance()->New(type); if (nullptr == newComp) { - ignerr << "Failed to create component type [" + gzerr << "Failed to create component type [" << compMsg.type() << "]" << std::endl; continue; } @@ -1799,7 +1799,7 @@ void EntityComponentManager::SetState( ////////////////////////////////////////////////// void EntityComponentManager::SetState( - const ignition::msgs::SerializedStateMap &_stateMsg) + const gz::msgs::SerializedStateMap &_stateMsg) { IGN_PROFILE("EntityComponentManager::SetState Map"); // Create / remove / update entities @@ -1837,7 +1837,7 @@ void EntityComponentManager::SetState( if (printedComps.find(type) == printedComps.end()) { printedComps.insert(type); - ignwarn << "Component type [" << type << "] has not been " + gzwarn << "Component type [" << type << "] has not been " << "registered in this process, so it can't be deserialized." << std::endl; } @@ -1865,7 +1865,7 @@ void EntityComponentManager::SetState( if (nullptr == newComp) { - ignerr << "Failed to create component of type [" << compMsg.type() + gzerr << "Failed to create component of type [" << compMsg.type() << "]" << std::endl; continue; } @@ -1924,7 +1924,7 @@ void EntityComponentManager::SetAllComponentsUnchanged() ///////////////////////////////////////////////// void EntityComponentManager::SetChanged( const Entity _entity, const ComponentTypeId _type, - gazebo::ComponentState _c) + sim::ComponentState _c) { // make sure _entity exists auto ecIter = this->dataPtr->componentTypeIndex.find(_entity); @@ -1990,7 +1990,7 @@ void EntityComponentManager::SetEntityCreateOffset(uint64_t _offset) { if (_offset < this->dataPtr->entityCount) { - ignwarn << "Setting an entity offset of [" << _offset << "] is less than " + gzwarn << "Setting an entity offset of [" << _offset << "] is less than " << "the current entity count of [" << this->dataPtr->entityCount << "]. " << "Incorrect behavior should be expected.\n"; } @@ -2045,7 +2045,7 @@ bool EntityComponentManagerPrivate::ClonedJointLinkName(Entity _joint, if (ComponentTypeT::typeId != components::ParentLinkName::typeId && ComponentTypeT::typeId != components::ChildLinkName::typeId) { - ignerr << "Template type is invalid. Must be either " + gzerr << "Template type is invalid. Must be either " << "components::ParentLinkName or components::ChildLinkName\n"; return false; } @@ -2065,7 +2065,7 @@ bool EntityComponentManagerPrivate::ClonedJointLinkName(Entity _joint, auto iter = this->originalToClonedLink.find(_originalLink); if (iter == this->originalToClonedLink.end()) { - ignerr << "Error: attempted to clone links, but link [" + gzerr << "Error: attempted to clone links, but link [" << _originalLink << "] was never cloned.\n"; return false; } @@ -2074,7 +2074,7 @@ bool EntityComponentManagerPrivate::ClonedJointLinkName(Entity _joint, auto nameComp = _ecm->Component(clonedLink); if (!nameComp) { - ignerr << "Link [" << _originalLink + gzerr << "Link [" << _originalLink << "] was cloned, but its clone has no name.\n"; return false; } diff --git a/src/EntityComponentManagerDiff.cc b/src/EntityComponentManagerDiff.cc index 09c9aef091..b2313a7ad9 100644 --- a/src/EntityComponentManagerDiff.cc +++ b/src/EntityComponentManagerDiff.cc @@ -19,8 +19,8 @@ #include "gz/sim/Entity.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ////////////////////////////////////////////////// void EntityComponentManagerDiff::InsertAddedEntity(const Entity &_entity) diff --git a/src/EntityComponentManagerDiff.hh b/src/EntityComponentManagerDiff.hh index 9a3c6b59ef..4e9983945d 100644 --- a/src/EntityComponentManagerDiff.hh +++ b/src/EntityComponentManagerDiff.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_ENTITYCOMPONENTMANAGER_DIFF_HH_ -#define IGNITION_GAZEBO_ENTITYCOMPONENTMANAGER_DIFF_HH_ +#ifndef GZ_SIM_ENTITYCOMPONENTMANAGER_DIFF_HH_ +#define GZ_SIM_ENTITYCOMPONENTMANAGER_DIFF_HH_ #include "gz/sim/Entity.hh" #include "gz/sim/Export.hh" @@ -24,17 +24,17 @@ #include -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { /// \\brief Used to track the changes in an EntityComponentManager /// /// Tracks added and removed entities for the purpose of a reset - class IGNITION_GAZEBO_VISIBLE EntityComponentManagerDiff + class GZ_GAZEBO_VISIBLE EntityComponentManagerDiff { /// \brief Add an added entity to the current diff /// \param[in] _entity Entity that was added diff --git a/src/EntityComponentManager_TEST.cc b/src/EntityComponentManager_TEST.cc index 9f42d3186f..42e65d8d7b 100644 --- a/src/EntityComponentManager_TEST.cc +++ b/src/EntityComponentManager_TEST.cc @@ -38,15 +38,15 @@ #include "EntityComponentManagerDiff.hh" #include "../test/helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace components; -namespace ignition +namespace gz { -namespace gazebo +namespace sim { -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { using IntComponent = components::Component; @@ -1546,11 +1546,11 @@ TEST_P(EntityComponentManagerFixture, EXPECT_TRUE(manager.SetParentEntity(e6, e2)); EXPECT_TRUE(manager.SetParentEntity(e7, e2)); - EXPECT_FALSE(manager.SetParentEntity(e1, gazebo::Entity(1000))); - EXPECT_FALSE(manager.SetParentEntity(gazebo::Entity(1000), e1)); + EXPECT_FALSE(manager.SetParentEntity(e1, sim::Entity(1000))); + EXPECT_FALSE(manager.SetParentEntity(sim::Entity(1000), e1)); // Check their parents - EXPECT_EQ(gazebo::kNullEntity, manager.ParentEntity(e1)); + EXPECT_EQ(sim::kNullEntity, manager.ParentEntity(e1)); EXPECT_EQ(e1, manager.ParentEntity(e2)); EXPECT_EQ(e1, manager.ParentEntity(e3)); EXPECT_EQ(e2, manager.ParentEntity(e4)); @@ -1559,8 +1559,8 @@ TEST_P(EntityComponentManagerFixture, EXPECT_EQ(e2, manager.ParentEntity(e7)); // Detach from graph - EXPECT_TRUE(manager.SetParentEntity(e7, gazebo::kNullEntity)); - EXPECT_EQ(gazebo::kNullEntity, manager.ParentEntity(e7)); + EXPECT_TRUE(manager.SetParentEntity(e7, sim::kNullEntity)); + EXPECT_EQ(sim::kNullEntity, manager.ParentEntity(e7)); // Reparent EXPECT_TRUE(manager.SetParentEntity(e5, e3)); diff --git a/src/EventManager_TEST.cc b/src/EventManager_TEST.cc index dd32fc802d..78ef5cda90 100644 --- a/src/EventManager_TEST.cc +++ b/src/EventManager_TEST.cc @@ -22,7 +22,7 @@ #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 3b5782d2e6..e39246659f 100644 --- a/src/LevelManager.cc +++ b/src/LevelManager.cc @@ -60,8 +60,8 @@ #include "SimulationRunner.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// LevelManager::LevelManager(SimulationRunner *_runner, const bool _useLevels) @@ -69,7 +69,7 @@ LevelManager::LevelManager(SimulationRunner *_runner, const bool _useLevels) { if (nullptr == _runner) { - ignerr << "Can't start level manager with null runner." << std::endl; + gzerr << "Can't start level manager with null runner." << std::endl; return; } @@ -84,7 +84,7 @@ LevelManager::LevelManager(SimulationRunner *_runner, const bool _useLevels) this->runner->sdfWorld->Name() + "/level/set_performer"); if (service.empty()) { - ignerr << "Failed to generate set_performer topic for world [" + gzerr << "Failed to generate set_performer topic for world [" << this->runner->sdfWorld->Name() << "]" << std::endl; return; } @@ -197,10 +197,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")) { @@ -215,7 +215,7 @@ void LevelManager::ReadLevelPerformerInfo() { if (this->useLevels) { - ignerr << "Could not find a plugin tag with name " << kPluginName + gzerr << "Could not find a plugin tag with name " << kPluginName << ". Levels and distributed simulation will not work.\n"; } } @@ -247,7 +247,7 @@ void LevelManager::ReadPerformers(const sdf::ElementPtr &_sdf) if (_sdf->HasElement("performer")) { - igndbg << "Reading performer info\n"; + gzdbg << "Reading performer info\n"; for (auto performer = _sdf->GetElement("performer"); performer; performer = performer->GetNextElement("performer")) { @@ -266,7 +266,7 @@ void LevelManager::ReadPerformers(const sdf::ElementPtr &_sdf) this->runner->entityCompMgr.Component( this->performerMap[ref]); - ignerr << "Found multiple performers (" << name << " and " + gzerr << "Found multiple performers (" << name << " and " << performer2->Data() << ") referring to the same entity\n"; } @@ -281,14 +281,14 @@ void LevelManager::ReadPerformers(const sdf::ElementPtr &_sdf) this->runner->entityCompMgr.CreateComponent(performerEntity, components::Geometry(geometry)); - ignmsg << "Created performer [" << performerEntity << " / " << name << "]" + gzmsg << "Created performer [" << performerEntity << " / " << name << "]" << std::endl; } } if (this->useLevels && performerMap.empty()) { - igndbg << "Levels enabled, but no s were speficied in SDF. Use " + gzdbg << "Levels enabled, but no s were speficied in SDF. Use " << "the /world//level/set_performer service to specify " << "performers.\n"; } @@ -328,7 +328,7 @@ bool LevelManager::OnSetPerformer(const msgs::StringMsg &_req, } else { - ignerr << "Empty performer name. Performer will not be created\n"; + gzerr << "Empty performer name. Performer will not be created\n"; } return true; @@ -343,7 +343,7 @@ bool LevelManager::OnSetPerformer(const msgs::StringMsg &_req, // components::Name(name)); // if (modelEntity == kNullEntity) // { - // ignerr << "Unable to find model with name[" << name << "]. " + // gzerr << "Unable to find model with name[" << name << "]. " // << "Performer not created\n"; // return true; // } @@ -364,7 +364,7 @@ bool LevelManager::OnSetPerformer(const msgs::StringMsg &_req, // } // else // { - // ignwarn << "Performer with name[" << name << "] " + // gzwarn << "Performer with name[" << name << "] " // << "has already been set.\n"; // } @@ -377,7 +377,7 @@ void LevelManager::ReadLevels(const sdf::ElementPtr &_sdf) { IGN_PROFILE("LevelManager::ReadLevels"); - igndbg << "Reading levels info\n"; + gzdbg << "Reading levels info\n"; if (_sdf == nullptr) return; @@ -392,7 +392,7 @@ void LevelManager::ReadLevels(const sdf::ElementPtr &_sdf) if (nullptr == geometry.BoxShape()) { - ignerr << "Level [" << name << "]'s geometry is not a box, level won't " + gzerr << "Level [" << name << "]'s geometry is not a box, level won't " << "be created." << std::endl; continue; } @@ -400,7 +400,7 @@ void LevelManager::ReadLevels(const sdf::ElementPtr &_sdf) double buffer = level->Get("buffer", 0.0).first; if (buffer < 0) { - ignwarn << "The buffer parameter for Level [" << name << "]cannot be a " + gzwarn << "The buffer parameter for Level [" << name << "]cannot be a " << " negative number. Setting to 0.0\n"; buffer = 0.0; } @@ -521,7 +521,7 @@ void LevelManager::CreatePerformers() if (this->worldEntity == kNullEntity) { - ignerr << "Could not find the world entity while creating performers\n"; + gzerr << "Could not find the world entity while creating performers\n"; return; } // Models @@ -621,7 +621,7 @@ void LevelManager::UpdateLevelsState() auto perfBox = _geometry->Data().BoxShape(); if (nullptr == perfBox) { - ignerr << "Internal error: geometry of performer [" << _perfEntity + gzerr << "Internal error: geometry of performer [" << _perfEntity << "] missing box." << std::endl; return true; } @@ -649,7 +649,7 @@ void LevelManager::UpdateLevelsState() auto box = _levelGeometry->Data().BoxShape(); if (nullptr == box) { - ignerr << "Level [" << _entity + gzerr << "Level [" << _entity << "]'s geometry is not a box." << std::endl; return true; } @@ -773,7 +773,7 @@ void LevelManager::UpdateLevelsState() { if (!this->IsLevelActive(level)) { - ignmsg << "Loaded level [" << level << "]" << std::endl; + gzmsg << "Loaded level [" << level << "]" << std::endl; this->activeLevels.push_back(level); } } @@ -781,7 +781,7 @@ void LevelManager::UpdateLevelsState() auto pendingEnd = this->activeLevels.end(); for (const auto &toUnload : levelsToUnload) { - ignmsg << "Unloaded level [" << toUnload << "]" << std::endl; + gzmsg << "Unloaded level [" << toUnload << "]" << std::endl; pendingEnd = std::remove(this->activeLevels.begin(), pendingEnd, toUnload); } // Erase from vector @@ -795,7 +795,7 @@ void LevelManager::LoadActiveEntities(const std::set &_namesToLoad) if (this->worldEntity == kNullEntity) { - ignerr << "Could not find the world entity while loading levels\n"; + gzerr << "Could not find the world entity while loading levels\n"; return; } @@ -904,7 +904,7 @@ int LevelManager::CreatePerformerEntity(const std::string &_name, components::Name(_name)); if (modelEntity == kNullEntity) { - ignwarn << "Attempting to set performer with name [" + gzwarn << "Attempting to set performer with name [" << _name << "] " << ", but the entity could not be found. Another attempt will be made " << "in the next iteration.\n"; @@ -914,7 +914,7 @@ int LevelManager::CreatePerformerEntity(const std::string &_name, if (!this->runner->entityCompMgr.ChildrenByComponents(modelEntity, components::Performer()).empty()) { - ignwarn << "Attempting to set performer with name [" + gzwarn << "Attempting to set performer with name [" << _name << "], but the entity already has a performer.\n"; return 1; } diff --git a/src/LevelManager.hh b/src/LevelManager.hh index 14e6d1dba3..85dc7d9ced 100644 --- a/src/LevelManager.hh +++ b/src/LevelManager.hh @@ -38,12 +38,12 @@ #include "gz/sim/SdfEntityCreator.hh" #include "gz/sim/Types.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { // // forward declaration class SimulationRunner; @@ -74,7 +74,7 @@ namespace ignition /// when the level is reloaded. Likewise, they should not be deleted. /// * Entities spawned during simulation are part of the default level. /// - class IGNITION_GAZEBO_VISIBLE LevelManager + class GZ_GAZEBO_VISIBLE LevelManager { /// \brief Constructor /// \param[in] _runner A pointer to the simulationrunner that owns this @@ -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 1fdb42c3d8..a22c05a4f3 100644 --- a/src/Link.cc +++ b/src/Link.cc @@ -39,17 +39,17 @@ #include "gz/sim/Link.hh" -class ignition::gazebo::LinkPrivate +class gz::sim::LinkPrivate { /// \brief Id of link entity. public: Entity id{kNullEntity}; }; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ////////////////////////////////////////////////// -Link::Link(gazebo::Entity _entity) +Link::Link(sim::Entity _entity) : dataPtr(std::make_unique()) { this->dataPtr->id = _entity; @@ -84,7 +84,7 @@ Entity Link::Entity() const } ////////////////////////////////////////////////// -void Link::ResetEntity(gazebo::Entity _newEntity) +void Link::ResetEntity(sim::Entity _newEntity) { this->dataPtr->id = _newEntity; } diff --git a/src/Link_TEST.cc b/src/Link_TEST.cc index c90937a887..f5da1459f0 100644 --- a/src/Link_TEST.cc +++ b/src/Link_TEST.cc @@ -22,11 +22,11 @@ ///////////////////////////////////////////////// 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 356d0d78c6..8d5e9024e4 100644 --- a/src/Model.cc +++ b/src/Model.cc @@ -27,17 +27,17 @@ #include "gz/sim/components/WindMode.hh" #include "gz/sim/Model.hh" -class ignition::gazebo::ModelPrivate +class gz::sim::ModelPrivate { /// \brief Id of model entity. public: Entity id{kNullEntity}; }; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ////////////////////////////////////////////////// -Model::Model(gazebo::Entity _entity) +Model::Model(sim::Entity _entity) : dataPtr(std::make_unique()) { this->dataPtr->id = _entity; diff --git a/src/ModelCommandAPI_TEST.cc b/src/ModelCommandAPI_TEST.cc index a03d5cb88d..fa58b5281d 100644 --- a/src/ModelCommandAPI_TEST.cc +++ b/src/ModelCommandAPI_TEST.cc @@ -26,7 +26,7 @@ #include "gz/sim/test_config.hh" // NOLINT(build/include) static const std::string kIgnModelCommand( - std::string(BREW_RUBY) + std::string(IGN_PATH) + "/ign model "); + std::string(BREW_RUBY) + std::string(GZ_PATH) + "/ign model "); ///////////////////////////////////////////////// @@ -73,7 +73,7 @@ std::string customExecStr(std::string _cmd) ///////////////////////////////////////////////// // Test `ign model` command when no Gazebo server is running. -// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +// See https://github.com/gazebosim/gz-sim/issues/1175 TEST(ModelCommandAPI, IGN_UTILS_TEST_DISABLED_ON_WIN32(NoServerRunning)) { const std::string cmd = kIgnModelCommand + "--list "; @@ -89,13 +89,13 @@ TEST(ModelCommandAPI, IGN_UTILS_TEST_DISABLED_ON_WIN32(NoServerRunning)) // Tests `ign model` command. TEST(ModelCommandAPI, IGN_UTILS_TEST_DISABLED_ON_WIN32(Commands)) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; // Using an static model to avoid any movements in the simulation. serverConfig.SetSdfFile( - ignition::common::joinPaths(std::string(PROJECT_SOURCE_PATH), + gz::common::joinPaths(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. @@ -389,13 +389,13 @@ TEST(ModelCommandAPI, IGN_UTILS_TEST_DISABLED_ON_WIN32(Commands)) // Tests `ign model -s` command with an airpressure sensor. TEST(ModelCommandAPI, AirPressureSensor) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; // Using an static model to avoid any movements in the simulation. serverConfig.SetSdfFile( - ignition::common::joinPaths(std::string(PROJECT_SOURCE_PATH), + gz::common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds", "air_pressure.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. @@ -432,13 +432,13 @@ TEST(ModelCommandAPI, AirPressureSensor) // Tests `ign model -s` command with an altimeter. TEST(ModelCommandAPI, AltimeterSensor) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; // Using an static model to avoid any movements in the simulation. serverConfig.SetSdfFile( - ignition::common::joinPaths(std::string(PROJECT_SOURCE_PATH), + gz::common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds", "altimeter_with_pose.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. @@ -482,13 +482,13 @@ TEST(ModelCommandAPI, AltimeterSensor) // Tests `ign model -s` command with a gpu lidar sensor. TEST(ModelCommandAPI, GpuLidarSensor) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; // Using an static model to avoid any movements in the simulation. serverConfig.SetSdfFile( - ignition::common::joinPaths(std::string(PROJECT_SOURCE_PATH), + gz::common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds", "gpu_lidar.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. @@ -538,13 +538,13 @@ TEST(ModelCommandAPI, GpuLidarSensor) // Tests `ign model -s` command with a magnetometer. TEST(ModelCommandAPI, MagnetometerSensor) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; // Using an static model to avoid any movements in the simulation. serverConfig.SetSdfFile( - ignition::common::joinPaths(std::string(PROJECT_SOURCE_PATH), + gz::common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds", "magnetometer.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. @@ -597,13 +597,13 @@ TEST(ModelCommandAPI, MagnetometerSensor) // Tests `ign model -s` command with an rgbd camera. TEST(ModelCommandAPI, IGN_UTILS_TEST_DISABLED_ON_MAC(RgbdCameraSensor)) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; // Using an static model to avoid any movements in the simulation. serverConfig.SetSdfFile( - ignition::common::joinPaths(std::string(PROJECT_SOURCE_PATH), + gz::common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds", "rgbd_camera_sensor.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 ad530f9bed..4135e8def8 100644 --- a/src/Model_TEST.cc +++ b/src/Model_TEST.cc @@ -29,11 +29,11 @@ ///////////////////////////////////////////////// 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()); } @@ -41,22 +41,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()); } @@ -64,20 +64,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()); } @@ -93,55 +93,55 @@ TEST(ModelTest, Links) // // modelC - ignition::gazebo::EntityComponentManager ecm; + gz::sim::EntityComponentManager ecm; // Model A auto modelAEntity = ecm.CreateEntity(); - ecm.CreateComponent(modelAEntity, ignition::gazebo::components::Model()); + ecm.CreateComponent(modelAEntity, gz::sim::components::Model()); ecm.CreateComponent(modelAEntity, - ignition::gazebo::components::Name("modelA_name")); + gz::sim::components::Name("modelA_name")); // Link AA - Child of Model A auto linkAAEntity = ecm.CreateEntity(); - ecm.CreateComponent(linkAAEntity, ignition::gazebo::components::Link()); + ecm.CreateComponent(linkAAEntity, gz::sim::components::Link()); ecm.CreateComponent(linkAAEntity, - ignition::gazebo::components::Name("linkAA_name")); + gz::sim::components::Name("linkAA_name")); ecm.CreateComponent(linkAAEntity, - ignition::gazebo::components::ParentEntity(modelAEntity)); + gz::sim::components::ParentEntity(modelAEntity)); // Link AB - Child of Model A auto linkABEntity = ecm.CreateEntity(); - ecm.CreateComponent(linkABEntity, ignition::gazebo::components::Link()); + ecm.CreateComponent(linkABEntity, gz::sim::components::Link()); ecm.CreateComponent(linkABEntity, - ignition::gazebo::components::Name("linkAB_name")); + gz::sim::components::Name("linkAB_name")); ecm.CreateComponent(linkABEntity, - ignition::gazebo::components::ParentEntity(modelAEntity)); + gz::sim::components::ParentEntity(modelAEntity)); // Model B - Child of Model A auto modelBEntity = ecm.CreateEntity(); - ecm.CreateComponent(modelBEntity, ignition::gazebo::components::Model()); + ecm.CreateComponent(modelBEntity, gz::sim::components::Model()); ecm.CreateComponent(modelBEntity, - ignition::gazebo::components::Name("modelB_name")); + gz::sim::components::Name("modelB_name")); ecm.CreateComponent(modelBEntity, - ignition::gazebo::components::ParentEntity(modelAEntity)); + gz::sim::components::ParentEntity(modelAEntity)); // Link BA - Child of Model B auto linkBAEntity = ecm.CreateEntity(); - ecm.CreateComponent(linkBAEntity, ignition::gazebo::components::Link()); + ecm.CreateComponent(linkBAEntity, gz::sim::components::Link()); ecm.CreateComponent(linkBAEntity, - ignition::gazebo::components::Name("linkBA_name")); + gz::sim::components::Name("linkBA_name")); ecm.CreateComponent(linkBAEntity, - ignition::gazebo::components::ParentEntity(modelBEntity)); + gz::sim::components::ParentEntity(modelBEntity)); // Model C auto modelCEntity = ecm.CreateEntity(); - ecm.CreateComponent(modelCEntity, ignition::gazebo::components::Model()); + ecm.CreateComponent(modelCEntity, gz::sim::components::Model()); ecm.CreateComponent(modelCEntity, - ignition::gazebo::components::Name("modelC_name")); + gz::sim::components::Name("modelC_name")); std::size_t foundLinks = 0; - ignition::gazebo::Model modelA(modelAEntity); + gz::sim::Model modelA(modelAEntity); auto links = modelA.Links(ecm); EXPECT_EQ(2u, links.size()); for (const auto &link : links) @@ -151,12 +151,12 @@ TEST(ModelTest, Links) } EXPECT_EQ(foundLinks, links.size()); - ignition::gazebo::Model modelB(modelBEntity); + gz::sim::Model modelB(modelBEntity); links = modelB.Links(ecm); ASSERT_EQ(1u, links.size()); EXPECT_EQ(linkBAEntity, links[0]); - ignition::gazebo::Model modelC(modelCEntity); + gz::sim::Model modelC(modelCEntity); EXPECT_EQ(0u, modelC.Links(ecm).size()); } @@ -168,41 +168,41 @@ TEST(ModelTest, Models) // - modelC // - modelD - ignition::gazebo::EntityComponentManager ecm; + gz::sim::EntityComponentManager ecm; // Model A auto modelAEntity = ecm.CreateEntity(); - ecm.CreateComponent(modelAEntity, ignition::gazebo::components::Model()); + ecm.CreateComponent(modelAEntity, gz::sim::components::Model()); ecm.CreateComponent(modelAEntity, - ignition::gazebo::components::Name("modelA_name")); + gz::sim::components::Name("modelA_name")); // Model B - Child of Model A auto modelBEntity = ecm.CreateEntity(); - ecm.CreateComponent(modelBEntity, ignition::gazebo::components::Model()); + ecm.CreateComponent(modelBEntity, gz::sim::components::Model()); ecm.CreateComponent(modelBEntity, - ignition::gazebo::components::Name("modelB_name")); + gz::sim::components::Name("modelB_name")); ecm.CreateComponent(modelBEntity, - ignition::gazebo::components::ParentEntity(modelAEntity)); + gz::sim::components::ParentEntity(modelAEntity)); // Model C - Child of Model A auto modelCEntity = ecm.CreateEntity(); - ecm.CreateComponent(modelCEntity, ignition::gazebo::components::Model()); + ecm.CreateComponent(modelCEntity, gz::sim::components::Model()); ecm.CreateComponent(modelCEntity, - ignition::gazebo::components::Name("modelC_name")); + gz::sim::components::Name("modelC_name")); ecm.CreateComponent(modelCEntity, - ignition::gazebo::components::ParentEntity(modelAEntity)); + gz::sim::components::ParentEntity(modelAEntity)); // Model D - Child of Model C auto modelDEntity = ecm.CreateEntity(); - ecm.CreateComponent(modelDEntity, ignition::gazebo::components::Model()); + ecm.CreateComponent(modelDEntity, gz::sim::components::Model()); ecm.CreateComponent(modelDEntity, - ignition::gazebo::components::Name("modelD_name")); + gz::sim::components::Name("modelD_name")); ecm.CreateComponent(modelDEntity, - ignition::gazebo::components::ParentEntity(modelCEntity)); + gz::sim::components::ParentEntity(modelCEntity)); std::size_t foundModels = 0; - ignition::gazebo::Model modelA(modelAEntity); + gz::sim::Model modelA(modelAEntity); auto models = modelA.Models(ecm); EXPECT_EQ(2u, models.size()); for (const auto &model : models) @@ -212,14 +212,14 @@ TEST(ModelTest, Models) } EXPECT_EQ(foundModels, models.size()); - ignition::gazebo::Model modelB(modelBEntity); + gz::sim::Model modelB(modelBEntity); EXPECT_EQ(0u, modelB.Models(ecm).size()); - ignition::gazebo::Model modelC(modelCEntity); + gz::sim::Model modelC(modelCEntity); models = modelC.Models(ecm); ASSERT_EQ(1u, models.size()); EXPECT_EQ(modelDEntity, models[0]); - ignition::gazebo::Model modelD(modelDEntity); + gz::sim::Model modelD(modelDEntity); EXPECT_EQ(0u, modelD.Models(ecm).size()); } diff --git a/src/Primitives.cc b/src/Primitives.cc index 2b9cd89282..4fa93cea54 100644 --- a/src/Primitives.cc +++ b/src/Primitives.cc @@ -19,8 +19,8 @@ #include #include "gz/sim/Primitives.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// constexpr const char * kBoxSdf = R"( @@ -293,7 +293,7 @@ constexpr const char *kSpotSdf = R"( )"; ///////////////////////////////////////////////// -std::string ignition::gazebo::getPrimitiveShape(const PrimitiveShape &_type) +std::string gz::sim::getPrimitiveShape(const PrimitiveShape &_type) { switch(_type) { @@ -313,7 +313,7 @@ std::string ignition::gazebo::getPrimitiveShape(const PrimitiveShape &_type) } ///////////////////////////////////////////////// -std::string ignition::gazebo::getPrimitiveLight(const PrimitiveLight &_type) +std::string gz::sim::getPrimitiveLight(const PrimitiveLight &_type) { switch(_type) { @@ -329,7 +329,7 @@ std::string ignition::gazebo::getPrimitiveLight(const PrimitiveLight &_type) } ///////////////////////////////////////////////// -std::string ignition::gazebo::getPrimitive(const std::string &_typeName) +std::string gz::sim::getPrimitive(const std::string &_typeName) { std::string type = common::lowercase(_typeName); @@ -350,15 +350,15 @@ std::string ignition::gazebo::getPrimitive(const std::string &_typeName) else if (type == "spot") return getPrimitiveLight(PrimitiveLight::kSpot); - ignwarn << "Invalid model string " << type << "\n"; - ignwarn << "The valid options are:\n"; - ignwarn << " - box\n"; - ignwarn << " - sphere\n"; - ignwarn << " - cylinder\n"; - ignwarn << " - capsule\n"; - ignwarn << " - ellipsoid\n"; - ignwarn << " - point\n"; - ignwarn << " - directional\n"; - ignwarn << " - spot\n"; + gzwarn << "Invalid model string " << type << "\n"; + gzwarn << "The valid options are:\n"; + gzwarn << " - box\n"; + gzwarn << " - sphere\n"; + gzwarn << " - cylinder\n"; + gzwarn << " - capsule\n"; + gzwarn << " - ellipsoid\n"; + gzwarn << " - point\n"; + gzwarn << " - directional\n"; + gzwarn << " - spot\n"; return ""; } diff --git a/src/Primitives_TEST.cc b/src/Primitives_TEST.cc index 112e948097..5e0777178b 100644 --- a/src/Primitives_TEST.cc +++ b/src/Primitives_TEST.cc @@ -20,8 +20,8 @@ #include #include -using PrimitiveShape = ignition::gazebo::PrimitiveShape; -using PrimitiveLight = ignition::gazebo::PrimitiveLight; +using PrimitiveShape = gz::sim::PrimitiveShape; +using PrimitiveLight = gz::sim::PrimitiveLight; ///////////////////////////////////////////////// TEST(Primitives, shapes) @@ -36,7 +36,7 @@ TEST(Primitives, shapes) for (auto prim : primitives) { - auto sdfString = ignition::gazebo::getPrimitiveShape(prim); + auto sdfString = gz::sim::getPrimitiveShape(prim); ASSERT_FALSE(sdfString.empty()); /// Verify that string contains valid SDF @@ -57,7 +57,7 @@ TEST(Primitives, lights) for (auto prim : primitives) { - auto sdfString = ignition::gazebo::getPrimitiveLight(prim); + auto sdfString = gz::sim::getPrimitiveLight(prim); ASSERT_FALSE(sdfString.empty()); /// Verify that string contains valid SDF @@ -70,7 +70,7 @@ TEST(Primitives, lights) ///////////////////////////////////////////////// TEST(Primitives, invalid) { - auto sdfString = ignition::gazebo::getPrimitive("foobar"); + auto sdfString = gz::sim::getPrimitive("foobar"); ASSERT_TRUE(sdfString.empty()); } @@ -84,7 +84,7 @@ TEST(Primitives, strings) for (auto prim : primitives) { - auto sdfString = ignition::gazebo::getPrimitive(prim); + auto sdfString = gz::sim::getPrimitive(prim); ASSERT_FALSE(sdfString.empty()); /// Verify that string contains valid SDF diff --git a/src/SdfEntityCreator.cc b/src/SdfEntityCreator.cc index 0c9962937e..876fcffb4e 100644 --- a/src/SdfEntityCreator.cc +++ b/src/SdfEntityCreator.cc @@ -80,7 +80,7 @@ #include "gz/sim/components/WindMode.hh" #include "gz/sim/components/World.hh" -class ignition::gazebo::SdfEntityCreatorPrivate +class gz::sim::SdfEntityCreatorPrivate { /// \brief Pointer to entity component manager. We don't assume ownership. public: EntityComponentManager *ecm{nullptr}; @@ -101,8 +101,8 @@ class ignition::gazebo::SdfEntityCreatorPrivate public: std::map newVisuals; }; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// /// \brief Resolve the pose of an SDF DOM object with respect to its relative_to @@ -127,7 +127,7 @@ static std::optional ResolveJointAxis( const sdf::Errors resolveAxisErrors = _unresolvedAxis.ResolveXyz(axisXyz); if (!resolveAxisErrors.empty()) { - ignerr << "Failed to resolve axis" << std::endl; + gzerr << "Failed to resolve axis" << std::endl; return std::nullopt; } @@ -136,7 +136,7 @@ static std::optional ResolveJointAxis( const sdf::Errors setXyzErrors = resolvedAxis.SetXyz(axisXyz); if (!setXyzErrors.empty()) { - ignerr << "Failed to resolve axis" << std::endl; + gzerr << "Failed to resolve axis" << std::endl; return std::nullopt; } @@ -447,13 +447,13 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Model *_model, } else { - ignerr << "Could not find the canonical link entity for " + gzerr << "Could not find the canonical link entity for " << canonicalLinkPair.second << "\n"; } } else if(!isStatic) { - ignerr << "Could not resolve the canonical link for " << _model->Name() + gzerr << "Could not resolve the canonical link for " << _model->Name() << "\n"; } @@ -624,7 +624,7 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Joint *_joint, auto resolvedAxis = ResolveJointAxis(*_joint->Axis(0)); if (!resolvedAxis) { - ignerr << "Failed to resolve joint axis 0 for joint '" << _joint->Name() + gzerr << "Failed to resolve joint axis 0 for joint '" << _joint->Name() << "'" << std::endl; return kNullEntity; } @@ -638,7 +638,7 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Joint *_joint, auto resolvedAxis = ResolveJointAxis(*_joint->Axis(1)); if (!resolvedAxis) { - ignerr << "Failed to resolve joint axis 1 for joint '" << _joint->Name() + gzerr << "Failed to resolve joint axis 1 for joint '" << _joint->Name() << "'" << std::endl; return kNullEntity; } @@ -667,12 +667,12 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Joint *_joint, _joint->ResolveParentLink(resolvedParentLinkName); if (!resolveParentErrors.empty()) { - ignerr << "Failed to resolve parent link for joint '" << _joint->Name() + gzerr << "Failed to resolve parent link for joint '" << _joint->Name() << "' with parent name '" << _joint->ParentLinkName() << "'" << std::endl; for (const auto &error : resolveParentErrors) { - ignerr << error << std::endl; + gzerr << error << std::endl; } return kNullEntity; @@ -692,12 +692,12 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Joint *_joint, _joint->ResolveChildLink(resolvedChildLinkName); if (!resolveChildErrors.empty()) { - ignerr << "Failed to resolve child link for joint '" << _joint->Name() + gzerr << "Failed to resolve child link for joint '" << _joint->Name() << "' with child name '" << _joint->ChildLinkName() << "'" << std::endl; for (const auto &error : resolveChildErrors) { - ignerr << error << std::endl; + gzerr << error << std::endl; } return kNullEntity; @@ -846,7 +846,7 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Sensor *_sensor) // \todo(anyone) Implement CPU-based lidar // this->dataPtr->ecm->CreateComponent(sensorEntity, // components::Lidar(*_sensor)); - ignwarn << "Sensor type LIDAR not supported yet. Try using" + gzwarn << "Sensor type LIDAR not supported yet. Try using" << "a GPU LIDAR instead." << std::endl; } else if (_sensor->Type() == sdf::SensorType::DEPTH_CAMERA) @@ -959,7 +959,7 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Sensor *_sensor) } else { - ignwarn << "Sensor type [" << static_cast(_sensor->Type()) + gzwarn << "Sensor type [" << static_cast(_sensor->Type()) << "] not supported yet." << std::endl; } diff --git a/src/SdfEntityCreator_TEST.cc b/src/SdfEntityCreator_TEST.cc index 624359c0cb..414175f998 100644 --- a/src/SdfEntityCreator_TEST.cc +++ b/src/SdfEntityCreator_TEST.cc @@ -55,11 +55,11 @@ #include "../test/helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// -class EntityCompMgrTest : public gazebo::EntityComponentManager +class EntityCompMgrTest : public sim::EntityComponentManager { public: void ProcessEntityRemovals() { @@ -167,35 +167,35 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) if (modelCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(1, 2, 3, 0, 0, 1), + EXPECT_EQ(gz::math::Pose3d(1, 2, 3, 0, 0, 1), _pose->Data()); EXPECT_EQ("box", _name->Data()); boxModelEntity = _entity; } else if (modelCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(-1, -2, -3, 0, 0, 1), + EXPECT_EQ(gz::math::Pose3d(-1, -2, -3, 0, 0, 1), _pose->Data()); EXPECT_EQ("cylinder", _name->Data()); cylModelEntity = _entity; } else if (modelCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0, 0, 0, 0, 0, 1), + EXPECT_EQ(gz::math::Pose3d(0, 0, 0, 0, 0, 1), _pose->Data()); EXPECT_EQ("sphere", _name->Data()); sphModelEntity = _entity; } else if (modelCount == 4) { - EXPECT_EQ(ignition::math::Pose3d(-4, -5, -6, 0, 0, 1), + EXPECT_EQ(gz::math::Pose3d(-4, -5, -6, 0, 0, 1), _pose->Data()); EXPECT_EQ("capsule", _name->Data()); capModelEntity = _entity; } else if (modelCount == 5) { - EXPECT_EQ(ignition::math::Pose3d(4, 5, 6, 0, 0, 1), + EXPECT_EQ(gz::math::Pose3d(4, 5, 6, 0, 0, 1), _pose->Data()); EXPECT_EQ("ellipsoid", _name->Data()); ellipModelEntity = _entity; @@ -236,7 +236,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) if (linkCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.1, 0.1, 0.1, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.1, 0.1, 0.1, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_link", _name->Data()); @@ -247,7 +247,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (linkCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.2, 0.2, 0.2, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.2, 0.2, 0.2, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_link", _name->Data()); @@ -258,7 +258,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (linkCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.3, 0.3, 0.3, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.3, 0.3, 0.3, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_link", _name->Data()); @@ -269,7 +269,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (linkCount == 4) { - EXPECT_EQ(ignition::math::Pose3d(0.5, 0.5, 0.5, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.5, 0.5, 0.5, 0, 0, 0), _pose->Data()); EXPECT_EQ("capsule_link", _name->Data()); @@ -280,7 +280,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (linkCount == 5) { - EXPECT_EQ(ignition::math::Pose3d(0.8, 0.8, 0.8, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.8, 0.8, 0.8, 0, 0, 0), _pose->Data()); EXPECT_EQ("ellipsoid_link", _name->Data()); @@ -370,7 +370,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) if (collisionCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.11, 0.11, 0.11, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.11, 0.11, 0.11, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_collision", _name->Data()); @@ -385,7 +385,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (collisionCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.21, 0.21, 0.21, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.21, 0.21, 0.21, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_collision", _name->Data()); @@ -400,7 +400,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (collisionCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.31, 0.31, 0.31, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.31, 0.31, 0.31, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_collision", _name->Data()); @@ -414,7 +414,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (collisionCount == 4) { - EXPECT_EQ(ignition::math::Pose3d(0.51, 0.51, 0.51, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.51, 0.51, 0.51, 0, 0, 0), _pose->Data()); EXPECT_EQ("capsule_collision", _name->Data()); @@ -429,7 +429,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (collisionCount == 5) { - EXPECT_EQ(ignition::math::Pose3d(0.81, 0.81, 0.81, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.81, 0.81, 0.81, 0, 0, 0), _pose->Data()); EXPECT_EQ("ellipsoid_collision", _name->Data()); @@ -439,7 +439,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) EXPECT_EQ(sdf::GeometryType::ELLIPSOID, _geometry->Data().Type()); EXPECT_NE(nullptr, _geometry->Data().EllipsoidShape()); - EXPECT_EQ(ignition::math::Vector3d(0.4, 0.6, 1.6), + EXPECT_EQ(gz::math::Vector3d(0.4, 0.6, 1.6), _geometry->Data().EllipsoidShape()->Radii()); } return true; @@ -485,7 +485,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) if (visualCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.12, 0.12, 0.12, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.12, 0.12, 0.12, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_visual", _name->Data()); @@ -511,7 +511,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (visualCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.22, 0.22, 0.22, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.22, 0.22, 0.22, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_visual", _name->Data()); @@ -537,7 +537,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (visualCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.32, 0.32, 0.32, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.32, 0.32, 0.32, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_visual", _name->Data()); @@ -562,7 +562,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (visualCount == 4) { - EXPECT_EQ(ignition::math::Pose3d(0.52, 0.52, 0.52, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.52, 0.52, 0.52, 0, 0, 0), _pose->Data()); EXPECT_EQ("capsule_visual", _name->Data()); @@ -588,7 +588,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (visualCount == 5) { - EXPECT_EQ(ignition::math::Pose3d(0.82, 0.82, 0.82, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.82, 0.82, 0.82, 0, 0, 0), _pose->Data()); EXPECT_EQ("ellipsoid_visual", _name->Data()); @@ -602,7 +602,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) EXPECT_EQ(sdf::GeometryType::ELLIPSOID, _geometry->Data().Type()); EXPECT_NE(nullptr, _geometry->Data().EllipsoidShape()); - EXPECT_EQ(ignition::math::Vector3d(0.4, 0.6, 1.6), + EXPECT_EQ(gz::math::Vector3d(0.4, 0.6, 1.6), _geometry->Data().EllipsoidShape()->Radii()); EXPECT_EQ(math::Color(0.0f, 0.0f, 0.0f), _material->Data().Emissive()); @@ -636,7 +636,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) lightCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 10, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.0, 0.0, 10, 0, 0, 0), _pose->Data()); EXPECT_EQ("sun", _name->Data()); @@ -646,19 +646,19 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) EXPECT_EQ("sun", _light->Data().Name()); EXPECT_EQ(sdf::LightType::DIRECTIONAL, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 10, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0, 0, 10, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ("", _light->Data().PoseRelativeTo()); EXPECT_TRUE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.8f, 0.8f, 0.8f, 1), + EXPECT_EQ(gz::math::Color(0.8f, 0.8f, 0.8f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(gz::math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(1000, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.9, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.01, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); - EXPECT_EQ(ignition::math::Vector3d(-0.5, 0.1, -0.9), + EXPECT_EQ(gz::math::Vector3d(-0.5, 0.1, -0.9), _light->Data().Direction()); return true; }); @@ -733,7 +733,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) EXPECT_EQ(worldEntity, _parent->Data()); EXPECT_EQ(worldEntity, this->ecm.ParentEntity(_entity)); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 0, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0, 0, 0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere", _name->Data()); sphModelEntity = _entity; @@ -764,7 +764,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) linkCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_link", _name->Data()); EXPECT_EQ(sphModelEntity, _parent->Data()); @@ -803,7 +803,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) visualCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_visual", _name->Data()); @@ -845,7 +845,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) // light attached to link if (lightCount == 1u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 1.0, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.0, 0.0, 1.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("link_light_point", _name->Data()); @@ -854,13 +854,13 @@ TEST_F(SdfEntityCreatorTest, CreateLights) EXPECT_EQ("link_light_point", _light->Data().Name()); EXPECT_EQ(sdf::LightType::POINT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 1, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0, 0, 1, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.0f, 0.0f, 1.0f, 1), + EXPECT_EQ(gz::math::Color(0.0f, 0.0f, 1.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.1f, 0.1f, 0.1f, 1), + EXPECT_EQ(gz::math::Color(0.1f, 0.1f, 0.1f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(2, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.05, _light->Data().ConstantAttenuationFactor()); @@ -870,7 +870,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) // directional light in the world else if (lightCount == 2u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 10, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.0, 0.0, 10, 0, 0, 0), _pose->Data()); EXPECT_EQ("directional", _name->Data()); @@ -879,25 +879,25 @@ TEST_F(SdfEntityCreatorTest, CreateLights) EXPECT_EQ("directional", _light->Data().Name()); EXPECT_EQ(sdf::LightType::DIRECTIONAL, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 10, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0, 0, 10, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_TRUE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.8f, 0.8f, 0.8f, 1), + EXPECT_EQ(gz::math::Color(0.8f, 0.8f, 0.8f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(gz::math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(100, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.9, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.01, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); - EXPECT_EQ(ignition::math::Vector3d(0.5, 0.2, -0.9), + EXPECT_EQ(gz::math::Vector3d(0.5, 0.2, -0.9), _light->Data().Direction()); } // point light in the world else if (lightCount == 3u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, -1.5, 3, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.0, -1.5, 3, 0, 0, 0), _pose->Data()); EXPECT_EQ("point", _name->Data()); @@ -906,13 +906,13 @@ TEST_F(SdfEntityCreatorTest, CreateLights) EXPECT_EQ("point", _light->Data().Name()); EXPECT_EQ(sdf::LightType::POINT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, -1.5, 3, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0, -1.5, 3, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(1.0f, 0.0f, 0.0f, 1), + EXPECT_EQ(gz::math::Color(1.0f, 0.0f, 0.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.1f, 0.1f, 0.1f, 1), + EXPECT_EQ(gz::math::Color(0.1f, 0.1f, 0.1f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(4, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.2, _light->Data().ConstantAttenuationFactor()); @@ -922,7 +922,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) // spot light in the world else if (lightCount == 4u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 1.5, 3, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.0, 1.5, 3, 0, 0, 0), _pose->Data()); EXPECT_EQ("spot", _name->Data()); @@ -931,19 +931,19 @@ TEST_F(SdfEntityCreatorTest, CreateLights) EXPECT_EQ("spot", _light->Data().Name()); EXPECT_EQ(sdf::LightType::SPOT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 1.5, 3, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0, 1.5, 3, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.0f, 1.0f, 0.0f, 1), + EXPECT_EQ(gz::math::Color(0.0f, 1.0f, 0.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(gz::math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(5, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.3, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.4, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); - EXPECT_EQ(ignition::math::Vector3d(0.0, 0.0, -1.0), + EXPECT_EQ(gz::math::Vector3d(0.0, 0.0, -1.0), _light->Data().Direction()); EXPECT_DOUBLE_EQ(0.1, _light->Data().SpotInnerAngle().Radian()); EXPECT_DOUBLE_EQ(0.5, _light->Data().SpotOuterAngle().Radian()); @@ -1218,7 +1218,7 @@ size_t removedCount(EntityCompMgrTest &_manager) { size_t count = 0; _manager.EachRemoved( - [&](const ignition::gazebo::Entity &, const Ts *...) -> bool + [&](const gz::sim::Entity &, const Ts *...) -> bool { ++count; return true; diff --git a/src/SdfGenerator.cc b/src/SdfGenerator.cc index 2bac6037cf..411ce0d730 100644 --- a/src/SdfGenerator.cc +++ b/src/SdfGenerator.cc @@ -60,12 +60,12 @@ #include "gz/sim/components/World.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace sdf_generator { @@ -970,7 +970,7 @@ namespace sdf_generator } else { - ignwarn << "Error retrieving Fuel model version," + gzwarn << "Error retrieving Fuel model version," << " saving model without version." << std::endl; } @@ -1017,5 +1017,5 @@ namespace sdf_generator } } } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/src/SdfGenerator.hh b/src/SdfGenerator.hh index 9824cf6737..c8cc3f770d 100644 --- a/src/SdfGenerator.hh +++ b/src/SdfGenerator.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SDFGENERATOR_HH_ -#define IGNITION_GAZEBO_SDFGENERATOR_HH_ +#ifndef GZ_SIM_SDFGENERATOR_HH_ +#define GZ_SIM_SDFGENERATOR_HH_ #include @@ -26,12 +26,12 @@ #include "gz/sim/EntityComponentManager.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace sdf_generator { @@ -45,7 +45,7 @@ namespace sdf_generator /// \input[in] _config Configuration for the world generator /// \returns Generated world string if generation succeeded. /// Otherwise, nullopt - IGNITION_GAZEBO_VISIBLE + GZ_GAZEBO_VISIBLE std::optional generateWorld( const EntityComponentManager &_ecm, const Entity &_entity, const IncludeUriMap &_includeUriMap = IncludeUriMap(), @@ -58,7 +58,7 @@ namespace sdf_generator /// \input[in] _includeUriMap Map from file paths to URIs used to preserve /// included Fuel models /// \input[in] _config Configuration for the world generator - IGNITION_GAZEBO_VISIBLE + GZ_GAZEBO_VISIBLE bool updateWorldElement( sdf::ElementPtr _elem, const EntityComponentManager &_ecm, const Entity &_entity, @@ -71,7 +71,7 @@ namespace sdf_generator /// \input[in] _ecm Immutable reference to the Entity Component Manager /// \input[in] _entity Model entity /// \returns true if update succeeded. - IGNITION_GAZEBO_VISIBLE + GZ_GAZEBO_VISIBLE bool updateModelElement(const sdf::ElementPtr &_elem, const EntityComponentManager &_ecm, const Entity &_entity); @@ -82,7 +82,7 @@ namespace sdf_generator /// \input[in] _saveFuelVersion True if "Save Fuel model versions" is enabled /// \input[in] _includeUriMap Map from file paths to URIs used to preserve /// included Fuel models - IGNITION_GAZEBO_VISIBLE + GZ_GAZEBO_VISIBLE void updateModelElementWithNestedInclude(sdf::ElementPtr &_elem, const bool _saveFuelVersion, const IncludeUriMap &_includeUriMap); @@ -94,7 +94,7 @@ namespace sdf_generator /// \input[in] _entity Entity of included resource /// \input[in] _uri Uri of the resource /// \returns true if update succeeded. - IGNITION_GAZEBO_VISIBLE + GZ_GAZEBO_VISIBLE bool updateIncludeElement(const sdf::ElementPtr &_elem, const EntityComponentManager &_ecm, const Entity &_entity, const std::string &_uri); @@ -105,7 +105,7 @@ namespace sdf_generator /// \input[in] _ecm Immutable reference to the Entity Component Manager /// \input[in] _entity Link entity /// \returns true if update succeeded. - IGNITION_GAZEBO_VISIBLE + GZ_GAZEBO_VISIBLE bool updateLinkElement(const sdf::ElementPtr &_elem, const EntityComponentManager &_ecm, const Entity &_entity); @@ -116,7 +116,7 @@ namespace sdf_generator /// \input[in] _ecm Immutable reference to the Entity Component Manager /// \input[in] _entity Sensor entity /// \returns true if update succeeded. - IGNITION_GAZEBO_VISIBLE + GZ_GAZEBO_VISIBLE bool updateSensorElement(sdf::ElementPtr _elem, const EntityComponentManager &_ecm, const Entity &_entity); @@ -127,7 +127,7 @@ namespace sdf_generator /// \input[in] _ecm Immutable reference to the Entity Component Manager /// \input[in] _entity Light entity /// \returns true if update succeeded. - IGNITION_GAZEBO_VISIBLE + GZ_GAZEBO_VISIBLE bool updateLightElement(sdf::ElementPtr _elem, const EntityComponentManager &_ecm, const Entity &_entity); @@ -138,13 +138,13 @@ namespace sdf_generator /// \input[in] _ecm Immutable reference to the Entity Component Manager /// \input[in] _entity joint entity /// \returns true if update succeeded. - IGNITION_GAZEBO_VISIBLE + GZ_GAZEBO_VISIBLE bool updateJointElement(sdf::ElementPtr _elem, const EntityComponentManager &_ecm, const Entity &_entity); } // namespace sdf_generator } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz -#endif /* end of include guard: IGNITION_GAZEBO_SDFGENERATOR_HH_ */ +#endif /* end of include guard: GZ_SIM_SDFGENERATOR_HH_ */ diff --git a/src/SdfGenerator_TEST.cc b/src/SdfGenerator_TEST.cc index 638f6a0b7b..42eea8b70b 100644 --- a/src/SdfGenerator_TEST.cc +++ b/src/SdfGenerator_TEST.cc @@ -45,8 +45,8 @@ #include "SdfGenerator.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// /// \breif Checks if elemA is a subset of elemB @@ -895,7 +895,7 @@ TEST_F(ElementUpdateFixture, WorldWithModelsExpandedWithOneIncluded) } ///////////////////////////////////////////////// -// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +// See https://github.com/gazebosim/gz-sim/issues/1175 TEST_F(ElementUpdateFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(WorldWithModelsUsingRelativeResourceURIs)) { diff --git a/src/Server.cc b/src/Server.cc index d567c88e24..7e28be9cd5 100644 --- a/src/Server.cc +++ b/src/Server.cc @@ -30,8 +30,8 @@ #include "ServerPrivate.hh" #include "SimulationRunner.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; /// \brief This struct provides access to the default world. struct DefaultWorld @@ -79,7 +79,7 @@ Server::Server(const ServerConfig &_config) case ServerConfig::SourceType::kSdfRoot: { this->dataPtr->sdfRoot = _config.SdfRoot()->Clone(); - ignmsg << "Loading SDF world from SDF DOM.\n"; + gzmsg << "Loading SDF world from SDF DOM.\n"; break; } @@ -94,7 +94,7 @@ Server::Server(const ServerConfig &_config) { msg += "File path [" + _config.SdfFile() + "].\n"; } - ignmsg << msg; + gzmsg << msg; errors = this->dataPtr->sdfRoot.LoadSdfString(_config.SdfString()); break; } @@ -106,12 +106,12 @@ Server::Server(const ServerConfig &_config) if (filePath.empty()) { - ignerr << "Failed to find world [" << _config.SdfFile() << "]" + gzerr << "Failed to find world [" << _config.SdfFile() << "]" << std::endl; return; } - ignmsg << "Loading SDF world file[" << filePath << "].\n"; + gzmsg << "Loading SDF world file[" << filePath << "].\n"; // \todo(nkoenig) Async resource download. // This call can block for a long period of time while @@ -125,7 +125,7 @@ Server::Server(const ServerConfig &_config) case ServerConfig::SourceType::kNone: default: { - ignmsg << "Loading default world.\n"; + gzmsg << "Loading default world.\n"; // Load an empty world. /// \todo(nkoenig) Add a "AddWorld" function to sdf::Root. errors = this->dataPtr->sdfRoot.LoadSdfString(DefaultWorld::World()); @@ -136,7 +136,7 @@ Server::Server(const ServerConfig &_config) if (!errors.empty()) { for (auto &err : errors) - ignerr << err << "\n"; + gzerr << err << "\n"; return; } @@ -175,14 +175,14 @@ bool Server::Run(const bool _blocking, const uint64_t _iterations, std::lock_guard lock(this->dataPtr->runMutex); if (!this->dataPtr->sigHandler.Initialized()) { - ignerr << "Signal handlers were not created. The server won't run.\n"; + gzerr << "Signal handlers were not created. The server won't run.\n"; return false; } // Do not allow running more than once. if (this->dataPtr->running) { - ignwarn << "The server is already runnnng.\n"; + gzwarn << "The server is already runnnng.\n"; return false; } } @@ -299,7 +299,7 @@ std::optional Server::AddSystem(const SystemPluginPtr &_system, // Do not allow running more than once. if (this->dataPtr->running) { - ignerr << "Cannot add system while the server is runnnng.\n"; + gzerr << "Cannot add system while the server is runnnng.\n"; return false; } @@ -319,7 +319,7 @@ std::optional Server::AddSystem(const std::shared_ptr &_system, std::lock_guard lock(this->dataPtr->runMutex); if (this->dataPtr->running) { - ignerr << "Cannot add system while the server is runnnng.\n"; + gzerr << "Cannot add system while the server is runnnng.\n"; return false; } diff --git a/src/ServerConfig.cc b/src/ServerConfig.cc index 0f26343c6f..727c919ef7 100644 --- a/src/ServerConfig.cc +++ b/src/ServerConfig.cc @@ -27,11 +27,11 @@ #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace 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() @@ -204,7 +204,7 @@ class ignition::gazebo::ServerConfigPrivate // Set a default log record path this->logRecordPath = common::joinPaths(home, - ".ignition", "gazebo", "log", common::timeToIso(this->timestamp)); + ".gz", "sim", "log", common::timeToIso(this->timestamp)); // If directory already exists, do not overwrite. This could potentially // happen if multiple simulation instances are started in rapid @@ -327,6 +327,9 @@ ServerConfig::~ServerConfig() = default; ////////////////////////////////////////////////// bool ServerConfig::SetSdfFile(const std::string &_file) { + if (_file.empty()) + return false; + this->dataPtr->source = ServerConfig::SourceType::kSdfFile; this->dataPtr->sdfFile = _file; this->dataPtr->sdfString = ""; @@ -497,7 +500,7 @@ unsigned int ServerConfig::Seed() const void ServerConfig::SetSeed(unsigned int _seed) { this->dataPtr->seed = _seed; - ignition::math::Rand::Seed(_seed); + gz::math::Rand::Seed(_seed); } ///////////////////////////////////////////////// @@ -572,7 +575,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; @@ -602,7 +605,7 @@ ServerConfig::LogRecordPlugin() const { auto entityName = "*"; auto entityType = "world"; - auto pluginName = "ignition::gazebo::systems::LogRecord"; + auto pluginName = "gz::sim::systems::LogRecord"; auto pluginFilename = "ignition-gazebo-log-system"; sdf::ElementPtr recordElem; @@ -610,7 +613,7 @@ ServerConfig::LogRecordPlugin() const recordElem = std::make_shared(); recordElem->SetName("plugin"); - igndbg << "Generating LogRecord SDF:" << std::endl; + gzdbg << "Generating LogRecord SDF:" << std::endl; if (!this->LogRecordPath().empty()) { @@ -660,7 +663,7 @@ ServerConfig::LogRecordPlugin() const topicElem->Set(topic); } - igndbg << recordElem->ToString("") << std::endl; + gzdbg << recordElem->ToString("") << std::endl; return ServerConfig::PluginInfo(entityName, entityType, @@ -772,14 +775,14 @@ parsePluginsFromDoc(const tinyxml2::XMLDocument &_doc) auto root = _doc.RootElement(); if (root == nullptr) { - ignerr << "No element found when parsing plugins\n"; + gzerr << "No element found when parsing plugins\n"; return ret; } auto plugins = root->FirstChildElement("plugins"); if (plugins == nullptr) { - ignerr << "No element found when parsing plugins\n"; + gzerr << "No element found when parsing plugins\n"; return ret; } @@ -795,7 +798,7 @@ parsePluginsFromDoc(const tinyxml2::XMLDocument &_doc) std::string name = nameStr == nullptr ? "" : nameStr; if (name.empty()) { - ignerr << "Plugin is missing the name attribute. " + gzerr << "Plugin is missing the name attribute. " << "Skipping this plugin.\n"; continue; } @@ -805,7 +808,7 @@ parsePluginsFromDoc(const tinyxml2::XMLDocument &_doc) std::string file = fileStr == nullptr ? "" : fileStr; if (file.empty()) { - ignerr << "A Plugin with name[" << name << "] is " + gzerr << "A Plugin with name[" << name << "] is " << "missing the filename attribute. Skipping this plugin.\n"; continue; } @@ -815,7 +818,7 @@ parsePluginsFromDoc(const tinyxml2::XMLDocument &_doc) std::string entityName = entityNameStr == nullptr ? "" : entityNameStr; if (entityName.empty()) { - ignerr << "A Plugin with name[" << name << "] and " + gzerr << "A Plugin with name[" << name << "] and " << "filename[" << file << "] is missing the entity_name attribute. " << "Skipping this plugin.\n"; continue; @@ -826,7 +829,7 @@ parsePluginsFromDoc(const tinyxml2::XMLDocument &_doc) std::string entityType = entityTypeStr == nullptr ? "" : entityTypeStr; if (entityType.empty()) { - ignerr << "A Plugin with name[" << name << "] and " + gzerr << "A Plugin with name[" << name << "] and " << "filename[" << file << "] is missing the entity_type attribute. " << "Skipping this plugin.\n"; continue; @@ -844,7 +847,7 @@ parsePluginsFromDoc(const tinyxml2::XMLDocument &_doc) ///////////////////////////////////////////////// std::list -ignition::gazebo::parsePluginsFromFile(const std::string &_fname) +gz::sim::parsePluginsFromFile(const std::string &_fname) { tinyxml2::XMLDocument doc; doc.LoadFile(_fname.c_str()); @@ -853,7 +856,7 @@ ignition::gazebo::parsePluginsFromFile(const std::string &_fname) ///////////////////////////////////////////////// std::list -ignition::gazebo::parsePluginsFromString(const std::string &_str) +gz::sim::parsePluginsFromString(const std::string &_str) { tinyxml2::XMLDocument doc; doc.Parse(_str.c_str()); @@ -863,31 +866,31 @@ ignition::gazebo::parsePluginsFromString(const std::string &_str) ///////////////////////////////////////////////// std::list -ignition::gazebo::loadPluginInfo(bool _isPlayback) +gz::sim::loadPluginInfo(bool _isPlayback) { std::list ret; // 1. Check contents of environment variable std::string envConfig; - bool configSet = ignition::common::env(gazebo::kServerConfigPathEnv, + bool configSet = gz::common::env(sim::kServerConfigPathEnv, envConfig, true); if (configSet) { - if (ignition::common::exists(envConfig)) + if (gz::common::exists(envConfig)) { // Parse configuration stored in environment variable - ret = ignition::gazebo::parsePluginsFromFile(envConfig); + ret = gz::sim::parsePluginsFromFile(envConfig); if (ret.empty()) { // This may be desired behavior, but warn just in case. // Some users may want to defer all loading until later // during runtime. - ignwarn << gazebo::kServerConfigPathEnv + gzwarn << sim::kServerConfigPathEnv << " set but no plugins found\n"; } - igndbg << "Loaded (" << ret.size() << ") plugins from file " << + gzdbg << "Loaded (" << ret.size() << ") plugins from file " << "[" << envConfig << "]\n"; return ret; @@ -897,7 +900,7 @@ ignition::gazebo::loadPluginInfo(bool _isPlayback) // This may be desired behavior, but warn just in case. // Some users may want to defer all loading until late // during runtime. - ignwarn << gazebo::kServerConfigPathEnv + gzwarn << sim::kServerConfigPathEnv << " set but no file found," << " no plugins loaded\n"; return ret; @@ -915,59 +918,59 @@ ignition::gazebo::loadPluginInfo(bool _isPlayback) } std::string defaultConfigDir; - ignition::common::env(IGN_HOMEDIR, defaultConfigDir); - defaultConfigDir = ignition::common::joinPaths(defaultConfigDir, ".ignition", - "gazebo", IGNITION_GAZEBO_MAJOR_VERSION_STR); + gz::common::env(IGN_HOMEDIR, defaultConfigDir); + defaultConfigDir = gz::common::joinPaths(defaultConfigDir, ".gz", + "sim", GZ_SIM_MAJOR_VERSION_STR); - auto defaultConfig = ignition::common::joinPaths(defaultConfigDir, + auto defaultConfig = gz::common::joinPaths(defaultConfigDir, configFilename); - if (!ignition::common::exists(defaultConfig)) + if (!gz::common::exists(defaultConfig)) { - auto installedConfig = ignition::common::joinPaths( - IGNITION_GAZEBO_SERVER_CONFIG_PATH, + auto installedConfig = gz::common::joinPaths( + GZ_SIM_SERVER_CONFIG_PATH, configFilename); - if (!ignition::common::createDirectories(defaultConfigDir)) + if (!gz::common::createDirectories(defaultConfigDir)) { - ignerr << "Failed to create directory [" << defaultConfigDir + gzerr << "Failed to create directory [" << defaultConfigDir << "]." << std::endl; return ret; } - if (!ignition::common::exists(installedConfig)) + if (!gz::common::exists(installedConfig)) { - ignerr << "Failed to copy installed config [" << installedConfig + gzerr << "Failed to copy installed config [" << installedConfig << "] to default config [" << defaultConfig << "]." << "(file " << installedConfig << " doesn't exist)" << std::endl; return ret; } - else if (!ignition::common::copyFile(installedConfig, defaultConfig)) + else if (!gz::common::copyFile(installedConfig, defaultConfig)) { - ignerr << "Failed to copy installed config [" << installedConfig + gzerr << "Failed to copy installed config [" << installedConfig << "] to default config [" << defaultConfig << "]." << std::endl; return ret; } else { - ignmsg << "Copied installed config [" << installedConfig + gzmsg << "Copied installed config [" << installedConfig << "] to default config [" << defaultConfig << "]." << std::endl; } } - ret = ignition::gazebo::parsePluginsFromFile(defaultConfig); + ret = gz::sim::parsePluginsFromFile(defaultConfig); if (ret.empty()) { // This may be desired behavior, but warn just in case. - ignwarn << "Loaded config: [" << defaultConfig + gzwarn << "Loaded config: [" << defaultConfig << "], but no plugins found\n"; } - igndbg << "Loaded (" << ret.size() << ") plugins from file " << + gzdbg << "Loaded (" << ret.size() << ") plugins from file " << "[" << defaultConfig << "]\n"; return ret; diff --git a/src/ServerConfig_TEST.cc b/src/ServerConfig_TEST.cc index 08962d53e6..25afaec84a 100644 --- a/src/ServerConfig_TEST.cc +++ b/src/ServerConfig_TEST.cc @@ -22,8 +22,8 @@ #include #include -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace 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()); } ////////////////////////////////////////////////// @@ -179,11 +179,11 @@ TEST(ParsePluginsFromFile, PlaybackConfig) TEST(LoadPluginInfo, FromEmptyEnv) { // Set environment to something that doesn't exist - ASSERT_TRUE(common::setenv(gazebo::kServerConfigPathEnv, "foo")); + ASSERT_TRUE(common::setenv(sim::kServerConfigPathEnv, "foo")); auto plugins = loadPluginInfo(); EXPECT_EQ(0u, plugins.size()); - EXPECT_TRUE(common::unsetenv(gazebo::kServerConfigPathEnv)); + EXPECT_TRUE(common::unsetenv(sim::kServerConfigPathEnv)); } ////////////////////////////////////////////////// @@ -192,7 +192,7 @@ TEST(LoadPluginInfo, FromValidEnv) auto validPath = common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "server_valid2.config"); - ASSERT_TRUE(common::setenv(gazebo::kServerConfigPathEnv, validPath)); + ASSERT_TRUE(common::setenv(sim::kServerConfigPathEnv, validPath)); auto plugins = loadPluginInfo(); ASSERT_EQ(2u, plugins.size()); @@ -202,16 +202,16 @@ 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(gazebo::kServerConfigPathEnv)); + EXPECT_TRUE(common::unsetenv(sim::kServerConfigPathEnv)); } ////////////////////////////////////////////////// @@ -225,7 +225,7 @@ 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 60d17d4776..60fb5cff65 100644 --- a/src/ServerPrivate.cc +++ b/src/ServerPrivate.cc @@ -29,8 +29,8 @@ #include "gz/sim/Util.hh" #include "SimulationRunner.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; /// \brief This struct provides access to the record plugin SDF string struct LoggingPlugin @@ -41,7 +41,7 @@ struct LoggingPlugin { static std::string recordPluginFileName = std::string("ignition-gazebo") + - IGNITION_GAZEBO_MAJOR_VERSION_STR + "-log-system"; + GZ_SIM_MAJOR_VERSION_STR + "-log-system"; return recordPluginFileName; } @@ -59,7 +59,7 @@ struct LoggingPlugin public: static std::string &RecordPluginName() { static std::string recordPluginName = - "ignition::gazebo::systems::LogRecord"; + "gz::sim::systems::LogRecord"; return recordPluginName; } @@ -76,7 +76,7 @@ struct LoggingPlugin public: static std::string &PlaybackPluginName() { static std::string playbackPluginName = - "ignition::gazebo::systems::LogPlayback"; + "gz::sim::systems::LogPlayback"; return playbackPluginName; } }; @@ -107,7 +107,7 @@ ServerPrivate::~ServerPrivate() ////////////////////////////////////////////////// void ServerPrivate::OnSignal(int _sig) { - igndbg << "Server received signal[" << _sig << "]\n"; + gzdbg << "Server received signal[" << _sig << "]\n"; this->Stop(); } @@ -155,7 +155,7 @@ bool ServerPrivate::Run(const uint64_t _iterations, if (!networkReady || receivedStop) { - ignerr << "Failed to start network, simulation terminating" << std::endl; + gzerr << "Failed to start network, simulation terminating" << std::endl; return false; } } @@ -321,11 +321,11 @@ void ServerPrivate::SetupTransport() std::string worldsService{"/gazebo/worlds"}; if (this->node.Advertise(worldsService, &ServerPrivate::WorldsService, this)) { - ignmsg << "Serving world names on [" << worldsService << "]" << std::endl; + gzmsg << "Serving world names on [" << worldsService << "]" << std::endl; } else { - ignerr << "Something went wrong, failed to advertise [" << worldsService + gzerr << "Something went wrong, failed to advertise [" << worldsService << "]" << std::endl; } @@ -334,12 +334,12 @@ void ServerPrivate::SetupTransport() if (this->node.Advertise(addPathService, &ServerPrivate::AddResourcePathsService, this)) { - ignmsg << "Resource path add service on [" << addPathService << "]." + gzmsg << "Resource path add service on [" << addPathService << "]." << std::endl; } else { - ignerr << "Something went wrong, failed to advertise [" << addPathService + gzerr << "Something went wrong, failed to advertise [" << addPathService << "]" << std::endl; } @@ -347,12 +347,12 @@ void ServerPrivate::SetupTransport() if (this->node.Advertise(getPathService, &ServerPrivate::ResourcePathsService, this)) { - ignmsg << "Resource path get service on [" << getPathService << "]." + gzmsg << "Resource path get service on [" << getPathService << "]." << std::endl; } else { - ignerr << "Something went wrong, failed to advertise [" << getPathService + gzerr << "Something went wrong, failed to advertise [" << getPathService << "]" << std::endl; } @@ -361,12 +361,12 @@ void ServerPrivate::SetupTransport() if (this->pathPub) { - ignmsg << "Resource paths published on [" << pathTopic << "]." + gzmsg << "Resource paths published on [" << pathTopic << "]." << std::endl; } else { - ignerr << "Something went wrong, failed to advertise [" << pathTopic + gzerr << "Something went wrong, failed to advertise [" << pathTopic << "]" << std::endl; } @@ -374,18 +374,18 @@ void ServerPrivate::SetupTransport() if (this->node.Advertise(serverControlService, &ServerPrivate::ServerControlService, this)) { - ignmsg << "Server control service on [" << serverControlService << "]." + gzmsg << "Server control service on [" << serverControlService << "]." << std::endl; } else { - ignerr << "Something went wrong, failed to advertise [" + gzerr << "Something went wrong, failed to advertise [" << serverControlService << "]" << std::endl; } } ////////////////////////////////////////////////// -bool ServerPrivate::WorldsService(ignition::msgs::StringMsg_V &_res) +bool ServerPrivate::WorldsService(gz::msgs::StringMsg_V &_res) { std::lock_guard lock(this->worldsMutex); @@ -401,7 +401,7 @@ bool ServerPrivate::WorldsService(ignition::msgs::StringMsg_V &_res) ////////////////////////////////////////////////// bool ServerPrivate::ServerControlService( - const ignition::msgs::ServerControl &_req, msgs::Boolean &_res) + const gz::msgs::ServerControl &_req, msgs::Boolean &_res) { _res.set_data(false); @@ -410,7 +410,7 @@ bool ServerPrivate::ServerControlService( if (!this->stopThread) { this->stopThread = std::make_shared([this]{ - ignlog << "Stopping Gazebo" << std::endl; + gzlog << "Stopping Gazebo" << std::endl; std::this_thread::sleep_for(std::chrono::milliseconds(1)); this->Stop(); }); @@ -421,21 +421,21 @@ bool ServerPrivate::ServerControlService( // TODO(chapulina): implement world cloning if (_req.clone() || _req.new_port() != 0 || !_req.save_world_name().empty()) { - ignerr << "ServerControl::clone is not implemented" << std::endl; + gzerr << "ServerControl::clone is not implemented" << std::endl; _res.set_data(false); } // TODO(chapulina): implement adding a new world if (_req.new_world()) { - ignerr << "ServerControl::new_world is not implemented" << std::endl; + gzerr << "ServerControl::new_world is not implemented" << std::endl; _res.set_data(false); } // TODO(chapulina): implement loading a world if (!_req.open_filename().empty()) { - ignerr << "ServerControl::open_filename is not implemented" << std::endl; + gzerr << "ServerControl::open_filename is not implemented" << std::endl; _res.set_data(false); } @@ -444,7 +444,7 @@ bool ServerPrivate::ServerControlService( ////////////////////////////////////////////////// void ServerPrivate::AddResourcePathsService( - const ignition::msgs::StringMsg_V &_req) + const gz::msgs::StringMsg_V &_req) { std::vector paths; for (int i = 0; i < _req.data_size(); ++i) @@ -467,7 +467,7 @@ void ServerPrivate::AddResourcePathsService( ////////////////////////////////////////////////// bool ServerPrivate::ResourcePathsService( - ignition::msgs::StringMsg_V &_res) + gz::msgs::StringMsg_V &_res) { _res.Clear(); diff --git a/src/ServerPrivate.hh b/src/ServerPrivate.hh index 8eb360dec7..08e83cdb17 100644 --- a/src/ServerPrivate.hh +++ b/src/ServerPrivate.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SERVERPRIVATE_HH_ -#define IGNITION_GAZEBO_SERVERPRIVATE_HH_ +#ifndef GZ_SIM_SERVERPRIVATE_HH_ +#define GZ_SIM_SERVERPRIVATE_HH_ #include @@ -49,16 +49,16 @@ using namespace std::chrono_literals; -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { class SimulationRunner; // Private data for Server - class IGNITION_GAZEBO_HIDDEN ServerPrivate + class GZ_GAZEBO_HIDDEN ServerPrivate { /// \brief Constructor public: ServerPrivate(); @@ -105,24 +105,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}; @@ -144,7 +144,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; @@ -157,7 +157,7 @@ namespace ignition /// \brief The server configuration. public: ServerConfig config; - /// \brief Client used to download resources from Ignition Fuel. + /// \brief Client used to download resources from Gazebo Fuel. public: std::unique_ptr fuelClient = nullptr; /// \brief Map from file paths to fuel URIs. This is set and updated by diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc index ec8b4cddd1..35d50c69ba 100644 --- a/src/Server_TEST.cc +++ b/src/Server_TEST.cc @@ -41,8 +41,8 @@ #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; ///////////////////////////////////////////////// @@ -51,10 +51,10 @@ class ServerFixture : public InternalFixture<::testing::TestWithParam> }; ///////////////////////////////////////////////// -// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +// See https://github.com/gazebosim/gz-sim/issues/1175 TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(DefaultServerConfig)) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; EXPECT_TRUE(serverConfig.SdfFile().empty()); EXPECT_TRUE(serverConfig.SdfString().empty()); EXPECT_FALSE(serverConfig.UpdateRate()); @@ -74,7 +74,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(DefaultServerConfig)) EXPECT_TRUE(serverConfig.Plugins().empty()); EXPECT_TRUE(serverConfig.LogRecordTopics().empty()); - gazebo::Server server(serverConfig); + sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_EQ(std::nullopt, server.Running(1)); @@ -90,7 +90,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(DefaultServerConfig)) ///////////////////////////////////////////////// TEST_P(ServerFixture, UpdateRate) { - gazebo::ServerConfig serverConfig; + sim::ServerConfig serverConfig; serverConfig.SetUpdateRate(1000.0); EXPECT_DOUBLE_EQ(1000.0, *serverConfig.UpdateRate()); serverConfig.SetUpdateRate(-1000.0); @@ -110,7 +110,7 @@ TEST_P(ServerFixture, ServerConfigPluginInfo) pluginInfo.SetName("interface"); pluginInfo.SetSdf(nullptr); - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.AddPlugin(pluginInfo); const std::list &plugins = serverConfig.Plugins(); @@ -171,7 +171,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(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); @@ -180,9 +180,9 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(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); + sim::Server server(serverConfig); // The simulation runner should not be running. EXPECT_FALSE(*server.Running(0)); @@ -201,7 +201,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ServerConfigRealPlugin)) int maxSleep{30}; while (!executed && sleep < maxSleep) { - igndbg << "Requesting /test/service" << std::endl; + gzdbg << "Requesting /test/service" << std::endl; executed = node.Request("/test/service", 100, rep, result); sleep++; } @@ -222,29 +222,29 @@ TEST_P(ServerFixture, 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); + gzdbg << "Create server" << std::endl; + sim::Server server(serverConfig); // The simulation runner should not be running. EXPECT_FALSE(*server.Running(0)); EXPECT_EQ(3u, *server.SystemCount()); // Run the server - igndbg << "Run server" << std::endl; + gzdbg << "Run server" << std::endl; EXPECT_TRUE(server.Run(false, 0, false)); EXPECT_FALSE(*server.Paused()); // The TestSensorSystem should have created a service. Call the service to // make sure the TestSensorSystem was successfully loaded. - igndbg << "Request service" << std::endl; + gzdbg << "Request service" << std::endl; transport::Node node; msgs::StringMsg rep; bool result{false}; @@ -253,7 +253,7 @@ TEST_P(ServerFixture, int maxSleep{30}; while (!executed && sleep < maxSleep) { - igndbg << "Requesting /test/service/sensor" << std::endl; + gzdbg << "Requesting /test/service/sensor" << std::endl; executed = node.Request("/test/service/sensor", 100, rep, result); sleep++; } @@ -265,7 +265,7 @@ TEST_P(ServerFixture, ///////////////////////////////////////////////// TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(SdfServerConfig)) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetSdfString(TestWorldSansPhysics::World()); EXPECT_TRUE(serverConfig.SdfFile().empty()); @@ -277,7 +277,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(SdfServerConfig)) EXPECT_FALSE(serverConfig.SdfFile().empty()); EXPECT_TRUE(serverConfig.SdfString().empty()); - gazebo::Server server(serverConfig); + sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_TRUE(*server.Paused()); @@ -298,7 +298,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()); @@ -320,7 +320,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); + sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_TRUE(*server.Paused()); @@ -346,7 +346,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ServerConfigLogRecord)) auto logFile = common::joinPaths(logPath, "state.tlog"); auto compressedFile = logPath + ".zip"; - igndbg << "Log path [" << logPath << "]" << std::endl; + gzdbg << "Log path [" << logPath << "]" << std::endl; common::removeAll(logPath); common::removeAll(compressedFile); @@ -354,11 +354,11 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ServerConfigLogRecord)) EXPECT_FALSE(common::exists(compressedFile)); { - gazebo::ServerConfig serverConfig; + sim::ServerConfig serverConfig; serverConfig.SetUseLogRecord(true); serverConfig.SetLogRecordPath(logPath); - gazebo::Server server(serverConfig); + sim::Server server(serverConfig); EXPECT_EQ(0u, *server.IterationCount()); EXPECT_EQ(3u, *server.EntityCount()); @@ -386,7 +386,7 @@ TEST_P(ServerFixture, auto logFile = common::joinPaths(logPath, "state.tlog"); auto compressedFile = logPath + ".zip"; - igndbg << "Log path [" << logPath << "]" << std::endl; + gzdbg << "Log path [" << logPath << "]" << std::endl; common::removeAll(logPath); common::removeAll(compressedFile); @@ -394,12 +394,12 @@ TEST_P(ServerFixture, EXPECT_FALSE(common::exists(compressedFile)); { - gazebo::ServerConfig serverConfig; + sim::ServerConfig serverConfig; serverConfig.SetUseLogRecord(true); serverConfig.SetLogRecordPath(logPath); serverConfig.SetLogRecordCompressPath(compressedFile); - gazebo::Server server(serverConfig); + sim::Server server(serverConfig); EXPECT_EQ(0u, *server.IterationCount()); EXPECT_EQ(3u, *server.EntityCount()); EXPECT_EQ(4u, *server.SystemCount()); @@ -412,7 +412,7 @@ TEST_P(ServerFixture, ///////////////////////////////////////////////// TEST_P(ServerFixture, SdfStringServerConfig) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); @@ -424,7 +424,7 @@ TEST_P(ServerFixture, SdfStringServerConfig) EXPECT_TRUE(serverConfig.SdfFile().empty()); EXPECT_FALSE(serverConfig.SdfString().empty()); - gazebo::Server server(serverConfig); + sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_TRUE(*server.Paused()); @@ -436,7 +436,7 @@ TEST_P(ServerFixture, SdfStringServerConfig) ///////////////////////////////////////////////// TEST_P(ServerFixture, RunBlocking) { - gazebo::Server server; + sim::Server server; EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_TRUE(*server.Paused()); @@ -462,7 +462,7 @@ TEST_P(ServerFixture, RunBlocking) ///////////////////////////////////////////////// TEST_P(ServerFixture, RunNonBlockingPaused) { - gazebo::Server server; + sim::Server server; // The server should not be running. EXPECT_FALSE(server.Running()); @@ -512,7 +512,7 @@ TEST_P(ServerFixture, RunNonBlockingPaused) ///////////////////////////////////////////////// TEST_P(ServerFixture, RunNonBlocking) { - gazebo::Server server; + sim::Server server; EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_EQ(0u, *server.IterationCount()); @@ -532,15 +532,15 @@ TEST_P(ServerFixture, RunNonBlocking) ///////////////////////////////////////////////// TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(RunOnceUnpaused)) { - gazebo::Server server; + sim::Server server; EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_EQ(0u, *server.IterationCount()); // Load a system - gazebo::SystemLoader systemLoader; + 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 @@ -549,9 +549,9 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(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 @@ -579,15 +579,15 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(RunOnceUnpaused)) ///////////////////////////////////////////////// TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(RunOncePaused)) { - gazebo::Server server; + sim::Server server; EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); EXPECT_EQ(0u, *server.IterationCount()); // Load a system - gazebo::SystemLoader systemLoader; + 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 @@ -596,9 +596,9 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(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 @@ -626,9 +626,9 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(RunOncePaused)) ///////////////////////////////////////////////// TEST_P(ServerFixture, RunNonBlockingMultiple) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetSdfString(TestWorldSansPhysics::World()); - gazebo::Server server(serverConfig); + sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); @@ -648,7 +648,7 @@ TEST_P(ServerFixture, RunNonBlockingMultiple) ///////////////////////////////////////////////// TEST_P(ServerFixture, SigInt) { - gazebo::Server server; + sim::Server server; EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); @@ -672,7 +672,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; + sim::Server server; EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); @@ -695,7 +695,7 @@ TEST_P(ServerFixture, ServerControlStop) // first, call with stop = false; the server should keep running while (!executed && sleep < maxSleep) { - igndbg << "Requesting /server_control" << std::endl; + gzdbg << "Requesting /server_control" << std::endl; executed = node.Request("/server_control", req, 100, res, result); sleep++; } @@ -711,7 +711,7 @@ TEST_P(ServerFixture, ServerControlStop) // now call with stop = true; the server should stop req.set_stop(true); - igndbg << "Requesting /server_control" << std::endl; + gzdbg << "Requesting /server_control" << std::endl; executed = node.Request("/server_control", req, 100, res, result); EXPECT_TRUE(executed); @@ -727,12 +727,12 @@ TEST_P(ServerFixture, ServerControlStop) ///////////////////////////////////////////////// TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(AddSystemWhileRunning)) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); - gazebo::Server server(serverConfig); + sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); server.SetUpdatePeriod(1us); @@ -748,9 +748,9 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(AddSystemWhileRunning)) EXPECT_EQ(3u, *server.SystemCount()); // Add system from plugin - gazebo::SystemLoader systemLoader; + 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()); @@ -775,24 +775,24 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(AddSystemWhileRunning)) ///////////////////////////////////////////////// TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(AddSystemAfterLoad)) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); - gazebo::Server server(serverConfig); + sim::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); // Add system from plugin - gazebo::SystemLoader systemLoader; + 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()); @@ -838,30 +838,30 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(AddSystemAfterLoad)) ///////////////////////////////////////////////// TEST_P(ServerFixture, Seed) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; EXPECT_EQ(0u, serverConfig.Seed()); unsigned int mySeed = 12345u; serverConfig.SetSeed(mySeed); EXPECT_EQ(mySeed, serverConfig.Seed()); - EXPECT_EQ(mySeed, ignition::math::Rand::Seed()); + EXPECT_EQ(mySeed, gz::math::Rand::Seed()); } ///////////////////////////////////////////////// TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ResourcePath)) { - ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", + gz::common::setenv("IGN_GAZEBO_RESOURCE_PATH", (std::string(PROJECT_SOURCE_PATH) + "/test/worlds:" + std::string(PROJECT_SOURCE_PATH) + "/test/worlds/models").c_str()); ServerConfig serverConfig; serverConfig.SetSdfFile("resource_paths.sdf"); - gazebo::Server server(serverConfig); + sim::Server server(serverConfig); test::Relay testSystem; unsigned int preUpdates{0}; testSystem.OnPreUpdate( - [&preUpdates](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + [&preUpdates](const sim::UpdateInfo &, + sim::EntityComponentManager &_ecm) { // Create AABB so it is populated unsigned int eachCount{0}; @@ -879,8 +879,8 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ResourcePath)) }); unsigned int postUpdates{0}; - testSystem.OnPostUpdate([&postUpdates](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&postUpdates](const sim::UpdateInfo &, + const sim::EntityComponentManager &_ecm) { // Check geometry components unsigned int eachCount{0}; @@ -908,7 +908,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ResourcePath)) // Check physics system loaded meshes and got their BB correct eachCount = 0; _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const gz::sim::Entity &, const components::AxisAlignedBox *_box)->bool { auto box = _box->Data(); @@ -937,11 +937,11 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ResourcePath)) ///////////////////////////////////////////////// TEST_P(ServerFixture, GetResourcePaths) { - ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", + gz::common::setenv("IGN_GAZEBO_RESOURCE_PATH", "/tmp/some/path:/home/user/another_path"); ServerConfig serverConfig; - gazebo::Server server(serverConfig); + sim::Server server(serverConfig); EXPECT_FALSE(*server.Running(0)); @@ -953,7 +953,7 @@ TEST_P(ServerFixture, GetResourcePaths) int maxSleep{30}; while (!executed && sleep < maxSleep) { - igndbg << "Requesting /gazebo/resource_paths/get" << std::endl; + gzdbg << "Requesting /gazebo/resource_paths/get" << std::endl; executed = node.Request("/gazebo/resource_paths/get", 100, res, result); sleep++; } @@ -967,13 +967,13 @@ TEST_P(ServerFixture, GetResourcePaths) ///////////////////////////////////////////////// TEST_P(ServerFixture, AddResourcePaths) { - ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", + gz::common::setenv("IGN_GAZEBO_RESOURCE_PATH", "/tmp/some/path:/home/user/another_path"); - ignition::common::setenv("SDF_PATH", ""); - ignition::common::setenv("IGN_FILE_PATH", ""); + gz::common::setenv("SDF_PATH", ""); + gz::common::setenv("IGN_FILE_PATH", ""); ServerConfig serverConfig; - gazebo::Server server(serverConfig); + sim::Server server(serverConfig); EXPECT_FALSE(*server.Running(0)); diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc index b404f225f0..b6e9054aaf 100644 --- a/src/SimulationRunner.cc +++ b/src/SimulationRunner.cc @@ -38,8 +38,8 @@ #include "network/NetworkManagerPrimary.hh" #include "SdfGenerator.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using StringSet = std::unordered_set; @@ -54,7 +54,7 @@ SimulationRunner::SimulationRunner(const sdf::World *_world, { if (nullptr == _world) { - ignerr << "Can't start simulation runner with null world." << std::endl; + gzerr << "Can't start simulation runner with null world." << std::endl; return; } @@ -154,13 +154,13 @@ SimulationRunner::SimulationRunner(const sdf::World *_world, { if (this->networkMgr->IsPrimary()) { - ignmsg << "Network Primary, expects [" + gzmsg << "Network Primary, expects [" << this->networkMgr->Config().numSecondariesExpected << "] secondaries." << std::endl; } else if (this->networkMgr->IsSecondary()) { - ignmsg << "Network Secondary, with namespace [" + gzmsg << "Network Secondary, with namespace [" << this->networkMgr->Namespace() << "]." << std::endl; } } @@ -180,9 +180,9 @@ SimulationRunner::SimulationRunner(const sdf::World *_world, if (this->systemMgr->TotalByEntity( worldEntity(this->entityCompMgr)).empty()) { - ignmsg << "No systems loaded from SDF, loading defaults" << std::endl; + gzmsg << "No systems loaded from SDF, loading defaults" << std::endl; bool isPlayback = !this->serverConfig.LogPlaybackPath().empty(); - auto plugins = ignition::gazebo::loadPluginInfo(isPlayback); + auto plugins = gz::sim::loadPluginInfo(isPlayback); this->LoadServerPlugins(plugins); } @@ -199,7 +199,7 @@ SimulationRunner::SimulationRunner(const sdf::World *_world, auto validNs = transport::TopicUtils::AsValidTopic(ns); if (validNs.empty()) { - ignerr << "Invalid namespace [" << ns + gzerr << "Invalid namespace [" << ns << "], not initializing runner transport." << std::endl; return; } @@ -214,7 +214,7 @@ SimulationRunner::SimulationRunner(const sdf::World *_world, this->node->Advertise("playback/control", &SimulationRunner::OnPlaybackControl, this); - ignmsg << "Serving world controls on [" << opts.NameSpace() + gzmsg << "Serving world controls on [" << opts.NameSpace() << "/control], [" << opts.NameSpace() << "/control/state] and [" << opts.NameSpace() << "/playback/control]" << std::endl; @@ -228,17 +228,17 @@ SimulationRunner::SimulationRunner(const sdf::World *_world, std::string infoService{"gui/info"}; this->node->Advertise(infoService, &SimulationRunner::GuiInfoService, this); - ignmsg << "Serving GUI information on [" << opts.NameSpace() << "/" + gzmsg << "Serving GUI information on [" << opts.NameSpace() << "/" << infoService << "]" << std::endl; - ignmsg << "World [" << _world->Name() << "] initialized with [" + gzmsg << "World [" << _world->Name() << "] initialized with [" << physics->Name() << "] physics profile." << std::endl; std::string genWorldSdfService{"generate_world_sdf"}; this->node->Advertise( genWorldSdfService, &SimulationRunner::GenerateWorldSdf, this); - ignmsg << "Serving world SDF generation service on [" << opts.NameSpace() + gzmsg << "Serving world SDF generation service on [" << opts.NameSpace() << "/" << genWorldSdfService << "]" << std::endl; } @@ -256,7 +256,7 @@ void SimulationRunner::UpdateCurrentInfo() // Rewind if (this->requestedRewind) { - igndbg << "Rewinding simulation back to time zero." << std::endl; + gzdbg << "Rewinding simulation back to time zero." << std::endl; this->realTimes.clear(); this->simTimes.clear(); this->realTimeFactor = 0; @@ -277,7 +277,7 @@ void SimulationRunner::UpdateCurrentInfo() // Seek if (this->requestedSeek >= std::chrono::steady_clock::duration::zero()) { - igndbg << "Seeking to " << std::chrono::duration_cast( + gzdbg << "Seeking to " << std::chrono::duration_cast( this->requestedSeek).count() << "s." << std::endl; this->realTimes.clear(); @@ -407,14 +407,14 @@ void SimulationRunner::PublishStats() IGN_PROFILE("SimulationRunner::PublishStats"); // Create the world statistics message. - ignition::msgs::WorldStatistics msg; + gz::msgs::WorldStatistics msg; msg.set_real_time_factor(this->realTimeFactor); auto realTimeSecNsec = - ignition::math::durationToSecNsec(this->currentInfo.realTime); + gz::math::durationToSecNsec(this->currentInfo.realTime); auto simTimeSecNsec = - ignition::math::durationToSecNsec(this->currentInfo.simTime); + gz::math::durationToSecNsec(this->currentInfo.simTime); msg.mutable_real_time()->set_sec(realTimeSecNsec.first); msg.mutable_real_time()->set_nsec(realTimeSecNsec.second); @@ -440,7 +440,7 @@ void SimulationRunner::PublishStats() // Create and publish the clock message. The clock message is not // throttled. - ignition::msgs::Clock clockMsg; + gz::msgs::Clock clockMsg; clockMsg.mutable_real()->set_sec(realTimeSecNsec.first); clockMsg.mutable_real()->set_nsec(realTimeSecNsec.second); clockMsg.mutable_sim()->set_sec(simTimeSecNsec.first); @@ -491,7 +491,7 @@ void SimulationRunner::ProcessSystemQueue() auto threadCount = this->systemMgr->SystemsPostUpdate().size() + 1u; - igndbg << "Creating PostUpdate worker threads: " + gzdbg << "Creating PostUpdate worker threads: " << threadCount << std::endl; this->postUpdateStartBarrier = std::make_unique(threadCount); @@ -502,7 +502,7 @@ void SimulationRunner::ProcessSystemQueue() for (auto &system : this->systemMgr->SystemsPostUpdate()) { - igndbg << "Creating postupdate worker thread (" << id << ")" << std::endl; + gzdbg << "Creating postupdate worker thread (" << id << ")" << std::endl; this->postUpdateThreads.push_back(std::thread([&, id]() { @@ -518,7 +518,7 @@ void SimulationRunner::ProcessSystemQueue() } this->postUpdateStopBarrier->Wait(); } - igndbg << "Exiting postupdate worker thread (" + gzdbg << "Exiting postupdate worker thread (" << id << ")" << std::endl; })); id++; @@ -530,7 +530,7 @@ void SimulationRunner::UpdateSystems() { IGN_PROFILE("SimulationRunner::UpdateSystems"); // \todo(nkoenig) Systems used to be updated in parallel using - // an ignition::common::WorkerPool. There is overhead associated with + // an gz::common::WorkerPool. There is overhead associated with // this, most notably the creation and destruction of WorkOrders (see // WorkerPool.cc). We could turn on parallel updates in the future, and/or // turn it on if there are sufficient systems. More testing is required. @@ -614,19 +614,19 @@ bool SimulationRunner::Run(const uint64_t _iterations) // Initialize network communications. if (this->networkMgr) { - igndbg << "Initializing network configuration" << std::endl; + gzdbg << "Initializing network configuration" << std::endl; this->networkMgr->Handshake(); // Secondaries are stepped through the primary, just keep alive until // simulation is over if (this->networkMgr->IsSecondary()) { - igndbg << "Secondary running." << std::endl; + gzdbg << "Secondary running." << std::endl; while (!this->stopReceived) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); } - igndbg << "Secondary finished run." << std::endl; + gzdbg << "Secondary finished run." << std::endl; return true; } } @@ -650,35 +650,35 @@ bool SimulationRunner::Run(const uint64_t _iterations) // because the GUI listens to these msgs to receive confirmation that // pause/play GUI requests have been processed by the server, so we want to // make sure that GUI requests are acknowledged quickly (see - // https://github.com/ignitionrobotics/ign-gui/pull/306 and - // https://github.com/ignitionrobotics/ign-gazebo/pull/1163) + // https://github.com/gazebosim/gz-gui/pull/306 and + // https://github.com/gazebosim/gz-sim/pull/1163) advertOpts.SetMsgsPerSec(10); - this->statsPub = this->node->Advertise( + this->statsPub = this->node->Advertise( "stats", advertOpts); } if (!this->rootStatsPub.Valid()) { // Check for the existence of other publishers on `/stats` - std::vector publishers; + std::vector publishers; this->node->TopicInfo("/stats", publishers); if (!publishers.empty()) { - ignwarn << "Found additional publishers on /stats," << + gzwarn << "Found additional publishers on /stats," << " using namespaced stats topic only" << std::endl; - igndbg << "Publishers [Address, Message Type]:\n"; + gzdbg << "Publishers [Address, Message Type]:\n"; /// List the publishers for (auto & pub : publishers) { - igndbg << " " << pub.Addr() << ", " + gzdbg << " " << pub.Addr() << ", " << pub.MsgTypeName() << std::endl; } } else { - ignmsg << "Found no publishers on /stats, adding root stats topic" + gzmsg << "Found no publishers on /stats, adding root stats topic" << std::endl; this->rootStatsPub = this->node->Advertise( "/stats"); @@ -687,33 +687,33 @@ bool SimulationRunner::Run(const uint64_t _iterations) // Create the clock publisher. if (!this->clockPub.Valid()) - this->clockPub = this->node->Advertise("clock"); + this->clockPub = this->node->Advertise("clock"); // Create the global clock publisher. if (!this->rootClockPub.Valid()) { // Check for the existence of other publishers on `/clock` - std::vector publishers; + std::vector publishers; this->node->TopicInfo("/clock", publishers); if (!publishers.empty()) { - ignwarn << "Found additional publishers on /clock," << + gzwarn << "Found additional publishers on /clock," << " using namespaced clock topic only" << std::endl; - igndbg << "Publishers [Address, Message Type]:\n"; + gzdbg << "Publishers [Address, Message Type]:\n"; /// List the publishers for (auto & pub : publishers) { - igndbg << " " << pub.Addr() << ", " + gzdbg << " " << pub.Addr() << ", " << pub.MsgTypeName() << std::endl; } } else { - ignmsg << "Found no publishers on /clock, adding root clock topic" + gzmsg << "Found no publishers on /clock, adding root clock topic" << std::endl; - this->rootClockPub = this->node->Advertise( + this->rootClockPub = this->node->Advertise( "/clock"); } } @@ -951,7 +951,7 @@ void SimulationRunner::LoadServerPlugins( } else { - ignwarn << "No support for attaching plugins to entity of type [" + gzwarn << "No support for attaching plugins to entity of type [" << plugin.EntityType() << "]" << std::endl; } @@ -970,7 +970,7 @@ void SimulationRunner::LoadLoggingPlugins(const ServerConfig &_config) if (_config.UseLogRecord() && !_config.LogPlaybackPath().empty()) { - ignwarn << + gzwarn << "Both recording and playback are specified, defaulting to playback\n"; } @@ -1145,13 +1145,13 @@ bool SimulationRunner::OnWorldControlState(const msgs::WorldControlState &_req, if (_req.world_control().reset().model_only()) { - ignwarn << "Model only reset is not supported." << std::endl; + gzwarn << "Model only reset is not supported." << std::endl; } } if (_req.world_control().seed() != 0) { - ignwarn << "Changing seed is not supported." << std::endl; + gzwarn << "Changing seed is not supported." << std::endl; } if (_req.world_control().has_run_to_sim_time()) @@ -1201,7 +1201,7 @@ bool SimulationRunner::OnPlaybackControl(const msgs::LogPlaybackControl &_req, if (_req.forward()) { - ignwarn << "Log forwarding is not supported, use seek." << std::endl; + gzwarn << "Log forwarding is not supported, use seek." << std::endl; } this->worldControls.push_back(control); @@ -1294,26 +1294,26 @@ void SimulationRunner::ProcessRecreateEntitiesCreate() // next iteration if (!this->entityCompMgr.RemoveComponent(ent)) { - ignerr << "Failed to remove Recreate component from entity[" + gzerr << "Failed to remove Recreate component from entity[" << ent << "]" << std::endl; } if (!this->entityCompMgr.RemoveComponent( clonedEntity)) { - ignerr << "Failed to remove Recreate component from entity[" + gzerr << "Failed to remove Recreate component from entity[" << clonedEntity << "]" << std::endl; } } else if (!nameComp) { - ignerr << "Missing name component for entity[" << ent << "]. " + gzerr << "Missing name component for entity[" << ent << "]. " << "The entity will not be cloned during the recreation process." << std::endl; } else if (!parentComp) { - ignerr << "Missing parent component for entity[" << ent << "]. " + gzerr << "Missing parent component for entity[" << ent << "]. " << "The entity will not be cloned during the recreation process." << std::endl; } @@ -1354,13 +1354,13 @@ SimulationRunner::UpdatePeriod() const } ///////////////////////////////////////////////// -const ignition::math::clock::duration &SimulationRunner::StepSize() const +const gz::math::clock::duration &SimulationRunner::StepSize() const { return this->stepSize; } ///////////////////////////////////////////////// -void SimulationRunner::SetStepSize(const ignition::math::clock::duration &_step) +void SimulationRunner::SetStepSize(const gz::math::clock::duration &_step) { this->stepSize = _step; } @@ -1436,7 +1436,7 @@ bool SimulationRunner::RequestRemoveEntity(const Entity _entity, } ////////////////////////////////////////////////// -bool SimulationRunner::GuiInfoService(ignition::msgs::GUI &_res) +bool SimulationRunner::GuiInfoService(gz::msgs::GUI &_res) { _res.Clear(); diff --git a/src/SimulationRunner.hh b/src/SimulationRunner.hh index 17127f00c1..0f060beac2 100644 --- a/src/SimulationRunner.hh +++ b/src/SimulationRunner.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SIMULATIONRUNNER_HH_ -#define IGNITION_GAZEBO_SIMULATIONRUNNER_HH_ +#ifndef GZ_SIM_SIMULATIONRUNNER_HH_ +#define GZ_SIM_SIMULATIONRUNNER_HH_ #include #include @@ -59,16 +59,16 @@ using namespace std::chrono_literals; -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { // Forward declarations. class SimulationRunnerPrivate; - class IGNITION_GAZEBO_VISIBLE SimulationRunner + class GZ_GAZEBO_VISIBLE SimulationRunner { /// \brief Constructor /// \param[in] _world Pointer to the SDF world. @@ -280,11 +280,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 @@ -319,7 +319,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(); @@ -438,34 +438,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 4a09c4e74c..a2a9597151 100644 --- a/src/SimulationRunner_TEST.cc +++ b/src/SimulationRunner_TEST.cc @@ -61,15 +61,15 @@ #include "../test/helpers/EnvTestFixture.hh" #include "SimulationRunner.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace components; -namespace ignition +namespace gz { -namespace gazebo +namespace sim { -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace components { using IntComponent = components::Component; @@ -207,35 +207,35 @@ TEST_P(SimulationRunnerTest, CreateEntities) EXPECT_EQ(worldEntity, _parent->Data()); if (modelCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(1, 2, 3, 0, 0, 1), + EXPECT_EQ(gz::math::Pose3d(1, 2, 3, 0, 0, 1), _pose->Data()); EXPECT_EQ("box", _name->Data()); boxModelEntity = _entity; } else if (modelCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(-1, -2, -3, 0, 0, 1), + EXPECT_EQ(gz::math::Pose3d(-1, -2, -3, 0, 0, 1), _pose->Data()); EXPECT_EQ("cylinder", _name->Data()); cylModelEntity = _entity; } else if (modelCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0, 0, 0, 0, 0, 1), + EXPECT_EQ(gz::math::Pose3d(0, 0, 0, 0, 0, 1), _pose->Data()); EXPECT_EQ("sphere", _name->Data()); sphModelEntity = _entity; } else if (modelCount == 4) { - EXPECT_EQ(ignition::math::Pose3d(-4, -5, -6, 0, 0, 1), + EXPECT_EQ(gz::math::Pose3d(-4, -5, -6, 0, 0, 1), _pose->Data()); EXPECT_EQ("capsule", _name->Data()); capModelEntity = _entity; } else if (modelCount == 5) { - EXPECT_EQ(ignition::math::Pose3d(4, 5, 6, 0, 0, 1), + EXPECT_EQ(gz::math::Pose3d(4, 5, 6, 0, 0, 1), _pose->Data()); EXPECT_EQ("ellipsoid", _name->Data()); ellipModelEntity = _entity; @@ -276,7 +276,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) if (linkCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.1, 0.1, 0.1, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.1, 0.1, 0.1, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_link", _name->Data()); EXPECT_EQ(boxModelEntity, _parent->Data()); @@ -284,7 +284,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (linkCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.2, 0.2, 0.2, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.2, 0.2, 0.2, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_link", _name->Data()); EXPECT_EQ(cylModelEntity, _parent->Data()); @@ -292,7 +292,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (linkCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.3, 0.3, 0.3, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.3, 0.3, 0.3, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_link", _name->Data()); EXPECT_EQ(sphModelEntity, _parent->Data()); @@ -300,7 +300,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (linkCount == 4) { - EXPECT_EQ(ignition::math::Pose3d(0.5, 0.5, 0.5, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.5, 0.5, 0.5, 0, 0, 0), _pose->Data()); EXPECT_EQ("capsule_link", _name->Data()); EXPECT_EQ(capModelEntity, _parent->Data()); @@ -308,7 +308,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (linkCount == 5) { - EXPECT_EQ(ignition::math::Pose3d(0.8, 0.8, 0.8, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.8, 0.8, 0.8, 0, 0, 0), _pose->Data()); EXPECT_EQ("ellipsoid_link", _name->Data()); EXPECT_EQ(ellipModelEntity, _parent->Data()); @@ -395,7 +395,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) if (collisionCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.11, 0.11, 0.11, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.11, 0.11, 0.11, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_collision", _name->Data()); @@ -409,7 +409,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (collisionCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.21, 0.21, 0.21, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.21, 0.21, 0.21, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_collision", _name->Data()); @@ -423,7 +423,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (collisionCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.31, 0.31, 0.31, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.31, 0.31, 0.31, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_collision", _name->Data()); @@ -436,7 +436,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (collisionCount == 4) { - EXPECT_EQ(ignition::math::Pose3d(0.51, 0.51, 0.51, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.51, 0.51, 0.51, 0, 0, 0), _pose->Data()); EXPECT_EQ("capsule_collision", _name->Data()); @@ -450,7 +450,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (collisionCount == 5) { - EXPECT_EQ(ignition::math::Pose3d(0.81, 0.81, 0.81, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.81, 0.81, 0.81, 0, 0, 0), _pose->Data()); EXPECT_EQ("ellipsoid_collision", _name->Data()); @@ -459,7 +459,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) EXPECT_EQ(sdf::GeometryType::ELLIPSOID, _geometry->Data().Type()); EXPECT_NE(nullptr, _geometry->Data().EllipsoidShape()); - EXPECT_EQ(ignition::math::Vector3d(0.4, 0.6, 1.6), + EXPECT_EQ(gz::math::Vector3d(0.4, 0.6, 1.6), _geometry->Data().EllipsoidShape()->Radii()); } return true; @@ -494,7 +494,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) if (visualCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.12, 0.12, 0.12, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.12, 0.12, 0.12, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_visual", _name->Data()); @@ -513,7 +513,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (visualCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.22, 0.22, 0.22, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.22, 0.22, 0.22, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_visual", _name->Data()); @@ -532,7 +532,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (visualCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.32, 0.32, 0.32, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.32, 0.32, 0.32, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_visual", _name->Data()); @@ -550,7 +550,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (visualCount == 4) { - EXPECT_EQ(ignition::math::Pose3d(0.52, 0.52, 0.52, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.52, 0.52, 0.52, 0, 0, 0), _pose->Data()); EXPECT_EQ("capsule_visual", _name->Data()); @@ -569,7 +569,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (visualCount == 5) { - EXPECT_EQ(ignition::math::Pose3d(0.82, 0.82, 0.82, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.82, 0.82, 0.82, 0, 0, 0), _pose->Data()); EXPECT_EQ("ellipsoid_visual", _name->Data()); @@ -578,7 +578,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) EXPECT_EQ(sdf::GeometryType::ELLIPSOID, _geometry->Data().Type()); EXPECT_NE(nullptr, _geometry->Data().EllipsoidShape()); - EXPECT_EQ(ignition::math::Vector3d(0.4, 0.6, 1.6), + EXPECT_EQ(gz::math::Vector3d(0.4, 0.6, 1.6), _geometry->Data().EllipsoidShape()->Radii()); EXPECT_EQ(math::Color(0.0f, 0.0f, 0.0f), _material->Data().Emissive()); @@ -610,7 +610,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) lightCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 10, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.0, 0.0, 10, 0, 0, 0), _pose->Data()); EXPECT_EQ("sun", _name->Data()); @@ -619,20 +619,20 @@ TEST_P(SimulationRunnerTest, CreateEntities) EXPECT_EQ("sun", _light->Data().Name()); EXPECT_EQ(sdf::LightType::DIRECTIONAL, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 10, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0, 0, 10, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ("", _light->Data().PoseRelativeTo()); EXPECT_TRUE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.8f, 0.8f, 0.8f, 1), + EXPECT_EQ(gz::math::Color(0.8f, 0.8f, 0.8f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(gz::math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(1000, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.9, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.01, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); EXPECT_DOUBLE_EQ(1.0, _light->Data().Intensity()); - EXPECT_EQ(ignition::math::Vector3d(-0.5, 0.1, -0.9), + EXPECT_EQ(gz::math::Vector3d(-0.5, 0.1, -0.9), _light->Data().Direction()); return true; }); @@ -703,7 +703,7 @@ TEST_P(SimulationRunnerTest, CreateLights) modelCount++; EXPECT_EQ(worldEntity, _parent->Data()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 0, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0, 0, 0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere", _name->Data()); sphModelEntity = _entity; @@ -734,7 +734,7 @@ TEST_P(SimulationRunnerTest, CreateLights) linkCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_link", _name->Data()); EXPECT_EQ(sphModelEntity, _parent->Data()); @@ -771,7 +771,7 @@ TEST_P(SimulationRunnerTest, CreateLights) visualCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_visual", _name->Data()); @@ -812,19 +812,19 @@ TEST_P(SimulationRunnerTest, CreateLights) // light attached to link if (lightCount == 1u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 1.0, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.0, 0.0, 1.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("link_light_point", _name->Data()); EXPECT_EQ(sphLinkEntity, _parent->Data()); EXPECT_EQ("link_light_point", _light->Data().Name()); EXPECT_EQ(sdf::LightType::POINT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 1, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0, 0, 1, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.0f, 0.0f, 1.0f, 1), + EXPECT_EQ(gz::math::Color(0.0f, 0.0f, 1.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.1f, 0.1f, 0.1f, 1), + EXPECT_EQ(gz::math::Color(0.1f, 0.1f, 0.1f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(2, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.05, _light->Data().ConstantAttenuationFactor()); @@ -834,43 +834,43 @@ TEST_P(SimulationRunnerTest, CreateLights) // directional light in the world else if (lightCount == 2u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 10, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.0, 0.0, 10, 0, 0, 0), _pose->Data()); EXPECT_EQ("directional", _name->Data()); EXPECT_EQ(worldEntity, _parent->Data()); EXPECT_EQ("directional", _light->Data().Name()); EXPECT_EQ(sdf::LightType::DIRECTIONAL, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 10, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0, 0, 10, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_TRUE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.8f, 0.8f, 0.8f, 1), + EXPECT_EQ(gz::math::Color(0.8f, 0.8f, 0.8f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(gz::math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(100, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.9, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.01, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); - EXPECT_EQ(ignition::math::Vector3d(0.5, 0.2, -0.9), + EXPECT_EQ(gz::math::Vector3d(0.5, 0.2, -0.9), _light->Data().Direction()); } // point light in the world else if (lightCount == 3u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, -1.5, 3, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.0, -1.5, 3, 0, 0, 0), _pose->Data()); EXPECT_EQ("point", _name->Data()); EXPECT_EQ(worldEntity, _parent->Data()); EXPECT_EQ("point", _light->Data().Name()); EXPECT_EQ(sdf::LightType::POINT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, -1.5, 3, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0, -1.5, 3, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(1.0f, 0.0f, 0.0f, 1), + EXPECT_EQ(gz::math::Color(1.0f, 0.0f, 0.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.1f, 0.1f, 0.1f, 1), + EXPECT_EQ(gz::math::Color(0.1f, 0.1f, 0.1f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(4, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.2, _light->Data().ConstantAttenuationFactor()); @@ -880,25 +880,25 @@ TEST_P(SimulationRunnerTest, CreateLights) // spot light in the world else if (lightCount == 4u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 1.5, 3, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0.0, 1.5, 3, 0, 0, 0), _pose->Data()); EXPECT_EQ("spot", _name->Data()); EXPECT_EQ(worldEntity, _parent->Data()); EXPECT_EQ("spot", _light->Data().Name()); EXPECT_EQ(sdf::LightType::SPOT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 1.5, 3, 0, 0, 0), + EXPECT_EQ(gz::math::Pose3d(0, 1.5, 3, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.0f, 1.0f, 0.0f, 1), + EXPECT_EQ(gz::math::Color(0.0f, 1.0f, 0.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(gz::math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(5, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.3, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.4, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); - EXPECT_EQ(ignition::math::Vector3d(0.0, 0.0, -1.0), + EXPECT_EQ(gz::math::Vector3d(0.0, 0.0, -1.0), _light->Data().Direction()); EXPECT_DOUBLE_EQ(0.1, _light->Data().SpotInnerAngle().Radian()); EXPECT_DOUBLE_EQ(0.5, _light->Data().SpotOuterAngle().Radian()); @@ -1184,7 +1184,7 @@ TEST_P(SimulationRunnerTest, Time) } ///////////////////////////////////////////////// -// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +// See https://github.com/gazebosim/gz-sim/issues/1175 TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) { // Load SDF file @@ -1200,9 +1200,9 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Get world entity Entity worldId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::World *_world)->bool + runner.EntityCompMgr().Each([&]( + const gz::sim::Entity &_entity, + const gz::sim::components::World *_world)->bool { EXPECT_NE(nullptr, _world); worldId = _entity; @@ -1212,9 +1212,9 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Get model entity Entity modelId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::Model *_model)->bool + runner.EntityCompMgr().Each([&]( + const gz::sim::Entity &_entity, + const gz::sim::components::Model *_model)->bool { EXPECT_NE(nullptr, _model); modelId = _entity; @@ -1224,9 +1224,9 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Get sensor entity Entity sensorId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::Sensor *_sensor)->bool + runner.EntityCompMgr().Each([&]( + const gz::sim::Entity &_entity, + const gz::sim::components::Sensor *_sensor)->bool { EXPECT_NE(nullptr, _sensor); sensorId = _entity; @@ -1236,9 +1236,9 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Get visual entity Entity visualId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::Visual *_visual)->bool + runner.EntityCompMgr().Each([&]( + const gz::sim::Entity &_entity, + const gz::sim::components::Visual *_visual)->bool { EXPECT_NE(nullptr, _visual); visualId = _entity; @@ -1248,7 +1248,7 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Check component registered by world plugin std::string worldComponentName{"WorldPluginComponent"}; - auto worldComponentId = ignition::common::hash64(worldComponentName); + auto worldComponentId = gz::common::hash64(worldComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(worldComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(worldId, @@ -1256,7 +1256,7 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Check component registered by model plugin std::string modelComponentName{"ModelPluginComponent"}; - auto modelComponentId = ignition::common::hash64(modelComponentName); + auto modelComponentId = gz::common::hash64(modelComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(modelComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(modelId, @@ -1264,7 +1264,7 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Check component registered by sensor plugin std::string sensorComponentName{"SensorPluginComponent"}; - auto sensorComponentId = ignition::common::hash64(sensorComponentName); + auto sensorComponentId = gz::common::hash64(sensorComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(sensorComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(sensorId, @@ -1272,7 +1272,7 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Check component registered by visual plugin std::string visualComponentName{"VisualPluginComponent"}; - auto visualComponentId = ignition::common::hash64(visualComponentName); + auto visualComponentId = gz::common::hash64(visualComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(visualComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(visualId, @@ -1304,7 +1304,7 @@ TEST_P(SimulationRunnerTest, // ServerConfig will fall back to environment variable auto config = common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "server_valid2.config"); - ASSERT_EQ(true, common::setenv(gazebo::kServerConfigPathEnv, config)); + ASSERT_EQ(true, common::setenv(sim::kServerConfigPathEnv, config)); ServerConfig serverConfig; // Create simulation runner @@ -1345,9 +1345,9 @@ TEST_P(SimulationRunnerTest, // Get world entity Entity worldId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::World *_world)->bool + runner.EntityCompMgr().Each([&]( + const gz::sim::Entity &_entity, + const gz::sim::components::World *_world)->bool { EXPECT_NE(nullptr, _world); worldId = _entity; @@ -1357,9 +1357,9 @@ TEST_P(SimulationRunnerTest, // Get model entity Entity modelId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::Model *_model)->bool + runner.EntityCompMgr().Each([&]( + const gz::sim::Entity &_entity, + const gz::sim::components::Model *_model)->bool { EXPECT_NE(nullptr, _model); modelId = _entity; @@ -1369,9 +1369,9 @@ TEST_P(SimulationRunnerTest, // Get sensor entity Entity sensorId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::Sensor *_sensor)->bool + runner.EntityCompMgr().Each([&]( + const gz::sim::Entity &_entity, + const gz::sim::components::Sensor *_sensor)->bool { EXPECT_NE(nullptr, _sensor); sensorId = _entity; @@ -1381,7 +1381,7 @@ TEST_P(SimulationRunnerTest, // Check component registered by world plugin std::string worldComponentName{"WorldPluginComponent"}; - auto worldComponentId = ignition::common::hash64(worldComponentName); + auto worldComponentId = gz::common::hash64(worldComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(worldComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(worldId, @@ -1389,7 +1389,7 @@ TEST_P(SimulationRunnerTest, // Check component registered by model plugin std::string modelComponentName{"ModelPluginComponent"}; - auto modelComponentId = ignition::common::hash64(modelComponentName); + auto modelComponentId = gz::common::hash64(modelComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(modelComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(modelId, @@ -1397,7 +1397,7 @@ TEST_P(SimulationRunnerTest, // Check component registered by sensor plugin std::string sensorComponentName{"SensorPluginComponent"}; - auto sensorComponentId = ignition::common::hash64(sensorComponentName); + auto sensorComponentId = gz::common::hash64(sensorComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(sensorComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(sensorId, @@ -1429,13 +1429,13 @@ TEST_P(SimulationRunnerTest, // The user may have modified their local config. auto config = common::joinPaths(PROJECT_SOURCE_PATH, "include", "gz", "sim", "server.config"); - ASSERT_TRUE(common::setenv(gazebo::kServerConfigPathEnv, config)); + ASSERT_TRUE(common::setenv(sim::kServerConfigPathEnv, config)); // Create simulation runner auto systemLoader = std::make_shared(); SimulationRunner runner(rootWithout.WorldByIndex(0), systemLoader); ASSERT_EQ(3u, runner.SystemCount()); - common::unsetenv(gazebo::kServerConfigPathEnv); + common::unsetenv(sim::kServerConfigPathEnv); } ///////////////////////////////////////////////// @@ -1455,24 +1455,24 @@ TEST_P(SimulationRunnerTest, // Get model entities auto boxEntity = runner.EntityCompMgr().EntityByComponents( - ignition::gazebo::components::Model(), - ignition::gazebo::components::Name("box")); + gz::sim::components::Model(), + gz::sim::components::Name("box")); EXPECT_NE(kNullEntity, boxEntity); auto sphereEntity = runner.EntityCompMgr().EntityByComponents( - ignition::gazebo::components::Model(), - ignition::gazebo::components::Name("sphere")); + gz::sim::components::Model(), + gz::sim::components::Name("sphere")); EXPECT_NE(kNullEntity, sphereEntity); auto cylinderEntity = runner.EntityCompMgr().EntityByComponents( - ignition::gazebo::components::Model(), - ignition::gazebo::components::Name("cylinder")); + gz::sim::components::Model(), + gz::sim::components::Name("cylinder")); EXPECT_NE(kNullEntity, cylinderEntity); // We can't access the type registered by the plugin unless we link against // it, but we know its name to check std::string componentName{"ModelPluginComponent"}; - auto componentId = ignition::common::hash64(componentName); + auto componentId = gz::common::hash64(componentName); // Check there's no double component EXPECT_FALSE(runner.EntityCompMgr().HasComponentType(componentId)); @@ -1544,7 +1544,7 @@ TEST_P(SimulationRunnerTest, // ServerConfig will fall back to environment variable auto config = common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "server_valid2.config"); - ASSERT_EQ(true, common::setenv(gazebo::kServerConfigPathEnv, config)); + ASSERT_EQ(true, common::setenv(sim::kServerConfigPathEnv, config)); ServerConfig serverConfig; // Create simulation runner diff --git a/src/SystemInternal.hh b/src/SystemInternal.hh index 01b1dfb6fc..78df9cbedc 100644 --- a/src/SystemInternal.hh +++ b/src/SystemInternal.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMINTERNAL_HH_ -#define IGNITION_GAZEBO_SYSTEMINTERNAL_HH_ +#ifndef GZ_SIM_SYSTEMINTERNAL_HH_ +#define GZ_SIM_SYSTEMINTERNAL_HH_ #include #include @@ -26,12 +26,12 @@ #include "gz/sim/System.hh" #include "gz/sim/SystemPluginPtr.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { /// \brief Class to hold systems internally. It supports systems loaded /// from plugins, as well as systems created at runtime. @@ -113,7 +113,7 @@ namespace ignition public: std::vector updates; }; } - } // namespace gazebo -} // namespace ignition -#endif // IGNITION_GAZEBO_SYSTEMINTERNAL_HH_ + } // namespace sim +} // namespace gz +#endif // GZ_SIM_SYSTEMINTERNAL_HH_ diff --git a/src/SystemLoader.cc b/src/SystemLoader.cc index 29e994d36b..de5b6e48f9 100644 --- a/src/SystemLoader.cc +++ b/src/SystemLoader.cc @@ -33,9 +33,9 @@ #include -using namespace ignition::gazebo; +using namespace gz::sim; -class ignition::gazebo::SystemLoaderPrivate +class gz::sim::SystemLoaderPrivate { ////////////////////////////////////////////////// public: explicit SystemLoaderPrivate() = default; @@ -44,26 +44,26 @@ 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 + "/.gz/sim/plugins"); - systemPaths.AddPluginPaths(IGN_GAZEBO_PLUGIN_INSTALL_DIR); + systemPaths.AddPluginPaths(GZ_SIM_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 << + gzerr << "Failed to load system plugin [" << _filename << "] : couldn't find shared library." << std::endl; } return false; @@ -72,7 +72,7 @@ class ignition::gazebo::SystemLoaderPrivate auto pluginNames = this->loader.LoadLib(pathToLib); if (pluginNames.empty()) { - ignerr << "Failed to load system plugin [" << _filename << + gzerr << "Failed to load system plugin [" << _filename << "] : couldn't load library on path [" << pathToLib << "]." << std::endl; return false; @@ -81,7 +81,7 @@ class ignition::gazebo::SystemLoaderPrivate auto pluginName = *pluginNames.begin(); if (pluginName.empty()) { - ignerr << "Failed to load system plugin [" << _filename << + gzerr << "Failed to load system plugin [" << _filename << "] : couldn't load library on path [" << pathToLib << "]." << std::endl; return false; @@ -90,7 +90,7 @@ class ignition::gazebo::SystemLoaderPrivate _plugin = this->loader.Instantiate(_name); if (!_plugin) { - ignerr << "Failed to load system plugin [" << _name << + gzerr << "Failed to load system plugin [" << _name << "] : could not instantiate from library [" << _filename << "] from path [" << pathToLib << "]." << std::endl; return false; @@ -98,7 +98,7 @@ class ignition::gazebo::SystemLoaderPrivate if (!_plugin->HasInterface()) { - ignerr << "Failed to load system plugin [" << _name << + gzerr << "Failed to load system plugin [" << _name << "] : system not found in library [" << _filename << "] from path [" << pathToLib << "]." << 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,11 +143,11 @@ std::optional SystemLoader::LoadPlugin( const std::string &_name, const sdf::ElementPtr &_sdf) { - ignition::plugin::PluginPtr plugin; + gz::plugin::PluginPtr plugin; if (_filename == "" || _name == "") { - ignerr << "Failed to instantiate system plugin: empty argument " + gzerr << "Failed to instantiate system plugin: empty argument " "[(filename): " << _filename << "] " << "[(name): " << _name << "]." << std::endl; return {}; @@ -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 adf14158e7..375744b989 100644 --- a/src/SystemLoader_TEST.cc +++ b/src/SystemLoader_TEST.cc @@ -26,15 +26,15 @@ #include "gz/sim/test_config.hh" // NOLINT(build/include) -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(SystemLoader, Constructor) { - gazebo::SystemLoader sm; + sim::SystemLoader sm; // Add test plugin to path (referenced in config) - auto testBuildPath = ignition::common::joinPaths( + auto testBuildPath = gz::common::joinPaths( std::string(PROJECT_BINARY_PATH), "lib"); sm.AddSystemPluginPath(testBuildPath); @@ -42,8 +42,8 @@ TEST(SystemLoader, Constructor) root.LoadSdfString(std::string("" "" "" + GZ_SIM_MAJOR_VERSION_STR + "-physics-system.so' " + "name='gz::sim::systems::Physics'>" ""); auto worldElem = root.WorldByIndex(0)->Element(); @@ -60,7 +60,7 @@ TEST(SystemLoader, Constructor) TEST(SystemLoader, EmptyNames) { - gazebo::SystemLoader sm; + sim::SystemLoader sm; sdf::ElementPtr element; auto system = sm.LoadPlugin("", "", element); ASSERT_FALSE(system.has_value()); diff --git a/src/SystemManager.cc b/src/SystemManager.cc index bde885612c..38327b139b 100644 --- a/src/SystemManager.cc +++ b/src/SystemManager.cc @@ -17,8 +17,8 @@ #include "SystemManager.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ////////////////////////////////////////////////// SystemManager::SystemManager(const SystemLoaderPtr &_systemLoader, @@ -46,7 +46,7 @@ void SystemManager::LoadPlugin(const Entity _entity, if (system) { this->AddSystem(system.value(), _entity, _sdf); - igndbg << "Loaded system [" << _name + gzdbg << "Loaded system [" << _name << "] for entity [" << _entity << "]" << std::endl; } } diff --git a/src/SystemManager.hh b/src/SystemManager.hh index 1a6071ab0e..b1a5147155 100644 --- a/src/SystemManager.hh +++ b/src/SystemManager.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMMANAGER_HH_ -#define IGNITION_GAZEBO_SYSTEMMANAGER_HH_ +#ifndef GZ_SIM_SYSTEMMANAGER_HH_ +#define GZ_SIM_SYSTEMMANAGER_HH_ #include #include @@ -29,15 +29,15 @@ #include "SystemInternal.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { /// \brief Used to load / unload sysetms as well as iterate over them. - class IGNITION_GAZEBO_VISIBLE SystemManager + class GZ_GAZEBO_VISIBLE SystemManager { /// \brief Constructor /// \param[in] _systemLoader A pointer to a SystemLoader to load plugins @@ -161,6 +161,6 @@ namespace ignition private: EventManager *eventMgr; }; } - } // namespace gazebo -} // namespace ignition -#endif // IGNITION_GAZEBO_SYSTEMINTERNAL_HH_ + } // namespace sim +} // namespace gz +#endif // GZ_SIM_SYSTEMINTERNAL_HH_ diff --git a/src/SystemManager_TEST.cc b/src/SystemManager_TEST.cc index c5699701c3..e6336d68af 100644 --- a/src/SystemManager_TEST.cc +++ b/src/SystemManager_TEST.cc @@ -25,7 +25,7 @@ #include "SystemManager.hh" -using namespace ignition::gazebo; +using namespace gz::sim; ///////////////////////////////////////////////// class SystemWithConfigure: diff --git a/src/System_TEST.cc b/src/System_TEST.cc index dbe29eef85..e238456085 100644 --- a/src/System_TEST.cc +++ b/src/System_TEST.cc @@ -19,7 +19,7 @@ #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 cbe0685178..8110deca1b 100644 --- a/src/TestFixture.cc +++ b/src/TestFixture.cc @@ -20,8 +20,8 @@ #include "gz/sim/TestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; /// \brief System that is inserted into the simulation loop to observe the ECM. class HelperSystem : @@ -106,14 +106,14 @@ void HelperSystem::PostUpdate(const UpdateInfo &_info, } ////////////////////////////////////////////////// -class ignition::gazebo::TestFixturePrivate +class gz::sim::TestFixturePrivate { /// \brief Initialize fixture /// \param[in] _config Server config public: void Init(const ServerConfig &_config); /// \brief Pointer to underlying server - public: std::shared_ptr server{nullptr}; + public: std::shared_ptr server{nullptr}; /// \brief Pointer to underlying Helper interface public: std::shared_ptr helperSystem{nullptr}; @@ -149,7 +149,7 @@ TestFixture::~TestFixture() void TestFixturePrivate::Init(const ServerConfig &_config) { this->helperSystem = std::make_shared(); - this->server = std::make_shared(_config); + this->server = std::make_shared(_config); } ////////////////////////////////////////////////// @@ -157,7 +157,7 @@ TestFixture &TestFixture::Finalize() { if (this->dataPtr->finalized) { - ignwarn << "Fixture has already been finalized, this only needs to be done" + gzwarn << "Fixture has already been finalized, this only needs to be done" << " once." << std::endl; return *this; } @@ -208,7 +208,7 @@ TestFixture &TestFixture::OnPostUpdate(std::function TestFixture::Server() const +std::shared_ptr TestFixture::Server() const { return this->dataPtr->server; } diff --git a/src/TestFixture_TEST.cc b/src/TestFixture_TEST.cc index 832e480770..02da54e5a6 100644 --- a/src/TestFixture_TEST.cc +++ b/src/TestFixture_TEST.cc @@ -26,8 +26,8 @@ #include "../test/helpers/EnvTestFixture.hh" #include "gz/sim/TestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// class TestFixtureTest : public InternalFixture<::testing::Test> diff --git a/src/Util.cc b/src/Util.cc index 804b6ea23b..7d49a5b4ad 100644 --- a/src/Util.cc +++ b/src/Util.cc @@ -41,12 +41,12 @@ #include "gz/sim/Util.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { ////////////////////////////////////////////////// math::Pose3d worldPose(const Entity &_entity, const EntityComponentManager &_ecm) @@ -54,7 +54,7 @@ math::Pose3d worldPose(const Entity &_entity, auto poseComp = _ecm.Component(_entity); if (nullptr == poseComp) { - ignwarn << "Trying to get world pose from entity [" << _entity + gzwarn << "Trying to get world pose from entity [" << _entity << "], which doesn't have a pose component" << std::endl; return math::Pose3d(); } @@ -97,7 +97,7 @@ std::string scopedName(const Entity &_entity, std::string prefix = entityTypeStr(entity, _ecm); if (prefix.empty()) { - ignwarn << "Skipping entity [" << name + gzwarn << "Skipping entity [" << name << "] when generating scoped name, entity type not known." << std::endl; } @@ -132,7 +132,7 @@ std::unordered_set entitiesFromScopedName( { if (_delim.empty()) { - ignwarn << "Can't process scoped name [" << _scopedName + gzwarn << "Can't process scoped name [" << _scopedName << "] with empty delimiter." << std::endl; return {}; } @@ -347,7 +347,7 @@ std::string asFullPath(const std::string &_uri, const std::string &_filePath) // When SDF is loaded from a string instead of a file if (std::string(sdf::kSdfStringSource) == _filePath) { - ignwarn << "Can't resolve full path for relative path [" + gzwarn << "Can't resolve full path for relative path [" << _uri << "]. Loaded from a data-string." << std::endl; return _uri; } @@ -449,20 +449,20 @@ void addResourcePaths(const std::vector &_paths) for (const auto &path : sdfPaths) sdfPathsStr += ':' + path; - ignition::common::setenv(kSdfPathEnv.c_str(), sdfPathsStr.c_str()); + gz::common::setenv(kSdfPathEnv.c_str(), sdfPathsStr.c_str()); std::string ignPathsStr; for (const auto &path : ignPaths) ignPathsStr += ':' + path; - ignition::common::setenv( + gz::common::setenv( systemPaths->FilePathEnv().c_str(), ignPathsStr.c_str()); std::string gzPathsStr; for (const auto &path : gzPaths) gzPathsStr += ':' + path; - ignition::common::setenv(kResourcePathEnv.c_str(), gzPathsStr.c_str()); + gz::common::setenv(kResourcePathEnv.c_str(), gzPathsStr.c_str()); // Force re-evaluation // SDF is evaluated at find call @@ -470,7 +470,7 @@ void addResourcePaths(const std::vector &_paths) } ////////////////////////////////////////////////// -ignition::gazebo::Entity topLevelModel(const Entity &_entity, +gz::sim::Entity topLevelModel(const Entity &_entity, const EntityComponentManager &_ecm) { auto entity = _entity; @@ -519,12 +519,12 @@ std::string validTopic(const std::vector &_topics) auto validTopic = transport::TopicUtils::AsValidTopic(topic); if (validTopic.empty()) { - ignerr << "Topic [" << topic << "] is invalid, ignoring." << std::endl; + gzerr << "Topic [" << topic << "] is invalid, ignoring." << std::endl; continue; } if (validTopic != topic) { - igndbg << "Topic [" << topic << "] changed to valid topic [" + gzdbg << "Topic [" << topic << "] changed to valid topic [" << validTopic << "]" << std::endl; } return validTopic; @@ -608,7 +608,7 @@ std::string resolveSdfWorldFile(const std::string &_sdfFile, } else { - ignwarn << "Fuel couldn't download URL [" << _sdfFile + gzwarn << "Fuel couldn't download URL [" << _sdfFile << "], error: [" << result.ReadableResult() << "]" << std::endl; } @@ -622,7 +622,7 @@ std::string resolveSdfWorldFile(const std::string &_sdfFile, systemPaths.SetFilePathEnv(kResourcePathEnv); // Worlds installed with ign-gazebo - systemPaths.AddFilePaths(IGN_GAZEBO_WORLD_INSTALL_DIR); + systemPaths.AddFilePaths(GZ_SIM_WORLD_INSTALL_DIR); filePath = systemPaths.FindFile(_sdfFile); } diff --git a/src/Util_TEST.cc b/src/Util_TEST.cc index cad8d3ad44..41f151d8b1 100644 --- a/src/Util_TEST.cc +++ b/src/Util_TEST.cc @@ -40,8 +40,8 @@ #include "helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; /// \brief Tests for Util.hh class UtilTest : public InternalFixture<::testing::Test> @@ -70,8 +70,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, sim::worldEntity(ecm)); + EXPECT_EQ(kNullEntity, sim::worldEntity(worldEntity, ecm)); ecm.CreateComponent(worldEntity, components::World()); ecm.CreateComponent(worldEntity, components::Name("world_name")); @@ -214,22 +214,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, sim::worldEntity(ecm)); + EXPECT_EQ(worldEntity, sim::worldEntity(worldEntity, ecm)); + EXPECT_EQ(worldEntity, sim::worldEntity(lightAEntity, ecm)); + EXPECT_EQ(worldEntity, sim::worldEntity(modelBEntity, ecm)); + EXPECT_EQ(worldEntity, sim::worldEntity(linkBEntity, ecm)); + EXPECT_EQ(worldEntity, sim::worldEntity(lightBEntity, ecm)); + EXPECT_EQ(worldEntity, sim::worldEntity(sensorBEntity, ecm)); + EXPECT_EQ(worldEntity, sim::worldEntity(modelCEntity, ecm)); + EXPECT_EQ(worldEntity, sim::worldEntity(linkCEntity, ecm)); + EXPECT_EQ(worldEntity, sim::worldEntity(collisionCEntity, ecm)); + EXPECT_EQ(worldEntity, sim::worldEntity(visualCEntity, ecm)); + EXPECT_EQ(worldEntity, sim::worldEntity(jointCEntity, ecm)); + EXPECT_EQ(worldEntity, sim::worldEntity(modelCCEntity, ecm)); + EXPECT_EQ(worldEntity, sim::worldEntity(linkCCEntity, ecm)); + EXPECT_EQ(worldEntity, sim::worldEntity(actorDEntity, ecm)); + EXPECT_EQ(kNullEntity, sim::worldEntity(kNullEntity, ecm)); } ///////////////////////////////////////////////// @@ -283,7 +283,7 @@ TEST_F(UtilTest, EntitiesFromScopedName) Entity _relativeTo, const std::unordered_set &_result, const std::string &_delim) { - auto res = gazebo::entitiesFromScopedName(_scopedName, ecm, _relativeTo, + auto res = sim::entitiesFromScopedName(_scopedName, ecm, _relativeTo, _delim); EXPECT_EQ(_result.size(), res.size()) << _scopedName; diff --git a/src/View.cc b/src/View.cc index d5d48433ea..d325c25fdd 100644 --- a/src/View.cc +++ b/src/View.cc @@ -17,12 +17,12 @@ #include "gz/sim/detail/View.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace detail { ////////////////////////////////////////////////// @@ -57,12 +57,12 @@ bool View::HasCachedComponentData(const Entity _entity) const if (cachedComps && !cachedConstComps) { - ignwarn << "Non-const component data is cached for entity " << _entity + gzwarn << "Non-const component data is cached for entity " << _entity << ", but const component data is not cached." << std::endl; } else if (cachedConstComps && !cachedComps) { - ignwarn << "Const component data is cached for entity " << _entity + gzwarn << "Const component data is cached for entity " << _entity << ", but non-const component data is not cached." << std::endl; } @@ -181,5 +181,5 @@ void View::Reset() } // namespace detail } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/src/World.cc b/src/World.cc index aa960e8610..80d9069498 100644 --- a/src/World.cc +++ b/src/World.cc @@ -30,17 +30,17 @@ #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 sim; ////////////////////////////////////////////////// -World::World(gazebo::Entity _entity) +World::World(sim::Entity _entity) : dataPtr(std::make_unique()) { this->dataPtr->id = _entity; @@ -140,7 +140,7 @@ Entity World::LightByName(const EntityComponentManager &_ecm, const std::string &_name) const { // Can't use components::Light in EntityByComponents, see - // https://github.com/ignitionrobotics/ign-gazebo/issues/376 + // https://github.com/gazebosim/gz-sim/issues/376 auto entities = _ecm.EntitiesByComponents( components::ParentEntity(this->dataPtr->id), components::Name(_name)); @@ -158,7 +158,7 @@ Entity World::ActorByName(const EntityComponentManager &_ecm, const std::string &_name) const { // Can't use components::Actor in EntityByComponents, see - // https://github.com/ignitionrobotics/ign-gazebo/issues/376 + // https://github.com/gazebosim/gz-sim/issues/376 auto entities = _ecm.EntitiesByComponents( components::ParentEntity(this->dataPtr->id), components::Name(_name)); @@ -185,11 +185,11 @@ Entity World::ModelByName(const EntityComponentManager &_ecm, std::vector World::Lights(const EntityComponentManager &_ecm) const { // Can't use components::Light in EntityByComponents, see - // https://github.com/ignitionrobotics/ign-gazebo/issues/376 + // https://github.com/gazebosim/gz-sim/issues/376 auto entities = _ecm.EntitiesByComponents( components::ParentEntity(this->dataPtr->id)); - std::vector result; + std::vector result; for (const auto &entity : entities) { if (_ecm.Component(entity)) @@ -202,11 +202,11 @@ std::vector World::Lights(const EntityComponentManager &_ecm) const std::vector World::Actors(const EntityComponentManager &_ecm) const { // Can't use components::Actor in EntityByComponents, see - // https://github.com/ignitionrobotics/ign-gazebo/issues/376 + // https://github.com/gazebosim/gz-sim/issues/376 auto entities = _ecm.EntitiesByComponents( components::ParentEntity(this->dataPtr->id)); - std::vector result; + std::vector result; for (const auto &entity : entities) { if (_ecm.Component(entity)) diff --git a/src/WorldControl.hh b/src/WorldControl.hh index 9e57ac458f..9eaf267a69 100644 --- a/src/WorldControl.hh +++ b/src/WorldControl.hh @@ -14,20 +14,20 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_WORLDCONTROL_HH_ -#define IGNITION_GAZEBO_WORLDCONTROL_HH_ +#ifndef GZ_SIM_WORLDCONTROL_HH_ +#define GZ_SIM_WORLDCONTROL_HH_ #include #include #include "gz/sim/config.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { /// \brief Helper struct to control world time. It's used to hold /// input from either msgs::WorldControl or msgs::LogPlaybackControl. @@ -56,6 +56,6 @@ namespace ignition std::chrono::steady_clock::duration seek{-1}; }; } - } // namespace gazebo -} // namespace ignition -#endif // IGNITION_GAZEBO_WORLDCONTROL_HH_ + } // namespace sim +} // namespace gz +#endif // GZ_SIM_WORLDCONTROL_HH_ diff --git a/src/World_TEST.cc b/src/World_TEST.cc index 06cd31b3da..824af1f761 100644 --- a/src/World_TEST.cc +++ b/src/World_TEST.cc @@ -22,11 +22,11 @@ ///////////////////////////////////////////////// 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 b3ea1e47ee..a8441970cf 100644 --- a/src/cmd/ModelCommandAPI.cc +++ b/src/cmd/ModelCommandAPI.cc @@ -58,8 +58,8 @@ #include #include -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ////////////////////////////////////////////////// /// \brief Get the name of the world being used by calling diff --git a/src/cmd/cmdgazebo.rb.in b/src/cmd/cmdgazebo.rb.in index 36fd7c6517..6c2ba1fa86 100755 --- a/src/cmd/cmdgazebo.rb.in +++ b/src/cmd/cmdgazebo.rb.in @@ -118,31 +118,31 @@ COMMANDS = { 'gazebo' => " The default verbosity is 1, use -v without \n"\ " arguments for level 3. \n"\ "\n"\ - " --gui-config [arg] Ignition GUI configuration file to load. \n"\ + " --gui-config [arg] Gazebo GUI configuration file to load. \n"\ " If no config is given, the configuration in \n"\ " the SDF file is used. And if that's not \n"\ " provided, the default installed config is \n"\ " used. \n"\ "\n"\ - " --physics-engine [arg] Ignition Physics engine plugin to load. \n"\ + " --physics-engine [arg] Gazebo Physics engine plugin to load. \n"\ " Gazebo will use DART by default. \n"\ " (ignition-physics-dartsim-plugin) \n"\ " Make sure custom plugins are in \n"\ " IGN_GAZEBO_PHYSICS_ENGINE_PATH. \n"\ "\n"\ - " --render-engine [arg] Ignition Rendering engine plugin to load for \n"\ + " --render-engine [arg] Gazebo Rendering engine plugin to load for \n"\ " both the server and the GUI. Gazebo will use \n"\ " OGRE2 by default. (ogre2) \n"\ " Make sure custom plugins are in \n"\ " IGN_GAZEBO_RENDER_ENGINE_PATH. \n"\ "\n"\ - " --render-engine-gui [arg] Ignition Rendering engine plugin to load for \n"\ + " --render-engine-gui [arg] Gazebo Rendering engine plugin to load for \n"\ " the GUI. Gazebo will use OGRE2 by default. \n"\ " (ogre2) \n"\ " Make sure custom plugins are in \n"\ " IGN_GAZEBO_RENDER_ENGINE_PATH. \n"\ "\n"\ - " --render-engine-server [arg] Ignition Rendering engine plugin to load for \n"\ + " --render-engine-server [arg] Gazebo Rendering engine plugin to load for \n"\ " the server. Gazebo will use OGRE2 by default. \n"\ " (ogre2) \n"\ " Make sure custom plugins are in \n"\ @@ -164,7 +164,7 @@ COMMANDS = { 'gazebo' => } # -# Class for the Ignition Gazebo command line tools. +# Class for the Gazebo command line tools. # class Cmd @@ -449,7 +449,7 @@ has properly set the DYLD_LIBRARY_PATH environment variables." if plugin.end_with? ".dylib" puts "`ign gazebo` currently only works with the -s argument on macOS. -See https://github.com/ignitionrobotics/ign-gazebo/issues/44 for more info." +See https://github.com/gazebosim/gz-sim/issues/44 for more info." exit(-1) end @@ -476,8 +476,8 @@ See https://github.com/ignitionrobotics/ign-gazebo/issues/44 for more info." end Signal.trap("INT") { - self.killProcess(guiPid, "Ignition Gazebo GUI", 5.0) - self.killProcess(serverPid, "Ignition Gazebo Server", 5.0) + self.killProcess(guiPid, "Gazebo Sim GUI", 5.0) + self.killProcess(serverPid, "Gazebo Sim Server", 5.0) return 1 } @@ -485,9 +485,9 @@ See https://github.com/ignitionrobotics/ign-gazebo/issues/44 for more info." pid, status = Process.wait2 if pid == serverPid - self.killProcess(guiPid, "Ignition Gazebo GUI", 5.0) + self.killProcess(guiPid, "Gazebo Sim GUI", 5.0) else - self.killProcess(serverPid, "Ignition Gazebo Server", 5.0) + self.killProcess(serverPid, "Gazebo Sim Server", 5.0) end # If the -s option was specified, then run only the server @@ -506,7 +506,7 @@ See https://github.com/ignitionrobotics/ign-gazebo/issues/44 for more info." else options['gui'] if plugin.end_with? ".dylib" puts "`ign gazebo` currently only works with the -s argument on macOS. -See https://github.com/ignitionrobotics/ign-gazebo/issues/44 for more info." +See https://github.com/gazebosim/gz-sim/issues/44 for more info." exit(-1) end diff --git a/src/cmd/cmdmodel.rb.in b/src/cmd/cmdmodel.rb.in index 88e65a50f3..c426a879dc 100644 --- a/src/cmd/cmdmodel.rb.in +++ b/src/cmd/cmdmodel.rb.in @@ -75,7 +75,7 @@ COMMANDS = { 'model' => } # -# Class for the Ignition Gazebo Model command line tools. +# Class for the Gazebo Model command line tools. # class Cmd diff --git a/src/cmd/ign.cc b/src/cmd/ign.cc index 4e275e3272..080dcb0813 100644 --- a/src/cmd/ign.cc +++ b/src/cmd/ign.cc @@ -33,26 +33,26 @@ ////////////////////////////////////////////////// extern "C" char *ignitionGazeboVersion() { - return strdup(IGNITION_GAZEBO_VERSION_FULL); + return strdup(GZ_SIM_VERSION_FULL); } ////////////////////////////////////////////////// extern "C" char *gazeboVersionHeader() { - return strdup(IGNITION_GAZEBO_VERSION_HEADER); + return strdup(GZ_SIM_VERSION_HEADER); } ////////////////////////////////////////////////// extern "C" void cmdVerbosity( const char *_verbosity) { - ignition::common::Console::SetVerbosity(std::atoi(_verbosity)); + gz::common::Console::SetVerbosity(std::atoi(_verbosity)); } ////////////////////////////////////////////////// extern "C" const char *worldInstallDir() { - return IGN_GAZEBO_WORLD_INSTALL_DIR; + return GZ_SIM_WORLD_INSTALL_DIR; } ////////////////////////////////////////////////// @@ -61,7 +61,7 @@ extern "C" int runServer(const char *_sdfString, int _networkSecondaries, int _record, const char *_recordPath, int _logOverwrite, const char *_playback, const char *_file) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; // Path for logs std::string recordPathMod = serverConfig.LogRecordPath(); @@ -71,7 +71,7 @@ extern "C" int runServer(const char *_sdfString, { if (_playback != nullptr && std::strlen(_playback) > 0) { - ignerr << "Both record and playback are specified. Only specify one.\n"; + gzerr << "Both record and playback are specified. Only specify one.\n"; return -1; } @@ -83,27 +83,27 @@ extern "C" int runServer(const char *_sdfString, recordPathMod = std::string(_recordPath); // Check if path or compressed file with same prefix exists - if (ignition::common::exists(recordPathMod)) + if (gz::common::exists(recordPathMod)) { // Overwrite if flag specified if (_logOverwrite > 0) { bool recordMsg = false; // Remove files before initializing console log files on top of them - if (ignition::common::exists(recordPathMod)) + if (gz::common::exists(recordPathMod)) { recordMsg = true; - ignition::common::removeAll(recordPathMod); + gz::common::removeAll(recordPathMod); } // Create log file before printing any messages so they can be logged - ignLogInit(recordPathMod, "server_console.log"); + gzLogInit(recordPathMod, "server_console.log"); if (recordMsg) { - ignmsg << "Log path already exists on disk! Existing files will " + gzmsg << "Log path already exists on disk! Existing files will " << "be overwritten." << std::endl; - ignmsg << "Removing existing path [" << recordPathMod << "]\n"; + gzmsg << "Removing existing path [" << recordPathMod << "]\n"; } } // Otherwise rename to unique path @@ -111,28 +111,28 @@ extern "C" int runServer(const char *_sdfString, { // Remove the separator at end of path if (!std::string(1, recordPathMod.back()).compare( - ignition::common::separator(""))) + gz::common::separator(""))) { recordPathMod = recordPathMod.substr(0, recordPathMod.length() - 1); } - recordPathMod = ignition::common::uniqueDirectoryPath(recordPathMod); + recordPathMod = gz::common::uniqueDirectoryPath(recordPathMod); - ignLogInit(recordPathMod, "server_console.log"); - ignwarn << "Log path already exists on disk! " + gzLogInit(recordPathMod, "server_console.log"); + gzwarn << "Log path already exists on disk! " << "Recording instead to [" << recordPathMod << "]" << std::endl; } } else { - ignLogInit(recordPathMod, "server_console.log"); + gzLogInit(recordPathMod, "server_console.log"); } } // Empty record path specified. Use default. else { // Create log file before printing any messages so they can be logged - ignLogInit(recordPathMod, "server_console.log"); - ignmsg << "Recording states to default path [" << recordPathMod << "]" + gzLogInit(recordPathMod, "server_console.log"); + gzmsg << "Recording states to default path [" << recordPathMod << "]" << std::endl; serverConfig.SetLogRecordPath(recordPathMod); @@ -140,12 +140,12 @@ extern "C" int runServer(const char *_sdfString, } else { - ignLogInit(serverConfig.LogRecordPath(), "server_console.log"); + gzLogInit(serverConfig.LogRecordPath(), "server_console.log"); } serverConfig.SetLogRecordPath(recordPathMod); - ignmsg << "Ignition Gazebo Server v" << IGNITION_GAZEBO_VERSION_FULL + gzmsg << "Ignition Gazebo Server v" << GZ_SIM_VERSION_FULL << std::endl; // Set the SDF string to user @@ -153,7 +153,7 @@ extern "C" int runServer(const char *_sdfString, { if (!serverConfig.SetSdfString(_sdfString)) { - ignerr << "Failed to set SDF string [" << _sdfString << "]" << std::endl; + gzerr << "Failed to set SDF string [" << _sdfString << "]" << std::endl; return -1; } } @@ -166,13 +166,13 @@ extern "C" int runServer(const char *_sdfString, // Set whether levels should be used. if (_levels > 0) { - ignmsg << "Using the level system\n"; + gzmsg << "Using the level system\n"; serverConfig.SetUseLevels(true); } if (_networkRole && std::strlen(_networkRole) > 0) { - ignmsg << "Using the distributed simulation and levels systems\n"; + gzmsg << "Using the distributed simulation and levels systems\n"; serverConfig.SetNetworkRole(_networkRole); serverConfig.SetNetworkSecondaries(_networkSecondaries); serverConfig.SetUseLevels(true); @@ -182,66 +182,66 @@ extern "C" int runServer(const char *_sdfString, { if (_sdfString != nullptr && std::strlen(_sdfString) > 0) { - ignerr << "Both an SDF file and playback flag are specified. " + gzerr << "Both an SDF file and playback flag are specified. " << "Only specify one.\n"; return -1; } else { - ignmsg << "Playing back states" << _playback << std::endl; - serverConfig.SetLogPlaybackPath(ignition::common::absPath( + gzmsg << "Playing back states" << _playback << std::endl; + serverConfig.SetLogPlaybackPath(gz::common::absPath( std::string(_playback))); } } // Create the Gazebo server - ignition::gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); // Run the server server.Run(true, _iterations, _run == 0); - igndbg << "Shutting down server" << std::endl; + gzdbg << "Shutting down server" << std::endl; return 0; } ////////////////////////////////////////////////// extern "C" int runGui(const char *_guiConfig) { - ignition::common::SignalHandler sigHandler; + gz::common::SignalHandler sigHandler; bool sigKilled = false; sigHandler.AddCallback([&](const int /*_sig*/) { sigKilled = true; }); - ignmsg << "Ignition Gazebo GUI v" << IGNITION_GAZEBO_VERSION_FULL + gzmsg << "Ignition Gazebo GUI v" << GZ_SIM_VERSION_FULL << std::endl; int argc = 0; char **argv = nullptr; // Initialize Qt app - ignition::gui::Application app(argc, argv); - app.AddPluginPath(IGN_GAZEBO_GUI_PLUGIN_INSTALL_DIR); + gz::gui::Application app(argc, argv); + app.AddPluginPath(GZ_SIM_WORLD_INSTALL_DIR;; // add import path so we can load custom modules - app.Engine()->addImportPath(IGN_GAZEBO_GUI_PLUGIN_INSTALL_DIR); + app.Engine()->addImportPath(GZ_SIM_WORLD_INSTALL_DIR;; // Set default config file for Gazebo std::string defaultConfigDir; - ignition::common::env(IGN_HOMEDIR, defaultConfigDir); - defaultConfigDir = ignition::common::joinPaths(defaultConfig, ".ignition", - "gazebo", IGNITION_GAZEBO_MAJOR_VERSION_STR); + gz::common::env(IGN_HOMEDIR, defaultConfigDir); + defaultConfigDir = gz::common::joinPaths(defaultConfig, ".gz", + "sim", GZ_SIM_MAJOR_VERSION_STR); - auto defaultConfig = ignition::common::joinPaths(defaultConfigDir, + auto defaultConfig = gz::common::joinPaths(defaultConfigDir, "gui.config"); app.SetDefaultConfigPath(defaultConfig); // Customize window - auto mainWin = app.findChild(); + auto mainWin = app.findChild(); auto win = mainWin->QuickWindow(); - win->setProperty("title", "Gazebo"); + win->setProperty("title", "Gazebo Sim"); // Instantiate GazeboDrawer.qml file into a component QQmlComponent component(app.Engine(), ":/Gazebo/GazeboDrawer.qml"); @@ -258,18 +258,18 @@ extern "C" int runGui(const char *_guiConfig) } else { - ignerr << "Failed to instantiate custom drawer, drawer will be empty" + gzerr << "Failed to instantiate custom drawer, drawer will be empty" << std::endl; } // Get list of worlds - ignition::transport::Node node; + gz::transport::Node node; bool executed{false}; bool result{false}; unsigned int timeout{5000}; std::string service{"/gazebo/worlds"}; - ignition::msgs::StringMsg_V worldsMsg; + gz::msgs::StringMsg_V worldsMsg; // This loop is here to allow the server time to download resources. // \todo(nkoenig) Async resource download. Search for "Async resource @@ -277,7 +277,7 @@ extern "C" int runGui(const char *_guiConfig) // resolved when this while loop can be removed. while (!sigKilled && !executed) { - igndbg << "GUI requesting list of world names. The server may be busy " + gzdbg << "GUI requesting list of world names. The server may be busy " << "downloading resources. Please be patient." << std::endl; executed = node.Request(service, timeout, worldsMsg, result); } @@ -286,9 +286,9 @@ extern "C" int runGui(const char *_guiConfig) if (!sigKilled) { if (!executed) - ignerr << "Timed out when getting world names." << std::endl; + gzerr << "Timed out when getting world names." << std::endl; else if (!result) - ignerr << "Failed to get world names." << std::endl; + gzerr << "Failed to get world names." << std::endl; } if (!executed || !result || worldsMsg.data().empty()) @@ -302,7 +302,7 @@ extern "C" int runGui(const char *_guiConfig) # pragma warning(push) # pragma warning(disable: 4996) #endif - std::vector runners; + std::vector runners; #ifndef _WIN32 # pragma GCC diagnostic pop #else @@ -314,12 +314,12 @@ extern "C" int runGui(const char *_guiConfig) { if (!app.LoadConfig(_guiConfig)) { - ignwarn << "Failed to load config file[" << _guiConfig << "]." + gzwarn << "Failed to load config file[" << _guiConfig << "]." << std::endl; } // Use the first world name with the config file - // TODO(anyone) Most of ign-gazebo's transport API includes the world name, + // TODO(anyone) Most of gz-sim'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 ~ @@ -331,16 +331,16 @@ extern "C" int runGui(const char *_guiConfig) # pragma warning(push) # pragma warning(disable: 4996) #endif - auto runner = new ignition::gazebo::GuiRunner(worldsMsg.data(0)); + auto runner = new gz::sim::GuiRunner(worldsMsg.data(0)); #ifndef _WIN32 # pragma GCC diagnostic pop #else # pragma warning(pop) #endif - runner->connect(&app, &ignition::gui::Application::PluginAdded, runner, - &ignition::gazebo::GuiRunner::OnPluginAdded); + runner->connect(&app, &gz::gui::Application::PluginAdded, runner, + &gz::sim::GuiRunner::OnPluginAdded); runners.push_back(runner); - runner->setParent(ignition::gui::App()); + runner->setParent(gz::gui::App()); } // GUI configuration from SDF (request to server) else @@ -355,16 +355,16 @@ extern "C" int runGui(const char *_guiConfig) result = false; service = std::string("/world/" + worldName + "/gui/info"); - igndbg << "Requesting GUI from [" << service << "]..." << std::endl; + gzdbg << "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) - ignerr << "Service call timed out for [" << service << "]" << std::endl; + gzerr << "Service call timed out for [" << service << "]" << std::endl; else if (!result) - ignerr << "Service call failed for [" << service << "]" << std::endl; + gzerr << "Service call failed for [" << service << "]" << std::endl; for (int p = 0; p < res.plugin_size(); ++p) { @@ -381,10 +381,10 @@ extern "C" int runGui(const char *_guiConfig) } // GUI runner - auto runner = new ignition::gazebo::GuiRunner(worldName); - runner->connect(&app, &ignition::gui::Application::PluginAdded, runner, - &ignition::gazebo::GuiRunner::OnPluginAdded); - runner->setParent(ignition::gui::App()); + auto runner = new gz::sim::GuiRunner(worldName); + runner->connect(&app, &gz::gui::Application::PluginAdded, runner, + &gz::sim::GuiRunner::OnPluginAdded); + runner->setParent(gz::gui::App()); runners.push_back(runner); } mainWin->configChanged(); @@ -392,48 +392,48 @@ extern "C" int runGui(const char *_guiConfig) if (runners.empty()) { - ignerr << "Failed to start a GUI runner." << std::endl; + gzerr << "Failed to start a GUI runner." << std::endl; return -1; } // If no plugins have been added, load default config file - auto plugins = mainWin->findChildren(); + auto plugins = mainWin->findChildren(); if (plugins.empty()) { // Check if there's a default config file under // ~/.gz/sim and use that. If there isn't, copy // the installed file there first. - if (!ignition::common::exists(defaultConfig)) + if (!gz::common::exists(defaultConfig)) { - auto installedConfig = ignition::common::joinPaths( - IGNITION_GAZEBO_GUI_CONFIG_PATH, "gui.config"); + auto installedConfig = gz::common::joinPaths( + GZ_SIM_GUI_CONFIG_PATH, "gui.config"); - if (!ignition::common::createDirectories(defaultConfigDir)) + if (!gz::common::createDirectories(defaultConfigDir)) { - ignerr << "Failed to create directory [" << defaultConfigDir + gzerr << "Failed to create directory [" << defaultConfigDir << "]." << std::endl; return -1; } - if (!ignition::common::exists(installedConfig)) + if (!gz::common::exists(installedConfig)) { - ignerr << "Failed to copy installed config [" << installedConfig + gzerr << "Failed to copy installed config [" << installedConfig << "] to default config [" << defaultConfig << "]." << "(file " << installedConfig << " doesn't exist)" << std::endl; return -1; } - if (!ignition::common::copyFile(installedConfig, defaultConfig)) + if (!gz::common::copyFile(installedConfig, defaultConfig)) { - ignerr << "Failed to copy installed config [" << installedConfig + gzerr << "Failed to copy installed config [" << installedConfig << "] to default config [" << defaultConfig << "]." << std::endl; return -1; } else { - ignmsg << "Copied installed config [" << installedConfig + gzmsg << "Copied installed config [" << installedConfig << "] to default config [" << defaultConfig << "]." << std::endl; } @@ -442,7 +442,7 @@ extern "C" int runGui(const char *_guiConfig) // Also set ~/.gz/sim/ver/gui.config as the default path if (!app.LoadConfig(defaultConfig)) { - ignerr << "Failed to load config file[" << _guiConfig << "]." + gzerr << "Failed to load config file[" << _guiConfig << "]." << std::endl; return -1; } @@ -456,6 +456,6 @@ extern "C" int runGui(const char *_guiConfig) delete runner; runners.clear(); - igndbg << "Shutting down GUI" << std::endl; + gzdbg << "Shutting down GUI" << std::endl; return 0; } diff --git a/src/comms/Broker.cc b/src/comms/Broker.cc index 3a78971b88..17ea19ba07 100644 --- a/src/comms/Broker.cc +++ b/src/comms/Broker.cc @@ -30,7 +30,7 @@ #include "gz/sim/Util.hh" /// \brief Private Broker data class. -class ignition::gazebo::comms::Broker::Implementation +class gz::sim::comms::Broker::Implementation { /// \brief The message manager. public: MsgManager data; @@ -50,19 +50,19 @@ class ignition::gazebo::comms::Broker::Implementation /// \brief The current time. public: std::chrono::steady_clock::duration time{0}; - /// \brief An Ignition Transport node for communications. - public: std::unique_ptr node; + /// \brief A Gazebo Transport node for communications. + public: std::unique_ptr node; }; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace comms; ////////////////////////////////////////////////// Broker::Broker() - : dataPtr(ignition::utils::MakeUniqueImpl()) + : dataPtr(gz::utils::MakeUniqueImpl()) { - this->dataPtr->node = std::make_unique(); + this->dataPtr->node = std::make_unique(); } ////////////////////////////////////////////////// @@ -87,7 +87,7 @@ void Broker::Start() if (!this->dataPtr->node->Advertise(this->dataPtr->bindSrv, &Broker::OnBind, this)) { - ignerr << "Error advertising srv [" << this->dataPtr->bindSrv << "]" + gzerr << "Error advertising srv [" << this->dataPtr->bindSrv << "]" << std::endl; return; } @@ -96,7 +96,7 @@ void Broker::Start() if (!this->dataPtr->node->Advertise(this->dataPtr->unbindSrv, &Broker::OnUnbind, this)) { - ignerr << "Error advertising srv [" << this->dataPtr->unbindSrv << "]" + gzerr << "Error advertising srv [" << this->dataPtr->unbindSrv << "]" << std::endl; return; } @@ -105,16 +105,16 @@ void Broker::Start() if (!this->dataPtr->node->Subscribe(this->dataPtr->msgTopic, &Broker::OnMsg, this)) { - ignerr << "Error subscribing to topic [" << this->dataPtr->msgTopic << "]" + gzerr << "Error subscribing to topic [" << this->dataPtr->msgTopic << "]" << std::endl; return; } - igndbg << "Broker services:" << std::endl; - igndbg << " Bind: [" << this->dataPtr->bindSrv << "]" << std::endl; - igndbg << " Unbind: [" << this->dataPtr->unbindSrv << "]" << std::endl; - igndbg << "Broker topics:" << std::endl; - igndbg << " Incoming messages: [" << this->dataPtr->msgTopic << "]" + gzdbg << "Broker services:" << std::endl; + gzdbg << " Bind: [" << this->dataPtr->bindSrv << "]" << std::endl; + gzdbg << " Unbind: [" << this->dataPtr->unbindSrv << "]" << std::endl; + gzdbg << "Broker topics:" << std::endl; + gzdbg << " Incoming messages: [" << this->dataPtr->msgTopic << "]" << std::endl; } @@ -131,13 +131,13 @@ void Broker::SetTime(const std::chrono::steady_clock::duration &_time) } ////////////////////////////////////////////////// -bool Broker::OnBind(const ignition::msgs::StringMsg_V &_req, - ignition::msgs::Boolean &/*_rep*/) +bool Broker::OnBind(const gz::msgs::StringMsg_V &_req, + gz::msgs::Boolean &/*_rep*/) { auto count = _req.data_size(); if (count != 3) { - ignerr << "Receive incorrect number of arguments. " + gzerr << "Receive incorrect number of arguments. " << "Expecting 3 and receive " << count << std::endl; return false; } @@ -151,19 +151,19 @@ bool Broker::OnBind(const ignition::msgs::StringMsg_V &_req, if (!this->DataManager().AddSubscriber(address, model, topic)) return false; - ignmsg << "Address [" << address << "] bound to model [" << model + gzmsg << "Address [" << address << "] bound to model [" << model << "] on topic [" << topic << "]" << std::endl; return true; } ////////////////////////////////////////////////// -void Broker::OnUnbind(const ignition::msgs::StringMsg_V &_req) +void Broker::OnUnbind(const gz::msgs::StringMsg_V &_req) { auto count = _req.data_size(); if (count != 2) { - ignerr << "Received incorrect number of arguments. " + gzerr << "Received incorrect number of arguments. " << "Expecting 2 and received " << count << std::endl; return; } @@ -174,21 +174,21 @@ void Broker::OnUnbind(const ignition::msgs::StringMsg_V &_req) std::lock_guard lock(this->dataPtr->mutex); this->DataManager().RemoveSubscriber(address, topic); - ignmsg << "Address [" << address << "] unbound on topic [" + gzmsg << "Address [" << address << "] unbound on topic [" << topic << "]" << std::endl; } ////////////////////////////////////////////////// -void Broker::OnMsg(const ignition::msgs::Dataframe &_msg) +void Broker::OnMsg(const gz::msgs::Dataframe &_msg) { // Place the message in the outbound queue of the sender. - auto msgPtr = std::make_shared(_msg); + auto msgPtr = std::make_shared(_msg); std::lock_guard lock(this->dataPtr->mutex); // Stamp the time. msgPtr->mutable_header()->mutable_stamp()->CopyFrom( - gazebo::convert(this->dataPtr->time)); + sim::convert(this->dataPtr->time)); this->DataManager().AddOutbound(_msg.src_address(), msgPtr); } diff --git a/src/comms/Broker_TEST.cc b/src/comms/Broker_TEST.cc index 0f84d14254..faca02c723 100644 --- a/src/comms/Broker_TEST.cc +++ b/src/comms/Broker_TEST.cc @@ -24,8 +24,8 @@ #include "gz/sim/comms/MsgManager.hh" #include "helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; /// \brief Tests for Broker class class BrokerTest : public InternalFixture<::testing::Test> @@ -48,7 +48,7 @@ TEST_F(BrokerTest, Broker) msgs::StringMsg_V wrongReqBind; wrongReqBind.add_data("addr1"); wrongReqBind.add_data("model1"); - ignition::msgs::Boolean unused; + gz::msgs::Boolean unused; EXPECT_FALSE(broker.OnBind(wrongReqBind, unused)); allData = broker.DataManager().Data(); EXPECT_EQ(0u, allData.size()); diff --git a/src/comms/ICommsModel.cc b/src/comms/ICommsModel.cc index 01a74ee965..587d533d42 100644 --- a/src/comms/ICommsModel.cc +++ b/src/comms/ICommsModel.cc @@ -28,12 +28,12 @@ #include "gz/sim/EntityComponentManager.hh" #include "gz/sim/EventManager.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace comms; /// \brief Private ICommsModel data class. -class ignition::gazebo::comms::ICommsModel::Implementation +class gz::sim::comms::ICommsModel::Implementation { /// \brief Broker instance. public: Broker broker; @@ -48,7 +48,7 @@ class ignition::gazebo::comms::ICommsModel::Implementation ////////////////////////////////////////////////// ICommsModel::ICommsModel() - : dataPtr(ignition::utils::MakeUniqueImpl()) + : dataPtr(gz::utils::MakeUniqueImpl()) { } @@ -70,8 +70,8 @@ void ICommsModel::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void ICommsModel::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void ICommsModel::PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("ICommsModel::PreUpdate"); @@ -95,7 +95,7 @@ void ICommsModel::PreUpdate(const ignition::gazebo::UpdateInfo &_info, while (this->dataPtr->currentTime < endTime) { - ignition::gazebo::UpdateInfo info(_info); + gz::sim::UpdateInfo info(_info); info.dt = std::min(this->dataPtr->timeStep.value(), _info.dt); info.simTime = this->dataPtr->currentTime.time_since_epoch(); this->StepImpl(_info, _ecm); diff --git a/src/comms/MsgManager.cc b/src/comms/MsgManager.cc index 37575c897e..4d6ad8272a 100644 --- a/src/comms/MsgManager.cc +++ b/src/comms/MsgManager.cc @@ -26,26 +26,26 @@ #include "gz/sim/comms/MsgManager.hh" /// \brief Private MsgManager data class. -class ignition::gazebo::comms::MsgManager::Implementation +class gz::sim::comms::MsgManager::Implementation { /// \brief Buffer to store the content associated to each address. /// The key is an address. The value contains all the information associated /// to the address. public: Registry data; - /// \brief An Ignition Transport node for communications. - public: std::unique_ptr node; + /// \brief A Gazebo Transport node for communications. + public: std::unique_ptr node; }; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace comms; ////////////////////////////////////////////////// MsgManager::MsgManager() - : dataPtr(ignition::utils::MakeUniqueImpl()) + : dataPtr(gz::utils::MakeUniqueImpl()) { - this->dataPtr->node = std::make_unique(); + this->dataPtr->node = std::make_unique(); } ////////////////////////////////////////////////// @@ -58,15 +58,15 @@ bool MsgManager::AddSubscriber(const std::string &_address, { if (!it->second.modelName.empty() && it->second.modelName != _modelName) { - ignerr << "AddSubscriber() error: Address already attached to a different" + gzerr << "AddSubscriber() error: Address already attached to a different" << " model" << std::endl; return false; } } this->dataPtr->data[_address].modelName = _modelName; - ignition::transport::Node::Publisher publisher = - this->dataPtr->node->Advertise(_topic); + gz::transport::Node::Publisher publisher = + this->dataPtr->node->Advertise(_topic); this->dataPtr->data[_address].subscriptions[_topic] = publisher; return true; @@ -93,7 +93,7 @@ bool MsgManager::RemoveSubscriber(const std::string &_address, auto it = this->dataPtr->data.find(_address); if (it == this->dataPtr->data.end()) { - ignerr << "RemoveSubscriber() error: Unable to find address [" + gzerr << "RemoveSubscriber() error: Unable to find address [" << _address << "]" << std::endl; return false; } @@ -115,7 +115,7 @@ bool MsgManager::RemoveInbound(const std::string &_address, auto it = this->dataPtr->data.find(_address); if (it == this->dataPtr->data.end()) { - ignerr << "RemoveInbound() error: Unable to find address [" + gzerr << "RemoveInbound() error: Unable to find address [" << _address << "]" << std::endl; return false; } @@ -132,7 +132,7 @@ bool MsgManager::RemoveOutbound(const std::string &_address, auto it = this->dataPtr->data.find(_address); if (it == this->dataPtr->data.end()) { - ignerr << "RemoveOutbound() error: Unable to find address [" + gzerr << "RemoveOutbound() error: Unable to find address [" << _address << "]" << std::endl; return false; } diff --git a/src/comms/MsgManager_TEST.cc b/src/comms/MsgManager_TEST.cc index 5986e6ff2c..88bae0cb23 100644 --- a/src/comms/MsgManager_TEST.cc +++ b/src/comms/MsgManager_TEST.cc @@ -23,8 +23,8 @@ #include "gz/sim/comms/MsgManager.hh" #include "helpers/EnvTestFixture.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; /// \brief Tests for MsgManager class class MsgManagerTest : public InternalFixture<::testing::Test> diff --git a/src/gui/AboutDialogHandler.cc b/src/gui/AboutDialogHandler.cc index 56b63e3ef8..f5188bc604 100644 --- a/src/gui/AboutDialogHandler.cc +++ b/src/gui/AboutDialogHandler.cc @@ -21,22 +21,22 @@ #include #include -using namespace ignition; -using namespace gazebo; -using namespace gazebo::gui; +using namespace gz; +using namespace sim; +using namespace sim::gui; ///////////////////////////////////////////////// AboutDialogHandler::AboutDialogHandler() { - aboutText += std::string(IGNITION_GAZEBO_VERSION_HEADER); + aboutText += std::string(GZ_SIM_VERSION_HEADER); aboutText += "" "" "" "" "" @@ -45,9 +45,9 @@ AboutDialogHandler::AboutDialogHandler() "Tutorials:" "" "" "" diff --git a/src/gui/AboutDialogHandler.hh b/src/gui/AboutDialogHandler.hh index 876c2f6ee1..dbd3d1f500 100644 --- a/src/gui/AboutDialogHandler.hh +++ b/src/gui/AboutDialogHandler.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_ABOUTDIALOGHANDLER_HH_ -#define IGNITION_GAZEBO_GUI_ABOUTDIALOGHANDLER_HH_ +#ifndef GZ_SIM_GUI_ABOUTDIALOGHANDLER_HH_ +#define GZ_SIM_GUI_ABOUTDIALOGHANDLER_HH_ #include #include @@ -24,12 +24,12 @@ #include "gz/sim/EntityComponentManager.hh" #include "gz/sim/Export.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace gui { /// \brief Class for handling about dialog diff --git a/src/gui/Gui.cc b/src/gui/Gui.cc index 6f6533ebde..499839137d 100644 --- a/src/gui/Gui.cc +++ b/src/gui/Gui.cc @@ -31,28 +31,28 @@ #include "GuiRunner.hh" #include "PathManager.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace gui { ////////////////////////////////////////////////// -std::unique_ptr createGui( +std::unique_ptr createGui( int &_argc, char **_argv, const char *_guiConfig, const char *_defaultGuiConfig, bool _loadPluginsFromSdf, const char *_renderEngine) { - ignition::common::SignalHandler sigHandler; + gz::common::SignalHandler sigHandler; bool sigKilled = false; sigHandler.AddCallback([&](const int /*_sig*/) { sigKilled = true; }); - ignmsg << "Ignition Gazebo GUI v" << IGNITION_GAZEBO_VERSION_FULL + gzmsg << "Gazebo Sim GUI v" << GZ_SIM_VERSION_FULL << std::endl; // Set auto scaling factor for HiDPI displays @@ -62,20 +62,20 @@ std::unique_ptr createGui( } // Initialize Qt app - auto app = std::make_unique(_argc, _argv); - app->AddPluginPath(IGN_GAZEBO_GUI_PLUGIN_INSTALL_DIR); + auto app = std::make_unique(_argc, _argv); + app->AddPluginPath(GZ_SIM_GUI_PLUGIN_INSTALL_DIR); - 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 - app->Engine()->addImportPath(IGN_GAZEBO_GUI_PLUGIN_INSTALL_DIR); + app->Engine()->addImportPath(GZ_SIM_GUI_PLUGIN_INSTALL_DIR); std::string defaultGuiConfigName = "gui.config"; // Set default config file for Gazebo @@ -92,11 +92,11 @@ std::unique_ptr createGui( { defaultGuiConfigName = "playback_gui.config"; } - ignition::common::env(IGN_HOMEDIR, defaultConfig); + gz::common::env(IGN_HOMEDIR, defaultConfig); defaultConfigFolder = - ignition::common::joinPaths(defaultConfig, ".ignition", - "gazebo", IGNITION_GAZEBO_MAJOR_VERSION_STR); - defaultConfig = ignition::common::joinPaths(defaultConfigFolder, + gz::common::joinPaths(defaultConfig, ".gz", + "sim", GZ_SIM_MAJOR_VERSION_STR); + defaultConfig = gz::common::joinPaths(defaultConfigFolder, defaultGuiConfigName); } else @@ -107,13 +107,13 @@ std::unique_ptr createGui( app->SetDefaultConfigPath(defaultConfig); // Customize window - auto mainWin = app->findChild(); + auto mainWin = app->findChild(); if (_renderEngine != nullptr) { mainWin->SetRenderEngine(_renderEngine); } auto win = mainWin->QuickWindow(); - win->setProperty("title", "Gazebo"); + win->setProperty("title", "Gazebo Sim"); // Let QML files use C++ functions and properties auto context = new QQmlContext(app->Engine()->rootContext()); @@ -135,17 +135,17 @@ std::unique_ptr createGui( } else { - ignerr << "Failed to instantiate custom drawer, drawer will be empty" + gzerr << "Failed to instantiate custom drawer, drawer will be empty" << std::endl; } // Get list of worlds - ignition::transport::Node node; + gz::transport::Node node; bool executed{false}; bool result{false}; unsigned int timeout{5000}; std::string service{"/gazebo/worlds"}; - ignition::msgs::StringMsg_V worldsMsg; + gz::msgs::StringMsg_V worldsMsg; // This loop is here to allow the server time to download resources. // \todo(nkoenig) Async resource download. Search for "Async resource @@ -153,7 +153,7 @@ std::unique_ptr createGui( // resolved when this while loop can be removed. while (!sigKilled && !executed) { - igndbg << "GUI requesting list of world names. The server may be busy " + gzdbg << "GUI requesting list of world names. The server may be busy " << "downloading resources. Please be patient." << std::endl; executed = node.Request(service, timeout, worldsMsg, result); } @@ -162,9 +162,9 @@ std::unique_ptr createGui( if (!sigKilled) { if (!executed) - ignerr << "Timed out when getting world names." << std::endl; + gzerr << "Timed out when getting world names." << std::endl; else if (!result) - ignerr << "Failed to get world names." << std::endl; + gzerr << "Failed to get world names." << std::endl; } if (!executed || !result || worldsMsg.data().empty()) @@ -177,17 +177,17 @@ std::unique_ptr createGui( std::string(_guiConfig) != "_playback_") { // Use the first world name with the config file - // TODO(anyone) Most of ign-gazebo's transport API includes the world name, + // TODO(anyone) Most of gz-sim'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 << "]." + gzwarn << "Failed to load config file[" << _guiConfig << "]." << std::endl; } } @@ -202,35 +202,35 @@ std::unique_ptr createGui( // Request GUI info for each world result = false; - ignition::msgs::GUI res; + gz::msgs::GUI res; service = transport::TopicUtils::AsValidTopic("/world/" + worldName + "/gui/info"); if (service.empty()) { - ignerr << "Failed to generate valid service for world [" << worldName + gzerr << "Failed to generate valid service for world [" << worldName << "]" << std::endl; } else { - igndbg << "Requesting GUI from [" << service << "]..." << std::endl; + gzdbg << "Requesting GUI from [" << service << "]..." << std::endl; // Request and block executed = node.Request(service, timeout, res, result); if (!executed) { - ignerr << "Service call timed out for [" << service << "]" + gzerr << "Service call timed out for [" << service << "]" << std::endl; } else if (!result) { - ignerr << "Service call failed for [" << service << "]" << std::endl; + gzerr << "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 @@ -256,50 +256,50 @@ std::unique_ptr createGui( if (0 == runnerCount) { - ignerr << "Failed to start a GUI runner." << std::endl; + gzerr << "Failed to start a GUI runner." << std::endl; return nullptr; } // If no plugins have been added, load default config file - auto plugins = mainWin->findChildren(); + auto plugins = mainWin->findChildren(); if (plugins.empty()) { // Check if there's a default config file under // ~/.gz/sim and use that. If there isn't, copy // the installed file there first. - if (!ignition::common::exists(defaultConfig)) + if (!gz::common::exists(defaultConfig)) { - if (!ignition::common::exists(defaultConfigFolder)) + if (!gz::common::exists(defaultConfigFolder)) { - if (!ignition::common::createDirectories(defaultConfigFolder)) + if (!gz::common::createDirectories(defaultConfigFolder)) { - ignerr << "Failed to create the default config folder [" + gzerr << "Failed to create the default config folder [" << defaultConfigFolder << "]\n"; return nullptr; } } - auto installedConfig = ignition::common::joinPaths( - IGNITION_GAZEBO_GUI_CONFIG_PATH, defaultGuiConfigName); - if (!ignition::common::exists(installedConfig)) + auto installedConfig = gz::common::joinPaths( + GZ_SIM_GUI_CONFIG_PATH, defaultGuiConfigName); + if (!gz::common::exists(installedConfig)) { - ignerr << "Failed to copy installed config [" << installedConfig + gzerr << "Failed to copy installed config [" << installedConfig << "] to default config [" << defaultConfig << "]." << "(file " << installedConfig << " doesn't exist)" << std::endl; return nullptr; } - if (!ignition::common::copyFile(installedConfig, defaultConfig)) + if (!gz::common::copyFile(installedConfig, defaultConfig)) { - ignerr << "Failed to copy installed config [" << installedConfig + gzerr << "Failed to copy installed config [" << installedConfig << "] to default config [" << defaultConfig << "]." << std::endl; return nullptr; } else { - ignmsg << "Copied installed config [" << installedConfig + gzmsg << "Copied installed config [" << installedConfig << "] to default config [" << defaultConfig << "]." << std::endl; } @@ -308,7 +308,7 @@ std::unique_ptr createGui( // Also set ~/.gz/sim/ver/gui.config as the default path if (!app->LoadConfig(defaultConfig)) { - ignerr << "Failed to load config file[" << defaultConfig << "]." + gzerr << "Failed to load config file[" << defaultConfig << "]." << std::endl; return nullptr; } @@ -321,14 +321,14 @@ std::unique_ptr createGui( int runGui(int &_argc, char **_argv, const char *_guiConfig, const char *_renderEngine) { - auto app = gazebo::gui::createGui( + auto app = sim::gui::createGui( _argc, _argv, _guiConfig, nullptr, true, _renderEngine); if (nullptr != app) { // Run main window. // This blocks until the window is closed or we receive a SIGINT app->exec(); - igndbg << "Shutting down ign-gazebo-gui" << std::endl; + gzdbg << "Shutting down ign-gazebo-gui" << std::endl; return 0; } @@ -336,5 +336,5 @@ int runGui(int &_argc, char **_argv, const char *_guiConfig, } } // namespace gui } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/src/gui/GuiEvents.cc b/src/gui/GuiEvents.cc index 762a78393e..66684c6613 100644 --- a/src/gui/GuiEvents.cc +++ b/src/gui/GuiEvents.cc @@ -17,7 +17,7 @@ #include "gz/sim/gui/GuiEvents.hh" -class ignition::gazebo::gui::events::GuiNewRemovedEntities::Implementation +class gz::sim::gui::events::GuiNewRemovedEntities::Implementation { /// \brief Set of newly created entities public: std::set newEntities; @@ -26,7 +26,7 @@ class ignition::gazebo::gui::events::GuiNewRemovedEntities::Implementation public: std::set removedEntities; }; -class ignition::gazebo::gui::events::NewRemovedEntities::Implementation +class gz::sim::gui::events::NewRemovedEntities::Implementation { /// \brief Set of newly created entities public: std::set newEntities; @@ -35,7 +35,7 @@ class ignition::gazebo::gui::events::NewRemovedEntities::Implementation public: std::set removedEntities; }; -class ignition::gazebo::gui::events::ModelEditorAddEntity::Implementation +class gz::sim::gui::events::ModelEditorAddEntity::Implementation { /// \brief Custom data map public: QMap data; @@ -47,20 +47,20 @@ class ignition::gazebo::gui::events::ModelEditorAddEntity::Implementation public: QString type; /// \breif Parent entity. - public: ignition::gazebo::Entity parent; + public: gz::sim::Entity parent; }; -class ignition::gazebo::gui::events::VisualPlugin::Implementation +class gz::sim::gui::events::VisualPlugin::Implementation { /// \brief Entity to load the visual plugin for - public: ignition::gazebo::Entity entity; + public: gz::sim::Entity entity; /// \brief Sdf element of the visual plugin public: sdf::ElementPtr element; }; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace gui; using namespace events; @@ -110,7 +110,7 @@ const std::set &NewRemovedEntities::RemovedEntities() const ///////////////////////////////////////////////// ModelEditorAddEntity::ModelEditorAddEntity(QString _entity, QString _type, - ignition::gazebo::Entity _parent) : + gz::sim::Entity _parent) : QEvent(kType), dataPtr(utils::MakeImpl()) { this->dataPtr->entity = _entity; @@ -131,7 +131,7 @@ QString ModelEditorAddEntity::EntityType() const } ///////////////////////////////////////////////// -ignition::gazebo::Entity ModelEditorAddEntity::ParentEntity() const +gz::sim::Entity ModelEditorAddEntity::ParentEntity() const { return this->dataPtr->parent; } @@ -143,7 +143,7 @@ QMap &ModelEditorAddEntity::Data() } ///////////////////////////////////////////////// -VisualPlugin::VisualPlugin(ignition::gazebo::Entity _entity, +VisualPlugin::VisualPlugin(gz::sim::Entity _entity, const sdf::ElementPtr &_elem) : QEvent(kType), dataPtr(utils::MakeImpl()) { @@ -152,7 +152,7 @@ VisualPlugin::VisualPlugin(ignition::gazebo::Entity _entity, } ///////////////////////////////////////////////// -ignition::gazebo::Entity VisualPlugin::Entity() const +gz::sim::Entity VisualPlugin::Entity() const { return this->dataPtr->entity; } diff --git a/src/gui/GuiEvents_TEST.cc b/src/gui/GuiEvents_TEST.cc index c0b5e13378..c350956919 100644 --- a/src/gui/GuiEvents_TEST.cc +++ b/src/gui/GuiEvents_TEST.cc @@ -20,8 +20,8 @@ #include "gz/sim/test_config.hh" #include "gz/sim/gui/GuiEvents.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace gui; ///////////////////////////////////////////////// diff --git a/src/gui/GuiFileHandler.cc b/src/gui/GuiFileHandler.cc index cd18bb5b07..4ef7b55419 100644 --- a/src/gui/GuiFileHandler.cc +++ b/src/gui/GuiFileHandler.cc @@ -25,9 +25,9 @@ #include "GuiFileHandler.hh" -using namespace ignition; -using namespace gazebo; -using namespace gazebo::gui; +using namespace gz; +using namespace sim; +using namespace sim::gui; ///////////////////////////////////////////////// void GuiFileHandler::SaveWorldAs(const QString &_fileUrl, @@ -45,7 +45,7 @@ void GuiFileHandler::SaveWorldAs(const QString &_fileUrl, std::string localPath = url.toLocalFile().toStdString() + suffix; std::string service{"/gazebo/worlds"}; - ignition::msgs::StringMsg_V worldsMsg; + gz::msgs::StringMsg_V worldsMsg; bool result{false}; unsigned int timeout{5000}; @@ -74,7 +74,7 @@ void GuiFileHandler::SaveWorldAs(const QString &_fileUrl, this->node.Request(sdfGenService, req, timeout, genWorldSdf, result); if (serviceCall && result && !genWorldSdf.data().empty()) { - igndbg << "Saving world: " << worldName << " to: " << localPath << "\n"; + gzdbg << "Saving world: " << worldName << " to: " << localPath << "\n"; std::ofstream fs(localPath, std::ios::out); if (fs.is_open()) { @@ -102,11 +102,11 @@ void GuiFileHandler::SaveWorldAs(const QString &_fileUrl, if (!status) { - ignerr << statusMsg.str(); + gzerr << statusMsg.str(); } else { - ignmsg << statusMsg.str(); + gzmsg << statusMsg.str(); } emit newSaveWorldStatus(status, QString::fromStdString(statusMsg.str())); } diff --git a/src/gui/GuiFileHandler.hh b/src/gui/GuiFileHandler.hh index 815cb60646..fc4b5c591e 100644 --- a/src/gui/GuiFileHandler.hh +++ b/src/gui/GuiFileHandler.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_GUIFILEHANDLER_HH_ -#define IGNITION_GAZEBO_GUI_GUIFILEHANDLER_HH_ +#ifndef GZ_SIM_GUI_GUIFILEHANDLER_HH_ +#define GZ_SIM_GUI_GUIFILEHANDLER_HH_ #include @@ -27,12 +27,12 @@ #include "gz/sim/EntityComponentManager.hh" #include "gz/sim/Export.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace gui { /// \brief Class for handling saving and loading of SDFormat files diff --git a/src/gui/GuiRunner.cc b/src/gui/GuiRunner.cc index a930a23620..a1b8e683e4 100644 --- a/src/gui/GuiRunner.cc +++ b/src/gui/GuiRunner.cc @@ -38,18 +38,18 @@ #include "GuiRunner.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; // Register SerializedStepMap to the Qt meta type system so we can pass objects // of this type in QMetaObject::invokeMethod Q_DECLARE_METATYPE(msgs::SerializedStepMap) ///////////////////////////////////////////////// -class ignition::gazebo::GuiRunner::Implementation +class gz::sim::GuiRunner::Implementation { /// \brief Entity-component manager. - public: gazebo::EntityComponentManager ecm; + public: sim::EntityComponentManager ecm; /// \brief Transport node. public: transport::Node node{}; @@ -82,7 +82,7 @@ class ignition::gazebo::GuiRunner::Implementation public: std::mutex systemLoadMutex; /// \brief Events containing visual plugins to load - public: std::vector> + public: std::vector> visualPlugins; /// \brief Systems implementing PreUpdate @@ -119,11 +119,11 @@ GuiRunner::GuiRunner(const std::string &_worldName) // and add support for accepting uint64_t data in ign-rendering Node's // UserData object. // todo(anyone) address - // https://github.com/ignitionrobotics/ign-gazebo/issues/1134 + // https://github.com/gazebosim/gz-sim/issues/1134 // so that an offset is not required this->dataPtr->ecm.SetEntityCreateOffset(math::MAX_I32 / 2); - auto win = ignition::gui::App()->findChild(); + auto win = gz::gui::App()->findChild(); auto winWorldNames = win->property("worldNames").toStringList(); winWorldNames.append(QString::fromStdString(_worldName)); win->setProperty("worldNames", winWorldNames); @@ -132,7 +132,7 @@ GuiRunner::GuiRunner(const std::string &_worldName) _worldName + "/state"); if (this->dataPtr->stateTopic.empty()) { - ignerr << "Failed to generate valid topic for world [" << _worldName << "]" + gzerr << "Failed to generate valid topic for world [" << _worldName << "]" << std::endl; return; } @@ -142,7 +142,7 @@ GuiRunner::GuiRunner(const std::string &_worldName) return fuel_tools::fetchResource(_uri.Str()); }); - igndbg << "Requesting initial state from [" << this->dataPtr->stateTopic + gzdbg << "Requesting initial state from [" << this->dataPtr->stateTopic << "]..." << std::endl; this->RequestState(); @@ -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; @@ -184,16 +184,16 @@ bool GuiRunner::eventFilter(QObject *_obj, QEvent *_event) if (pressedPlay || pressedStepWhilePaused) req.mutable_state()->CopyFrom(this->dataPtr->ecm.State()); - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error sharing WorldControl info with the server.\n"; + gzerr << "Error sharing WorldControl info with the server.\n"; }; this->dataPtr->node.Request(this->dataPtr->controlService, req, cb); } } - else if (_event->type() == ignition::gazebo::gui::events::VisualPlugin::kType) + else if (_event->type() == gz::sim::gui::events::VisualPlugin::kType) { auto visualPluginEvent = reinterpret_cast(_event); @@ -216,13 +216,13 @@ 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); if (reqSrvValid.empty()) { - ignerr << "Failed to generate valid service [" << reqSrv << "]" + gzerr << "Failed to generate valid service [" << reqSrv << "]" << std::endl; return; } @@ -235,11 +235,11 @@ void GuiRunner::RequestState() if (!this->dataPtr->node.Advertise(reqSrv, &GuiRunner::OnStateAsyncService, this)) { - ignerr << "Failed to advertise [" << reqSrv << "]" << std::endl; + gzerr << "Failed to advertise [" << reqSrv << "]" << std::endl; } } - ignition::msgs::StringMsg req; + gz::msgs::StringMsg req; req.set_data(reqSrv); // Subscribe to periodic updates. @@ -270,7 +270,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); @@ -310,7 +310,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); @@ -359,7 +359,7 @@ void GuiRunner::LoadSystems() sysConfigure->Configure(entity, pluginElem, this->dataPtr->ecm, this->dataPtr->eventMgr); } - igndbg << "Loaded system [" << name + gzdbg << "Loaded system [" << name << "] for entity [" << entity << "] in GUI" << std::endl; } diff --git a/src/gui/GuiRunner.hh b/src/gui/GuiRunner.hh index 6834997311..669f2c2cf1 100644 --- a/src/gui/GuiRunner.hh +++ b/src/gui/GuiRunner.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_GUIRUNNER_HH_ -#define IGNITION_GAZEBO_GUI_GUIRUNNER_HH_ +#ifndef GZ_SIM_GUI_GUIRUNNER_HH_ +#define GZ_SIM_GUI_GUIRUNNER_HH_ #include @@ -28,15 +28,15 @@ #include "gz/sim/EventManager.hh" #include "gz/sim/gui/Export.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { /// \brief Responsible for running GUI systems as new states are received from /// the backend. -class IGNITION_GAZEBO_GUI_VISIBLE GuiRunner : public QObject +class GZ_GAZEBO_GUI_VISIBLE GuiRunner : public QObject { Q_OBJECT diff --git a/src/gui/Gui_TEST.cc b/src/gui/Gui_TEST.cc index b455712de2..c7c8644d82 100644 --- a/src/gui/Gui_TEST.cc +++ b/src/gui/Gui_TEST.cc @@ -33,26 +33,26 @@ int gg_argc = 1; char **gg_argv = new char *[gg_argc]; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; class GuiTest : public InternalFixture<::testing::Test> { }; ///////////////////////////////////////////////// -// https://github.com/ignitionrobotics/ign-gazebo/issues/8 -// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +// https://github.com/gazebosim/gz-sim/issues/8 +// See https://github.com/gazebosim/gz-sim/issues/1175 TEST_F(GuiTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PathManager)) { common::Console::SetVerbosity(4); - igndbg << "Start test" << std::endl; + gzdbg << "Start test" << std::endl; - ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", + gz::common::setenv("IGN_GAZEBO_RESOURCE_PATH", "/from_env:/tmp/more_env"); - ignition::common::setenv("SDF_PATH", ""); - ignition::common::setenv("IGN_FILE_PATH", ""); - igndbg << "Environment set" << std::endl; + gz::common::setenv("SDF_PATH", ""); + gz::common::setenv("IGN_FILE_PATH", ""); + gzdbg << "Environment set" << std::endl; transport::Node node; @@ -66,7 +66,7 @@ TEST_F(GuiTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PathManager)) return true; }; node.Advertise("/gazebo/worlds", worldsCb); - igndbg << "Worlds advertised" << std::endl; + gzdbg << "Worlds advertised" << std::endl; // GUI info callback bool guiInfoCalled{false}; @@ -77,7 +77,7 @@ TEST_F(GuiTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PathManager)) return true; }; node.Advertise("/world/world_name/gui/info", guiInfoCb); - igndbg << "GUI info advertised" << std::endl; + gzdbg << "GUI info advertised" << std::endl; // Resource paths callback bool pathsCalled{false}; @@ -89,12 +89,12 @@ TEST_F(GuiTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PathManager)) return true; }; node.Advertise("/gazebo/resource_paths/get", pathsCb); - igndbg << "Paths advertised" << std::endl; + gzdbg << "Paths advertised" << std::endl; - auto app = ignition::gazebo::gui::createGui( + auto app = gz::sim::gui::createGui( gg_argc, gg_argv, nullptr, nullptr, false, nullptr); EXPECT_NE(nullptr, app); - igndbg << "GUI created" << std::endl; + gzdbg << "GUI created" << std::endl; EXPECT_TRUE(worldsCalled); EXPECT_TRUE(guiInfoCalled); @@ -103,7 +103,7 @@ TEST_F(GuiTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PathManager)) // Check paths for (auto env : {"IGN_GAZEBO_RESOURCE_PATH", "SDF_PATH", "IGN_FILE_PATH"}) { - igndbg << "Checking variable [" << env << "]" << std::endl; + gzdbg << "Checking variable [" << env << "]" << std::endl; char *pathCStr = std::getenv(env); auto paths = common::Split(pathCStr, ':'); @@ -128,7 +128,7 @@ TEST_F(GuiTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PathManager)) topicCalled = true; }; node.Subscribe("/gazebo/resource_paths", topicCb); - igndbg << "Paths subscribed" << std::endl; + gzdbg << "Paths subscribed" << std::endl; // Notify new path through a topic msgs::StringMsg_V msg; @@ -149,7 +149,7 @@ TEST_F(GuiTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PathManager)) // Check paths for (auto env : {"IGN_GAZEBO_RESOURCE_PATH", "SDF_PATH", "IGN_FILE_PATH"}) { - igndbg << "Checking variable [" << env << "]" << std::endl; + gzdbg << "Checking variable [" << env << "]" << std::endl; char *pathCStr = std::getenv(env); auto paths = common::Split(pathCStr, ':'); diff --git a/src/gui/Gui_clean_exit_TEST.cc b/src/gui/Gui_clean_exit_TEST.cc index 921418f5ce..972c515eb2 100644 --- a/src/gui/Gui_clean_exit_TEST.cc +++ b/src/gui/Gui_clean_exit_TEST.cc @@ -28,7 +28,7 @@ #include "gz/sim/gui/Gui.hh" #include "gz/sim/test_config.hh" // NOLINT(build/include) -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// class GazeboDeathTest @@ -41,10 +41,10 @@ class GazeboDeathTest /// \param[in] _fileName Full path to the SDFormat file to load. void startServer(const std::string &_fileName) { - gazebo::ServerConfig config; + sim::ServerConfig config; config.SetSdfFile(_fileName); - gazebo::Server server(config); + sim::Server server(config); EXPECT_TRUE(server.Run(true, 1, true)); } @@ -54,7 +54,7 @@ void startGui() { int argc = 1; char *argv = const_cast("ign-gazebo-gui"); - EXPECT_EQ(0, gazebo::gui::runGui(argc, &argv, "", "")); + EXPECT_EQ(0, sim::gui::runGui(argc, &argv, "", "")); } ///////////////////////////////////////////////// @@ -77,7 +77,7 @@ void startBoth(const std::string &_fileName) ///////////////////////////////////////////////// /// TODO (azeey) Temporarliy disabled until -/// https://github.com/ignitionrobotics/ign-gazebo/issues/1443 is resolved +/// https://github.com/gazebosim/gz-sim/issues/1443 is resolved TEST_P(GazeboDeathTest, DISABLED_CleanExit) { std::string githubAction; diff --git a/src/gui/PathManager.cc b/src/gui/PathManager.cc index 68a4bb7d5c..a600a31687 100644 --- a/src/gui/PathManager.cc +++ b/src/gui/PathManager.cc @@ -28,9 +28,9 @@ #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; -using namespace gazebo::gui; +using namespace gz; +using namespace sim; +using namespace sim::gui; ////////////////////////////////////////////////// void onAddResourcePaths(const msgs::StringMsg_V &_msg) @@ -49,10 +49,10 @@ void onAddResourcePaths(const msgs::StringMsg_V &_res, const bool _result) { if (!_result) { - ignerr << "Failed to get resource paths through service" << std::endl; + gzerr << "Failed to get resource paths through service" << std::endl; return; } - igndbg << "Received resource paths." << std::endl; + gzdbg << "Received resource paths." << std::endl; onAddResourcePaths(_res); } @@ -63,7 +63,7 @@ PathManager::PathManager() // Trigger an initial request to get all paths from server std::string service{"/gazebo/resource_paths/get"}; - igndbg << "Requesting resource paths through [" << service << "]" + gzdbg << "Requesting resource paths through [" << service << "]" << std::endl; this->node.Request(service, onAddResourcePaths); diff --git a/src/gui/PathManager.hh b/src/gui/PathManager.hh index 0d0dd93d13..1b5b2963a4 100644 --- a/src/gui/PathManager.hh +++ b/src/gui/PathManager.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_PATHMANAGER_HH_ -#define IGNITION_GAZEBO_GUI_PATHMANAGER_HH_ +#ifndef GZ_SIM_GUI_PATHMANAGER_HH_ +#define GZ_SIM_GUI_PATHMANAGER_HH_ #include @@ -24,12 +24,12 @@ #include "gz/sim/Export.hh" #include "gz/sim/config.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace gui { /// \brief Class for handling paths and their environment variables. diff --git a/src/gui/plugins/CMakeLists.txt b/src/gui/plugins/CMakeLists.txt index 62fcf2d096..18537b0414 100644 --- a/src/gui/plugins/CMakeLists.txt +++ b/src/gui/plugins/CMakeLists.txt @@ -4,7 +4,7 @@ # [PUBLIC_LINK_LIBS ] # [PRIVATE_LINK_LIBS ]) # -# Add a gui library to Ignition Gazebo. +# Add a gui library to Gazebo. # # Required. Name of the gui library # @@ -49,7 +49,7 @@ endfunction() # [PUBLIC_LINK_LIBS ] # [PRIVATE_LINK_LIBS ]) # -# Add a gui plugin to Ignition Gazebo. +# Add a gui plugin to Gazebo. # # Required. Name of the gui plugin. # @@ -112,7 +112,7 @@ function(gz_add_gui_plugin plugin_name) endif() endif() - install (TARGETS ${plugin_name} DESTINATION ${IGNITION_GAZEBO_GUI_PLUGIN_INSTALL_DIR}) + install (TARGETS ${plugin_name} DESTINATION ${GZ_SIM_GUI_PLUGIN_INSTALL_DIR}) endfunction() add_subdirectory(modules) diff --git a/src/gui/plugins/align_tool/AlignTool.cc b/src/gui/plugins/align_tool/AlignTool.cc index 26d03c1f3d..bacddfb350 100644 --- a/src/gui/plugins/align_tool/AlignTool.cc +++ b/src/gui/plugins/align_tool/AlignTool.cc @@ -48,7 +48,7 @@ #include "AlignTool.hh" -namespace ignition::gazebo +namespace gz::sim { class AlignToolPrivate { @@ -97,8 +97,8 @@ namespace ignition::gazebo }; } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// AlignTool::AlignTool() @@ -106,8 +106,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); } @@ -121,8 +121,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); } ///////////////////////////////////////////////// @@ -166,11 +166,11 @@ void AlignTool::OnAlignConfig(const QString &_config) } else { - ignwarn << "Invalid align axis config: " << newConfig << "\n"; - ignwarn << "The valid options are:\n"; - ignwarn << " - min\n"; - ignwarn << " - mid\n"; - ignwarn << " - max\n"; + gzwarn << "Invalid align axis config: " << newConfig << "\n"; + gzwarn << "The valid options are:\n"; + gzwarn << " - min\n"; + gzwarn << " - mid\n"; + gzwarn << " - max\n"; } } @@ -201,11 +201,11 @@ void AlignTool::OnAlignAxis(const QString &_axis) } else { - ignwarn << "Invalid align axis string: " << newAxis << "\n"; - ignwarn << "The valid options are:\n"; - ignwarn << " - X\n"; - ignwarn << " - Y\n"; - ignwarn << " - Z\n"; + gzwarn << "Invalid align axis string: " << newAxis << "\n"; + gzwarn << "The valid options are:\n"; + gzwarn << " - X\n"; + gzwarn << " - Y\n"; + gzwarn << " - Z\n"; } } @@ -227,10 +227,10 @@ void AlignTool::OnAlignTarget(const QString &_target) } else { - ignwarn << "Invalid align target string: " << newTarget << "\n"; - ignwarn << "The valid options are:\n"; - ignwarn << " - first\n"; - ignwarn << " - last\n"; + gzwarn << "Invalid align target string: " << newTarget << "\n"; + gzwarn << "The valid options are:\n"; + gzwarn << " - first\n"; + gzwarn << " - last\n"; } } @@ -352,14 +352,14 @@ void AlignTool::Align() this->dataPtr->scene = rendering::sceneFromFirstRenderEngine(); // Get current list of selected entities - std::vector selectedList; - ignition::rendering::VisualPtr relativeVisual; + std::vector selectedList; + gz::rendering::VisualPtr relativeVisual; for (const auto &entityId : this->dataPtr->selectedEntities) { for (auto i = 0u; i < this->dataPtr->scene->VisualCount(); ++i) { - ignition::rendering::VisualPtr vis = + gz::rendering::VisualPtr vis = this->dataPtr->scene->VisualByIndex(i); if (!vis) continue; @@ -388,11 +388,11 @@ void AlignTool::Align() (relativeVisual = selectedList.back()); // Callback function for ignition node request - std::function cb = - [](const ignition::msgs::Boolean &/* _rep*/, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &/* _rep*/, const bool _result) { if (!_result) - ignerr << "Error setting pose" << std::endl; + gzerr << "Error setting pose" << std::endl; }; // Set service topic @@ -403,11 +403,11 @@ void AlignTool::Align() } int axisIndex = static_cast(this->dataPtr->axis); - ignition::msgs::Pose req; + gz::msgs::Pose req; - ignition::math::AxisAlignedBox targetBox = relativeVisual->BoundingBox(); - ignition::math::Vector3d targetMin = targetBox.Min(); - ignition::math::Vector3d targetMax = targetBox.Max(); + gz::math::AxisAlignedBox targetBox = relativeVisual->BoundingBox(); + gz::math::Vector3d targetMin = targetBox.Min(); + gz::math::Vector3d targetMax = targetBox.Max(); // Index math to avoid iterating through the selected node for (unsigned int i = this->dataPtr->first; @@ -417,9 +417,9 @@ void AlignTool::Align() if (!vis) continue; - ignition::math::AxisAlignedBox box = vis->BoundingBox(); - ignition::math::Vector3d min = box.Min(); - ignition::math::Vector3d max = box.Max(); + gz::math::AxisAlignedBox box = vis->BoundingBox(); + gz::math::Vector3d min = box.Min(); + gz::math::Vector3d max = box.Max(); // Check here to see if visual is top level or not, continue if not rendering::VisualPtr topLevelVis = this->TopLevelVisual( @@ -550,7 +550,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 @@ -565,10 +565,10 @@ bool AlignTool::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::EntitiesSelected::kType) + gz::sim::gui::events::EntitiesSelected::kType) { auto selectedEvent = - reinterpret_cast( + reinterpret_cast( _event); // Only update if a valid cast, the data isn't empty, and @@ -588,7 +588,7 @@ bool AlignTool::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::DeselectAllEntities::kType) + gz::sim::gui::events::DeselectAllEntities::kType) { this->dataPtr->selectedEntities.clear(); } @@ -596,5 +596,5 @@ bool AlignTool::eventFilter(QObject *_obj, QEvent *_event) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::AlignTool, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::AlignTool, + gz::gui::Plugin) diff --git a/src/gui/plugins/align_tool/AlignTool.hh b/src/gui/plugins/align_tool/AlignTool.hh index 1ff73c02ae..be479089e3 100644 --- a/src/gui/plugins/align_tool/AlignTool.hh +++ b/src/gui/plugins/align_tool/AlignTool.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_ALIGNTOOL_HH_ -#define IGNITION_GAZEBO_GUI_ALIGNTOOL_HH_ +#ifndef GZ_SIM_GUI_ALIGNTOOL_HH_ +#define GZ_SIM_GUI_ALIGNTOOL_HH_ #include @@ -24,9 +24,9 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { /// \brief Enumeration of the states within the Align Tool. enum class AlignState @@ -68,7 +68,7 @@ namespace gazebo /// ## Configuration /// \ : Set the service to receive align tool requests. class AlignTool : - public ignition::gazebo::GuiSystem + public gz::sim::GuiSystem { Q_OBJECT diff --git a/src/gui/plugins/banana_for_scale/BananaForScale.cc b/src/gui/plugins/banana_for_scale/BananaForScale.cc index a134466d00..13b9be730e 100644 --- a/src/gui/plugins/banana_for_scale/BananaForScale.cc +++ b/src/gui/plugins/banana_for_scale/BananaForScale.cc @@ -32,12 +32,12 @@ #include "gz/sim/gui/GuiEvents.hh" -namespace ignition::gazebo +namespace gz::sim { class BananaPrivate { /// \brief Fuel client - public: std::unique_ptr + public: std::unique_ptr fuelClient {nullptr}; }; @@ -49,16 +49,16 @@ const char kBanana[] = const char kBigBanana[] = "https://fuel.ignitionrobotics.org/1.0/mjcarroll/models/big banana for scale"; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// BananaForScale::BananaForScale() - : ignition::gui::Plugin(), + : gz::gui::Plugin(), dataPtr(std::make_unique()) { this->dataPtr->fuelClient = - std::make_unique(); + std::make_unique(); } ///////////////////////////////////////////////// @@ -78,35 +78,35 @@ void BananaForScale::OnMode(const QString &_mode) std::transform(modelSdfString.begin(), modelSdfString.end(), modelSdfString.begin(), ::tolower); - ignition::common::URI modelUri; + gz::common::URI modelUri; if (_mode == "banana") { - modelUri = ignition::common::URI(kBanana); + modelUri = gz::common::URI(kBanana); } else if (_mode == "bigbanana") { - modelUri = ignition::common::URI(kBigBanana); + modelUri = gz::common::URI(kBigBanana); } std::string path; std::string sdfPath; if (this->dataPtr->fuelClient->CachedModel(modelUri, path)) { - sdfPath = ignition::common::joinPaths(path, "model.sdf"); + sdfPath = gz::common::joinPaths(path, "model.sdf"); } else { std::string localPath; auto result = this->dataPtr->fuelClient->DownloadModel(modelUri, localPath); - sdfPath = ignition::common::joinPaths(localPath, "model.sdf"); + sdfPath = gz::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) +IGNITION_ADD_PLUGIN(gz::sim::BananaForScale, + 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..f49d552a41 100644 --- a/src/gui/plugins/banana_for_scale/BananaForScale.hh +++ b/src/gui/plugins/banana_for_scale/BananaForScale.hh @@ -15,21 +15,21 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_BANANA_FOR_SCALE_HH_ -#define IGNITION_GAZEBO_GUI_BANANA_FOR_SCALE_HH_ +#ifndef GZ_SIM_GUI_BANANA_FOR_SCALE_HH_ +#define GZ_SIM_GUI_BANANA_FOR_SCALE_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { 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/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 183de3a8c1..ccea924b86 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -74,7 +74,7 @@ #include "ComponentInspector.hh" #include "Pose3d.hh" -namespace ignition::gazebo +namespace gz::sim { class ComponentInspectorPrivate { @@ -117,12 +117,12 @@ namespace ignition::gazebo }; } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const msgs::Light &_data) +void gz::sim::setData(QStandardItem *_item, const msgs::Light &_data) { if (nullptr == _item) return; @@ -172,7 +172,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const msgs::Light &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, +void gz::sim::setData(QStandardItem *_item, const math::Vector3d &_data) { if (nullptr == _item) @@ -189,7 +189,7 @@ void ignition::gazebo::setData(QStandardItem *_item, ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const std::string &_data) +void gz::sim::setData(QStandardItem *_item, const std::string &_data) { if (nullptr == _item) return; @@ -202,7 +202,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const std::string &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, +void gz::sim::setData(QStandardItem *_item, const std::ostringstream &_data) { if (nullptr == _item) @@ -216,7 +216,7 @@ void ignition::gazebo::setData(QStandardItem *_item, ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const bool &_data) +void gz::sim::setData(QStandardItem *_item, const bool &_data) { if (nullptr == _item) return; @@ -228,7 +228,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const bool &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const int &_data) +void gz::sim::setData(QStandardItem *_item, const int &_data) { if (nullptr == _item) return; @@ -240,14 +240,14 @@ void ignition::gazebo::setData(QStandardItem *_item, const int &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const Entity &_data) +void gz::sim::setData(QStandardItem *_item, const Entity &_data) { setData(_item, static_cast(_data)); } ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const double &_data) +void gz::sim::setData(QStandardItem *_item, const double &_data) { if (nullptr == _item) return; @@ -259,7 +259,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const double &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const sdf::Physics &_data) +void gz::sim::setData(QStandardItem *_item, const sdf::Physics &_data) { if (nullptr == _item) return; @@ -274,7 +274,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const sdf::Physics &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, +void gz::sim::setData(QStandardItem *_item, const sdf::Material &_data) { if (nullptr == _item) @@ -307,7 +307,7 @@ void ignition::gazebo::setData(QStandardItem *_item, ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, +void gz::sim::setData(QStandardItem *_item, const math::SphericalCoordinates &_data) { if (nullptr == _item) @@ -326,7 +326,7 @@ void ignition::gazebo::setData(QStandardItem *_item, } ////////////////////////////////////////////////// -void ignition::gazebo::setUnit(QStandardItem *_item, const std::string &_unit) +void gz::sim::setUnit(QStandardItem *_item, const std::string &_unit) { if (nullptr == _item) return; @@ -355,7 +355,7 @@ ComponentsModel::ComponentsModel() : QStandardItemModel() ///////////////////////////////////////////////// QStandardItem *ComponentsModel::AddComponentType( - ignition::gazebo::ComponentTypeId _typeId) + gz::sim::ComponentTypeId _typeId) { IGN_PROFILE_THREAD_NAME("Qt thread"); IGN_PROFILE("ComponentsModel::AddComponentType"); @@ -386,7 +386,7 @@ QStandardItem *ComponentsModel::AddComponentType( ///////////////////////////////////////////////// void ComponentsModel::RemoveComponentType( - ignition::gazebo::ComponentTypeId _typeId) + gz::sim::ComponentTypeId _typeId) { IGN_PROFILE_THREAD_NAME("Qt thread"); IGN_PROFILE("ComponentsModel::RemoveComponentType"); @@ -423,7 +423,7 @@ QHash ComponentsModel::RoleNames() ComponentInspector::ComponentInspector() : GuiSystem(), dataPtr(std::make_unique()) { - qRegisterMetaType(); + qRegisterMetaType(); qRegisterMetaType("Entity"); } @@ -436,8 +436,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( @@ -552,7 +552,7 @@ void ComponentInspector::Update(const UpdateInfo &, if (nullptr == item) { - ignerr << "Failed to get item for component type [" << typeId << "]" + gzerr << "Failed to get item for component type [" << typeId << "]" << std::endl; continue; } @@ -866,7 +866,7 @@ void ComponentInspector::Update(const UpdateInfo &, } // Remove components no longer present - list items to remove - std::list itemsToRemove; + std::list itemsToRemove; for (auto itemIt : this->dataPtr->componentsModel.items) { auto typeId = itemIt.first; @@ -882,7 +882,7 @@ void ComponentInspector::Update(const UpdateInfo &, QMetaObject::invokeMethod(&this->dataPtr->componentsModel, "RemoveComponentType", Qt::QueuedConnection, - Q_ARG(ignition::gazebo::ComponentTypeId, typeId)); + Q_ARG(gz::sim::ComponentTypeId, typeId)); } } @@ -898,7 +898,7 @@ bool ComponentInspector::eventFilter(QObject *_obj, QEvent *_event) { if (!this->dataPtr->locked) { - if (_event->type() == gazebo::gui::events::EntitiesSelected::kType) + if (_event->type() == sim::gui::events::EntitiesSelected::kType) { auto event = reinterpret_cast(_event); if (event && !event->Data().empty()) @@ -907,7 +907,7 @@ bool ComponentInspector::eventFilter(QObject *_obj, QEvent *_event) } } - if (_event->type() == gazebo::gui::events::DeselectAllEntities::kType) + if (_event->type() == sim::gui::events::DeselectAllEntities::kType) { auto event = reinterpret_cast( _event); @@ -992,20 +992,20 @@ void ComponentInspector::OnLight( double _outerAngle, double _falloff, double _intensity, int _type, bool _isLightOn, bool _visualizeVisual) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error setting light configuration" << std::endl; + gzerr << "Error setting light configuration" << std::endl; }; - ignition::msgs::Light req; + gz::msgs::Light req; req.set_name(this->dataPtr->entityName); req.set_id(this->dataPtr->entity); - ignition::msgs::Set(req.mutable_diffuse(), - ignition::math::Color(_rDiffuse, _gDiffuse, _bDiffuse, _aDiffuse)); - ignition::msgs::Set(req.mutable_specular(), - ignition::math::Color(_rSpecular, _gSpecular, _bSpecular, _aSpecular)); + gz::msgs::Set(req.mutable_diffuse(), + gz::math::Color(_rDiffuse, _gDiffuse, _bDiffuse, _aDiffuse)); + gz::msgs::Set(req.mutable_specular(), + gz::math::Color(_rSpecular, _gSpecular, _bSpecular, _aSpecular)); req.set_range(_attRange); req.set_attenuation_linear(_attLinear); req.set_attenuation_constant(_attConstant); @@ -1015,11 +1015,11 @@ void ComponentInspector::OnLight( req.set_is_light_off(!_isLightOn); req.set_visualize_visual(_visualizeVisual); if (_type == 0) - req.set_type(ignition::msgs::Light::POINT); + req.set_type(gz::msgs::Light::POINT); else if (_type == 1) - req.set_type(ignition::msgs::Light::SPOT); + req.set_type(gz::msgs::Light::SPOT); else - req.set_type(ignition::msgs::Light::DIRECTIONAL); + req.set_type(gz::msgs::Light::DIRECTIONAL); if (_type == 1) // sdf::LightType::SPOT { @@ -1031,8 +1031,8 @@ void ComponentInspector::OnLight( // if sdf::LightType::SPOT || sdf::LightType::DIRECTIONAL if (_type == 1 || _type == 2) { - ignition::msgs::Set(req.mutable_direction(), - ignition::math::Vector3d(_directionX, _directionY, _directionZ)); + gz::msgs::Set(req.mutable_direction(), + gz::math::Vector3d(_directionX, _directionY, _directionZ)); } auto lightConfigService = "/world/" + this->dataPtr->worldName + @@ -1040,7 +1040,7 @@ void ComponentInspector::OnLight( lightConfigService = transport::TopicUtils::AsValidTopic(lightConfigService); if (lightConfigService.empty()) { - ignerr << "Invalid light command service topic provided" << std::endl; + gzerr << "Invalid light command service topic provided" << std::endl; return; } this->dataPtr->node.Request(lightConfigService, req, cb); @@ -1049,14 +1049,14 @@ void ComponentInspector::OnLight( ///////////////////////////////////////////////// void ComponentInspector::OnPhysics(double _stepSize, double _realTimeFactor) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error setting physics parameters" << std::endl; + gzerr << "Error setting physics parameters" << std::endl; }; - ignition::msgs::Physics req; + gz::msgs::Physics req; req.set_max_step_size(_stepSize); req.set_real_time_factor(_realTimeFactor); auto physicsCmdService = "/world/" + this->dataPtr->worldName @@ -1064,7 +1064,7 @@ void ComponentInspector::OnPhysics(double _stepSize, double _realTimeFactor) physicsCmdService = transport::TopicUtils::AsValidTopic(physicsCmdService); if (physicsCmdService.empty()) { - ignerr << "Invalid physics command service topic provided" << std::endl; + gzerr << "Invalid physics command service topic provided" << std::endl; return; } this->dataPtr->node.Request(physicsCmdService, req, cb); @@ -1120,16 +1120,16 @@ void ComponentInspector::OnMaterialColor( } else { - ignerr << "Invalid material type: " << type << std::endl; + gzerr << "Invalid material type: " << type << std::endl; return; } } - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error setting material color configuration" + gzerr << "Error setting material color configuration" << " on visual" << std::endl; }; @@ -1154,7 +1154,7 @@ void ComponentInspector::OnMaterialColor( materialCmdService = transport::TopicUtils::AsValidTopic(materialCmdService); if (materialCmdService.empty()) { - ignerr << "Invalid material command service topic provided" << std::endl; + gzerr << "Invalid material command service topic provided" << std::endl; return; } this->dataPtr->node.Request(materialCmdService, req, cb); @@ -1167,7 +1167,7 @@ void ComponentInspector::OnSphericalCoordinates(QString _surface, { if (_surface != QString("EARTH_WGS84")) { - ignerr << "Surface [" << _surface.toStdString() << "] not supported." + gzerr << "Surface [" << _surface.toStdString() << "] not supported." << std::endl; return; } @@ -1176,7 +1176,7 @@ void ComponentInspector::OnSphericalCoordinates(QString _surface, [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error setting spherical coordinates." << std::endl; + gzerr << "Error setting spherical coordinates." << std::endl; }; msgs::SphericalCoordinates req; @@ -1192,7 +1192,7 @@ void ComponentInspector::OnSphericalCoordinates(QString _surface, transport::TopicUtils::AsValidTopic(sphericalCoordsCmdService); if (sphericalCoordsCmdService.empty()) { - ignerr << "Invalid spherical coordinates service" << std::endl; + gzerr << "Invalid spherical coordinates service" << std::endl; return; } this->dataPtr->node.Request(sphericalCoordsCmdService, req, cb); @@ -1217,5 +1217,5 @@ transport::Node &ComponentInspector::TransportNode() } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::ComponentInspector, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::ComponentInspector, + gz::gui::Plugin) diff --git a/src/gui/plugins/component_inspector/ComponentInspector.hh b/src/gui/plugins/component_inspector/ComponentInspector.hh index 94db83c0f6..6707b3d4a9 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.hh +++ b/src/gui/plugins/component_inspector/ComponentInspector.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_HH_ -#define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_HH_ +#ifndef GZ_SIM_GUI_COMPONENTINSPECTOR_HH_ +#define GZ_SIM_GUI_COMPONENTINSPECTOR_HH_ #include #include @@ -36,11 +36,11 @@ #include -Q_DECLARE_METATYPE(ignition::gazebo::ComponentTypeId) +Q_DECLARE_METATYPE(gz::sim::ComponentTypeId) -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class ComponentInspectorPrivate; @@ -60,7 +60,7 @@ namespace gazebo } else { - ignwarn << "Attempting to set unsupported data type to item [" + gzwarn << "Attempting to set unsupported data type to item [" << _item->text().toStdString() << "]" << std::endl; } } @@ -154,12 +154,12 @@ namespace gazebo /// \param[in] _typeId Type of component to be added. /// \return Newly created item. public slots: QStandardItem *AddComponentType( - ignition::gazebo::ComponentTypeId _typeId); + gz::sim::ComponentTypeId _typeId); /// \brief Remove a component type from the inspector. /// \param[in] _typeId Type of component to be removed. public slots: void RemoveComponentType( - ignition::gazebo::ComponentTypeId _typeId); + gz::sim::ComponentTypeId _typeId); /// \brief Keep track of items in the tree, according to type ID. public: std::map items; @@ -169,7 +169,7 @@ namespace gazebo /// /// ## Configuration /// None - class ComponentInspector : public gazebo::GuiSystem + class ComponentInspector : public sim::GuiSystem { Q_OBJECT diff --git a/src/gui/plugins/component_inspector/Pose3d.cc b/src/gui/plugins/component_inspector/Pose3d.cc index d1095fec9b..501fef61f4 100644 --- a/src/gui/plugins/component_inspector/Pose3d.cc +++ b/src/gui/plugins/component_inspector/Pose3d.cc @@ -22,8 +22,8 @@ #include "Pose3d.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace inspector; ///////////////////////////////////////////////// @@ -51,7 +51,7 @@ void Pose3d::OnPose(double _x, double _y, double _z, double _roll, [](const msgs::Boolean &, const bool _result) { if (!_result) - ignerr << "Error setting pose" << std::endl; + gzerr << "Error setting pose" << std::endl; }; msgs::Pose req; diff --git a/src/gui/plugins/component_inspector/Pose3d.hh b/src/gui/plugins/component_inspector/Pose3d.hh index 368c0f70d5..534793560e 100644 --- a/src/gui/plugins/component_inspector/Pose3d.hh +++ b/src/gui/plugins/component_inspector/Pose3d.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_POSE3D_HH_ -#define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_POSE3D_HH_ +#ifndef GZ_SIM_GUI_COMPONENTINSPECTOR_POSE3D_HH_ +#define GZ_SIM_GUI_COMPONENTINSPECTOR_POSE3D_HH_ #include @@ -29,9 +29,9 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class ComponentInspector; namespace inspector diff --git a/src/gui/plugins/component_inspector/Types.hh b/src/gui/plugins/component_inspector/Types.hh index 0ec0e59890..3625eb189a 100644 --- a/src/gui/plugins/component_inspector/Types.hh +++ b/src/gui/plugins/component_inspector/Types.hh @@ -15,16 +15,16 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_TYPES_HH_ -#define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_TYPES_HH_ +#ifndef GZ_SIM_GUI_COMPONENTINSPECTOR_TYPES_HH_ +#define GZ_SIM_GUI_COMPONENTINSPECTOR_TYPES_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace inspector { diff --git a/src/gui/plugins/component_inspector_editor/AirPressure.cc b/src/gui/plugins/component_inspector_editor/AirPressure.cc index 65d3b10cf8..b3b873fb02 100644 --- a/src/gui/plugins/component_inspector_editor/AirPressure.cc +++ b/src/gui/plugins/component_inspector_editor/AirPressure.cc @@ -24,8 +24,8 @@ #include "ComponentInspectorEditor.hh" #include "Types.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// AirPressure::AirPressure(ComponentInspectorEditor *_inspector) @@ -64,7 +64,7 @@ Q_INVOKABLE void AirPressure::OnAirPressureNoise( double _stdDevBias, double _dynamicBiasStdDev, double _dynamicBiasCorrelationTime) { - ignition::gazebo::UpdateCallback cb = + gz::sim::UpdateCallback cb = [=](EntityComponentManager &_ecm) { auto comp = _ecm.Component( @@ -82,11 +82,11 @@ Q_INVOKABLE void AirPressure::OnAirPressureNoise( airpressure->SetPressureNoise(noise); } else - ignerr << "Unable to get the air pressure data.\n"; + gzerr << "Unable to get the air pressure data.\n"; } else { - ignerr << "Unable to get the air pressure component.\n"; + gzerr << "Unable to get the air pressure component.\n"; } }; this->inspector->AddUpdateCallback(cb); @@ -96,7 +96,7 @@ Q_INVOKABLE void AirPressure::OnAirPressureNoise( Q_INVOKABLE void AirPressure::OnAirPressureReferenceAltitude( double _referenceAltitude) { - ignition::gazebo::UpdateCallback cb = + gz::sim::UpdateCallback cb = [=](EntityComponentManager &_ecm) { auto comp = _ecm.Component( @@ -109,11 +109,11 @@ Q_INVOKABLE void AirPressure::OnAirPressureReferenceAltitude( airpressure->SetReferenceAltitude(_referenceAltitude); } else - ignerr << "Unable to get the air pressure data.\n"; + gzerr << "Unable to get the air pressure data.\n"; } else { - ignerr << "Unable to get the air pressure component.\n"; + gzerr << "Unable to get the air pressure component.\n"; } }; this->inspector->AddUpdateCallback(cb); diff --git a/src/gui/plugins/component_inspector_editor/AirPressure.hh b/src/gui/plugins/component_inspector_editor/AirPressure.hh index f7e5e2a5ef..ba72252564 100644 --- a/src/gui/plugins/component_inspector_editor/AirPressure.hh +++ b/src/gui/plugins/component_inspector_editor/AirPressure.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_AIRPRESSURE_HH_ -#define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_AIRPRESSURE_HH_ +#ifndef GZ_SIM_GUI_COMPONENTINSPECTOR_AIRPRESSURE_HH_ +#define GZ_SIM_GUI_COMPONENTINSPECTOR_AIRPRESSURE_HH_ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class ComponentInspectorEditor; diff --git a/src/gui/plugins/component_inspector_editor/Altimeter.cc b/src/gui/plugins/component_inspector_editor/Altimeter.cc index 672b617fa3..793b7d716b 100644 --- a/src/gui/plugins/component_inspector_editor/Altimeter.cc +++ b/src/gui/plugins/component_inspector_editor/Altimeter.cc @@ -23,8 +23,8 @@ #include "ComponentInspectorEditor.hh" #include "Types.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// Altimeter::Altimeter(ComponentInspectorEditor *_inspector) @@ -68,7 +68,7 @@ Q_INVOKABLE void Altimeter::OnAltimeterPositionNoise( double _stdDevBias, double _dynamicBiasStdDev, double _dynamicBiasCorrelationTime) { - ignition::gazebo::UpdateCallback cb = + gz::sim::UpdateCallback cb = [=](EntityComponentManager &_ecm) { auto comp = _ecm.Component( @@ -86,11 +86,11 @@ Q_INVOKABLE void Altimeter::OnAltimeterPositionNoise( altimeter->SetVerticalPositionNoise(noise); } else - ignerr << "Unable to get the altimeter data.\n"; + gzerr << "Unable to get the altimeter data.\n"; } else { - ignerr << "Unable to get the altimeter component.\n"; + gzerr << "Unable to get the altimeter component.\n"; } }; this->inspector->AddUpdateCallback(cb); @@ -102,7 +102,7 @@ Q_INVOKABLE void Altimeter::OnAltimeterVelocityNoise( double _stdDevBias, double _dynamicBiasStdDev, double _dynamicBiasCorrelationTime) { - ignition::gazebo::UpdateCallback cb = + gz::sim::UpdateCallback cb = [=](EntityComponentManager &_ecm) { auto comp = _ecm.Component( @@ -120,11 +120,11 @@ Q_INVOKABLE void Altimeter::OnAltimeterVelocityNoise( altimeter->SetVerticalVelocityNoise(noise); } else - ignerr << "Unable to get the altimeter data.\n"; + gzerr << "Unable to get the altimeter data.\n"; } else { - ignerr << "Unable to get the altimeter component.\n"; + gzerr << "Unable to get the altimeter component.\n"; } }; this->inspector->AddUpdateCallback(cb); diff --git a/src/gui/plugins/component_inspector_editor/Altimeter.hh b/src/gui/plugins/component_inspector_editor/Altimeter.hh index a55a7f6090..a36308cdba 100644 --- a/src/gui/plugins/component_inspector_editor/Altimeter.hh +++ b/src/gui/plugins/component_inspector_editor/Altimeter.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_ALTIMETER_HH_ -#define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_ALTIMETER_HH_ +#ifndef GZ_SIM_GUI_COMPONENTINSPECTOR_ALTIMETER_HH_ +#define GZ_SIM_GUI_COMPONENTINSPECTOR_ALTIMETER_HH_ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class ComponentInspectorEditor; diff --git a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc index 6aacd3b4dc..c86fdf430e 100644 --- a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc +++ b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc @@ -89,7 +89,7 @@ #include "ModelEditor.hh" #include "Pose3d.hh" -namespace ignition::gazebo +namespace gz::sim { class ComponentInspectorEditorPrivate { @@ -133,25 +133,25 @@ namespace ignition::gazebo public: ModelEditor modelEditor; /// \brief Air pressure sensor inspector elements - public: std::unique_ptr airPressure; + public: std::unique_ptr airPressure; /// \brief Altimeter sensor inspector elements - public: std::unique_ptr altimeter; + public: std::unique_ptr altimeter; /// \brief Imu inspector elements - public: std::unique_ptr imu; + public: std::unique_ptr imu; /// \brief Joint inspector elements - public: std::unique_ptr joint; + public: std::unique_ptr joint; /// \brief Lidar inspector elements - public: std::unique_ptr lidar; + public: std::unique_ptr lidar; /// \brief Magnetometer inspector elements - public: std::unique_ptr magnetometer; + public: std::unique_ptr magnetometer; /// \brief Pose inspector elements - public: std::unique_ptr pose3d; + public: std::unique_ptr pose3d; /// \brief Set of callbacks to execute during the Update function. public: std::vector< @@ -162,12 +162,12 @@ namespace ignition::gazebo }; } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const msgs::Light &_data) +void gz::sim::setData(QStandardItem *_item, const msgs::Light &_data) { if (nullptr == _item) return; @@ -215,7 +215,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const msgs::Light &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, +void gz::sim::setData(QStandardItem *_item, const math::Vector3d &_data) { if (nullptr == _item) @@ -232,7 +232,7 @@ void ignition::gazebo::setData(QStandardItem *_item, ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const std::string &_data) +void gz::sim::setData(QStandardItem *_item, const std::string &_data) { if (nullptr == _item) return; @@ -245,7 +245,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const std::string &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, +void gz::sim::setData(QStandardItem *_item, const std::ostringstream &_data) { if (nullptr == _item) @@ -259,7 +259,7 @@ void ignition::gazebo::setData(QStandardItem *_item, ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const bool &_data) +void gz::sim::setData(QStandardItem *_item, const bool &_data) { if (nullptr == _item) return; @@ -271,7 +271,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const bool &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const int &_data) +void gz::sim::setData(QStandardItem *_item, const int &_data) { if (nullptr == _item) return; @@ -283,14 +283,14 @@ void ignition::gazebo::setData(QStandardItem *_item, const int &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const Entity &_data) +void gz::sim::setData(QStandardItem *_item, const Entity &_data) { setData(_item, static_cast(_data)); } ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const double &_data) +void gz::sim::setData(QStandardItem *_item, const double &_data) { if (nullptr == _item) return; @@ -302,7 +302,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const double &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const sdf::Physics &_data) +void gz::sim::setData(QStandardItem *_item, const sdf::Physics &_data) { if (nullptr == _item) return; @@ -317,7 +317,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const sdf::Physics &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, +void gz::sim::setData(QStandardItem *_item, const sdf::Material &_data) { if (nullptr == _item) @@ -350,7 +350,7 @@ void ignition::gazebo::setData(QStandardItem *_item, ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, +void gz::sim::setData(QStandardItem *_item, const math::SphericalCoordinates &_data) { if (nullptr == _item) @@ -369,7 +369,7 @@ void ignition::gazebo::setData(QStandardItem *_item, } ////////////////////////////////////////////////// -void ignition::gazebo::setUnit(QStandardItem *_item, const std::string &_unit) +void gz::sim::setUnit(QStandardItem *_item, const std::string &_unit) { if (nullptr == _item) return; @@ -398,7 +398,7 @@ ComponentsModel::ComponentsModel() : QStandardItemModel() ///////////////////////////////////////////////// QStandardItem *ComponentsModel::AddComponentType( - ignition::gazebo::ComponentTypeId _typeId) + gz::sim::ComponentTypeId _typeId) { IGN_PROFILE_THREAD_NAME("Qt thread"); IGN_PROFILE("ComponentsModel::AddComponentType"); @@ -429,7 +429,7 @@ QStandardItem *ComponentsModel::AddComponentType( ///////////////////////////////////////////////// void ComponentsModel::RemoveComponentType( - ignition::gazebo::ComponentTypeId _typeId) + gz::sim::ComponentTypeId _typeId) { IGN_PROFILE_THREAD_NAME("Qt thread"); IGN_PROFILE("ComponentsModel::RemoveComponentType"); @@ -466,7 +466,7 @@ QHash ComponentsModel::RoleNames() ComponentInspectorEditor::ComponentInspectorEditor() : GuiSystem(), dataPtr(std::make_unique()) { - qRegisterMetaType(); + qRegisterMetaType(); qRegisterMetaType("Entity"); } @@ -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( @@ -550,7 +550,7 @@ void ComponentInspectorEditor::Update(const UpdateInfo &_info, _ecm.EachNoCache< components::Name, components::Link, - components::ParentEntity>([&](const ignition::gazebo::Entity &, + components::ParentEntity>([&](const gz::sim::Entity &, const components::Name *_name, const components::Link *, const components::ParentEntity *_parent) -> bool @@ -632,7 +632,7 @@ void ComponentInspectorEditor::Update(const UpdateInfo &_info, if (nullptr == item) { - ignerr << "Failed to get item for component type [" << typeId << "]" + gzerr << "Failed to get item for component type [" << typeId << "]" << std::endl; continue; } @@ -953,7 +953,7 @@ void ComponentInspectorEditor::Update(const UpdateInfo &_info, } // Remove components no longer present - list items to remove - std::list itemsToRemove; + std::list itemsToRemove; for (auto itemIt : this->dataPtr->componentsModel.items) { auto typeId = itemIt.first; @@ -969,7 +969,7 @@ void ComponentInspectorEditor::Update(const UpdateInfo &_info, QMetaObject::invokeMethod(&this->dataPtr->componentsModel, "RemoveComponentType", Qt::QueuedConnection, - Q_ARG(ignition::gazebo::ComponentTypeId, typeId)); + Q_ARG(gz::sim::ComponentTypeId, typeId)); } this->dataPtr->modelEditor.Update(_info, _ecm); @@ -998,7 +998,7 @@ bool ComponentInspectorEditor::eventFilter(QObject *_obj, QEvent *_event) { if (!this->dataPtr->locked) { - if (_event->type() == gazebo::gui::events::EntitiesSelected::kType) + if (_event->type() == sim::gui::events::EntitiesSelected::kType) { auto event = reinterpret_cast(_event); if (event && !event->Data().empty()) @@ -1007,7 +1007,7 @@ bool ComponentInspectorEditor::eventFilter(QObject *_obj, QEvent *_event) } } - if (_event->type() == gazebo::gui::events::DeselectAllEntities::kType) + if (_event->type() == sim::gui::events::DeselectAllEntities::kType) { auto event = reinterpret_cast( _event); @@ -1029,7 +1029,7 @@ Entity ComponentInspectorEditor::GetEntity() const } ///////////////////////////////////////////////// -void ComponentInspectorEditor::SetEntity(const gazebo::Entity &_entity) +void ComponentInspectorEditor::SetEntity(const sim::Entity &_entity) { // If nothing is selected, display world properties if (_entity == kNullEntity) @@ -1107,20 +1107,20 @@ void ComponentInspectorEditor::OnLight( double _directionY, double _directionZ, double _innerAngle, double _outerAngle, double _falloff, double _intensity, int _type) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error setting light configuration" << std::endl; + gzerr << "Error setting light configuration" << std::endl; }; - ignition::msgs::Light req; + gz::msgs::Light req; req.set_name(this->dataPtr->entityName); req.set_id(this->dataPtr->entity); - ignition::msgs::Set(req.mutable_diffuse(), - ignition::math::Color(_rDiffuse, _gDiffuse, _bDiffuse, _aDiffuse)); - ignition::msgs::Set(req.mutable_specular(), - ignition::math::Color(_rSpecular, _gSpecular, _bSpecular, _aSpecular)); + gz::msgs::Set(req.mutable_diffuse(), + gz::math::Color(_rDiffuse, _gDiffuse, _bDiffuse, _aDiffuse)); + gz::msgs::Set(req.mutable_specular(), + gz::math::Color(_rSpecular, _gSpecular, _bSpecular, _aSpecular)); req.set_range(_attRange); req.set_attenuation_linear(_attLinear); req.set_attenuation_constant(_attConstant); @@ -1128,11 +1128,11 @@ void ComponentInspectorEditor::OnLight( req.set_cast_shadows(_castShadows); req.set_intensity(_intensity); if (_type == 0) - req.set_type(ignition::msgs::Light::POINT); + req.set_type(gz::msgs::Light::POINT); else if (_type == 1) - req.set_type(ignition::msgs::Light::SPOT); + req.set_type(gz::msgs::Light::SPOT); else - req.set_type(ignition::msgs::Light::DIRECTIONAL); + req.set_type(gz::msgs::Light::DIRECTIONAL); if (_type == 1) // sdf::LightType::SPOT { @@ -1144,8 +1144,8 @@ void ComponentInspectorEditor::OnLight( // if sdf::LightType::SPOT || sdf::LightType::DIRECTIONAL if (_type == 1 || _type == 2) { - ignition::msgs::Set(req.mutable_direction(), - ignition::math::Vector3d(_directionX, _directionY, _directionZ)); + gz::msgs::Set(req.mutable_direction(), + gz::math::Vector3d(_directionX, _directionY, _directionZ)); } auto lightConfigService = "/world/" + this->dataPtr->worldName + @@ -1153,7 +1153,7 @@ void ComponentInspectorEditor::OnLight( lightConfigService = transport::TopicUtils::AsValidTopic(lightConfigService); if (lightConfigService.empty()) { - ignerr << "Invalid light command service topic provided" << std::endl; + gzerr << "Invalid light command service topic provided" << std::endl; return; } this->dataPtr->node.Request(lightConfigService, req, cb); @@ -1163,14 +1163,14 @@ void ComponentInspectorEditor::OnLight( void ComponentInspectorEditor::OnPhysics(double _stepSize, double _realTimeFactor) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error setting physics parameters" << std::endl; + gzerr << "Error setting physics parameters" << std::endl; }; - ignition::msgs::Physics req; + gz::msgs::Physics req; req.set_max_step_size(_stepSize); req.set_real_time_factor(_realTimeFactor); auto physicsCmdService = "/world/" + this->dataPtr->worldName @@ -1178,7 +1178,7 @@ void ComponentInspectorEditor::OnPhysics(double _stepSize, physicsCmdService = transport::TopicUtils::AsValidTopic(physicsCmdService); if (physicsCmdService.empty()) { - ignerr << "Invalid physics command service topic provided" << std::endl; + gzerr << "Invalid physics command service topic provided" << std::endl; return; } this->dataPtr->node.Request(physicsCmdService, req, cb); @@ -1234,16 +1234,16 @@ void ComponentInspectorEditor::OnMaterialColor( } else { - ignerr << "Invalid material type: " << type << std::endl; + gzerr << "Invalid material type: " << type << std::endl; return; } } - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error setting material color configuration" + gzerr << "Error setting material color configuration" << " on visual" << std::endl; }; @@ -1268,7 +1268,7 @@ void ComponentInspectorEditor::OnMaterialColor( materialCmdService = transport::TopicUtils::AsValidTopic(materialCmdService); if (materialCmdService.empty()) { - ignerr << "Invalid material command service topic provided" << std::endl; + gzerr << "Invalid material command service topic provided" << std::endl; return; } this->dataPtr->node.Request(materialCmdService, req, cb); @@ -1281,7 +1281,7 @@ void ComponentInspectorEditor::OnSphericalCoordinates(QString _surface, { if (_surface != QString("EARTH_WGS84")) { - ignerr << "Surface [" << _surface.toStdString() << "] not supported." + gzerr << "Surface [" << _surface.toStdString() << "] not supported." << std::endl; return; } @@ -1290,7 +1290,7 @@ void ComponentInspectorEditor::OnSphericalCoordinates(QString _surface, [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error setting spherical coordinates." << std::endl; + gzerr << "Error setting spherical coordinates." << std::endl; }; msgs::SphericalCoordinates req; @@ -1306,7 +1306,7 @@ void ComponentInspectorEditor::OnSphericalCoordinates(QString _surface, transport::TopicUtils::AsValidTopic(sphericalCoordsCmdService); if (sphericalCoordsCmdService.empty()) { - ignerr << "Invalid spherical coordinates service" << std::endl; + gzerr << "Invalid spherical coordinates service" << std::endl; return; } this->dataPtr->node.Request(sphericalCoordsCmdService, req, cb); @@ -1345,11 +1345,11 @@ void ComponentInspectorEditor::OnAddEntity(const QString &_entity, { // currently just assumes parent is the model // todo(anyone) support adding visuals / collisions / sensors to links - ignition::gazebo::gui::events::ModelEditorAddEntity addEntityEvent( + gz::sim::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); } @@ -1358,14 +1358,14 @@ void ComponentInspectorEditor::OnAddJoint(const QString &_jointType, const QString &_parentLink, const QString &_childLink) { - ignition::gazebo::gui::events::ModelEditorAddEntity addEntityEvent( + gz::sim::gui::events::ModelEditorAddEntity addEntityEvent( _jointType, "joint", this->dataPtr->entity); 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); } @@ -1386,17 +1386,17 @@ void ComponentInspectorEditor::OnLoadMesh(const QString &_entity, return; } - ignition::gazebo::gui::events::ModelEditorAddEntity addEntityEvent( + gz::sim::gui::events::ModelEditorAddEntity addEntityEvent( _entity, _type, this->dataPtr->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) +IGNITION_ADD_PLUGIN(gz::sim::ComponentInspectorEditor, + gz::gui::Plugin) diff --git a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.hh b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.hh index a68c48f47e..b7817152ad 100644 --- a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.hh +++ b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_COMPONENTINSPECTOREDITOR_HH_ -#define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOREDITOR_HH_ +#ifndef GZ_SIM_GUI_COMPONENTINSPECTOREDITOR_HH_ +#define GZ_SIM_GUI_COMPONENTINSPECTOREDITOR_HH_ #include #include @@ -35,11 +35,11 @@ #include #include "Types.hh" -Q_DECLARE_METATYPE(ignition::gazebo::ComponentTypeId) +Q_DECLARE_METATYPE(gz::sim::ComponentTypeId) -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class ComponentInspectorEditorPrivate; @@ -59,7 +59,7 @@ namespace gazebo } else { - ignwarn << "Attempting to set unsupported data type to item [" + gzwarn << "Attempting to set unsupported data type to item [" << _item->text().toStdString() << "]" << std::endl; } } @@ -152,12 +152,12 @@ namespace gazebo /// \param[in] _typeId Type of component to be added. /// \return Newly created item. public slots: QStandardItem *AddComponentType( - ignition::gazebo::ComponentTypeId _typeId); + gz::sim::ComponentTypeId _typeId); /// \brief Remove a component type from the inspector. /// \param[in] _typeId Type of component to be removed. public slots: void RemoveComponentType( - ignition::gazebo::ComponentTypeId _typeId); + gz::sim::ComponentTypeId _typeId); /// \brief Keep track of items in the tree, according to type ID. public: std::map items; @@ -167,7 +167,7 @@ namespace gazebo /// /// ## Configuration /// None - class ComponentInspectorEditor : public gazebo::GuiSystem + class ComponentInspectorEditor : public sim::GuiSystem { Q_OBJECT @@ -335,7 +335,7 @@ namespace gazebo /// \brief Set the entity currently inspected. /// \param[in] _entity Entity ID. - public: Q_INVOKABLE void SetEntity(const gazebo::Entity &_entity); + public: Q_INVOKABLE void SetEntity(const sim::Entity &_entity); /// \brief Notify that entity has changed. signals: void EntityChanged(); diff --git a/src/gui/plugins/component_inspector_editor/Imu.cc b/src/gui/plugins/component_inspector_editor/Imu.cc index 5a2b4beb04..df5805265e 100644 --- a/src/gui/plugins/component_inspector_editor/Imu.cc +++ b/src/gui/plugins/component_inspector_editor/Imu.cc @@ -24,8 +24,8 @@ #include "Imu.hh" #include "Types.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// Imu::Imu(ComponentInspectorEditor *_inspector) @@ -99,7 +99,7 @@ Q_INVOKABLE void Imu::OnLinearAccelerationXNoise( double _stdDevBias, double _dynamicBiasStdDev, double _dynamicBiasCorrelationTime) { - ignition::gazebo::UpdateCallback cb = + gz::sim::UpdateCallback cb = [=](EntityComponentManager &_ecm) { auto comp = _ecm.Component( @@ -117,11 +117,11 @@ Q_INVOKABLE void Imu::OnLinearAccelerationXNoise( imu->SetLinearAccelerationXNoise(noise); } else - ignerr << "Unable to get the imu linear acceleration x noise data.\n"; + gzerr << "Unable to get the imu linear acceleration x noise data.\n"; } else { - ignerr << "Unable to get the imu component.\n"; + gzerr << "Unable to get the imu component.\n"; } }; this->inspector->AddUpdateCallback(cb); @@ -133,7 +133,7 @@ Q_INVOKABLE void Imu::OnLinearAccelerationYNoise( double _stdDevBias, double _dynamicBiasStdDev, double _dynamicBiasCorrelationTime) { - ignition::gazebo::UpdateCallback cb = + gz::sim::UpdateCallback cb = [=](EntityComponentManager &_ecm) { auto comp = _ecm.Component( @@ -151,11 +151,11 @@ Q_INVOKABLE void Imu::OnLinearAccelerationYNoise( imu->SetLinearAccelerationYNoise(noise); } else - ignerr << "Unable to get the imu linear acceleration y noise data.\n"; + gzerr << "Unable to get the imu linear acceleration y noise data.\n"; } else { - ignerr << "Unable to get the imu component.\n"; + gzerr << "Unable to get the imu component.\n"; } }; this->inspector->AddUpdateCallback(cb); @@ -167,7 +167,7 @@ Q_INVOKABLE void Imu::OnLinearAccelerationZNoise( double _stdDevBias, double _dynamicBiasStdDev, double _dynamicBiasCorrelationTime) { - ignition::gazebo::UpdateCallback cb = + gz::sim::UpdateCallback cb = [=](EntityComponentManager &_ecm) { auto comp = _ecm.Component( @@ -185,11 +185,11 @@ Q_INVOKABLE void Imu::OnLinearAccelerationZNoise( imu->SetLinearAccelerationZNoise(noise); } else - ignerr << "Unable to get the imu linear acceleration z noise data.\n"; + gzerr << "Unable to get the imu linear acceleration z noise data.\n"; } else { - ignerr << "Unable to get the imu component.\n"; + gzerr << "Unable to get the imu component.\n"; } }; this->inspector->AddUpdateCallback(cb); @@ -201,7 +201,7 @@ Q_INVOKABLE void Imu::OnAngularVelocityXNoise( double _stdDevBias, double _dynamicBiasStdDev, double _dynamicBiasCorrelationTime) { - ignition::gazebo::UpdateCallback cb = + gz::sim::UpdateCallback cb = [=](EntityComponentManager &_ecm) { auto comp = _ecm.Component( @@ -219,11 +219,11 @@ Q_INVOKABLE void Imu::OnAngularVelocityXNoise( imu->SetAngularVelocityXNoise(noise); } else - ignerr << "Unable to get the imu angular velocity x noise data.\n"; + gzerr << "Unable to get the imu angular velocity x noise data.\n"; } else { - ignerr << "Unable to get the imu component.\n"; + gzerr << "Unable to get the imu component.\n"; } }; this->inspector->AddUpdateCallback(cb); @@ -235,7 +235,7 @@ Q_INVOKABLE void Imu::OnAngularVelocityYNoise( double _stdDevBias, double _dynamicBiasStdDev, double _dynamicBiasCorrelationTime) { - ignition::gazebo::UpdateCallback cb = + gz::sim::UpdateCallback cb = [=](EntityComponentManager &_ecm) { auto comp = _ecm.Component( @@ -253,11 +253,11 @@ Q_INVOKABLE void Imu::OnAngularVelocityYNoise( imu->SetAngularVelocityYNoise(noise); } else - ignerr << "Unable to get the imu angular velocity y noise data.\n"; + gzerr << "Unable to get the imu angular velocity y noise data.\n"; } else { - ignerr << "Unable to get the imu component.\n"; + gzerr << "Unable to get the imu component.\n"; } }; this->inspector->AddUpdateCallback(cb); @@ -269,7 +269,7 @@ Q_INVOKABLE void Imu::OnAngularVelocityZNoise( double _stdDevBias, double _dynamicBiasStdDev, double _dynamicBiasCorrelationTime) { - ignition::gazebo::UpdateCallback cb = + gz::sim::UpdateCallback cb = [=](EntityComponentManager &_ecm) { auto comp = _ecm.Component( @@ -287,11 +287,11 @@ Q_INVOKABLE void Imu::OnAngularVelocityZNoise( imu->SetAngularVelocityZNoise(noise); } else - ignerr << "Unable to get the imu angular velocity z noise data.\n"; + gzerr << "Unable to get the imu angular velocity z noise data.\n"; } else { - ignerr << "Unable to get the imu component.\n"; + gzerr << "Unable to get the imu component.\n"; } }; this->inspector->AddUpdateCallback(cb); diff --git a/src/gui/plugins/component_inspector_editor/Imu.hh b/src/gui/plugins/component_inspector_editor/Imu.hh index 210dc17370..b8e4d6671d 100644 --- a/src/gui/plugins/component_inspector_editor/Imu.hh +++ b/src/gui/plugins/component_inspector_editor/Imu.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_IMU_HH_ -#define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_IMU_HH_ +#ifndef GZ_SIM_GUI_COMPONENTINSPECTOR_IMU_HH_ +#define GZ_SIM_GUI_COMPONENTINSPECTOR_IMU_HH_ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class ComponentInspectorEditor; diff --git a/src/gui/plugins/component_inspector_editor/JointType.cc b/src/gui/plugins/component_inspector_editor/JointType.cc index 25191b0303..67710ea5ed 100644 --- a/src/gui/plugins/component_inspector_editor/JointType.cc +++ b/src/gui/plugins/component_inspector_editor/JointType.cc @@ -26,8 +26,8 @@ #include "ComponentInspectorEditor.hh" #include "Types.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// JointType::JointType(ComponentInspectorEditor *_inspector) @@ -77,7 +77,7 @@ JointType::JointType(ComponentInspectorEditor *_inspector) ///////////////////////////////////////////////// Q_INVOKABLE void JointType::OnJointType(QString _jointType) { - ignition::gazebo::UpdateCallback cb = + gz::sim::UpdateCallback cb = [=](EntityComponentManager &_ecm) { components::JointType *comp = @@ -113,11 +113,11 @@ Q_INVOKABLE void JointType::OnJointType(QString _jointType) } else if (!comp) { - ignerr << "Unable to get the joint type component.\n"; + gzerr << "Unable to get the joint type component.\n"; } else { - ignerr << "Unable to get the joint's parent entity component.\n"; + gzerr << "Unable to get the joint's parent entity component.\n"; } }; this->inspector->AddUpdateCallback(cb); diff --git a/src/gui/plugins/component_inspector_editor/JointType.hh b/src/gui/plugins/component_inspector_editor/JointType.hh index b37d4d4968..0ae8ed399a 100644 --- a/src/gui/plugins/component_inspector_editor/JointType.hh +++ b/src/gui/plugins/component_inspector_editor/JointType.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_JOINT_HH_ -#define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_JOINT_HH_ +#ifndef GZ_SIM_GUI_COMPONENTINSPECTOR_JOINT_HH_ +#define GZ_SIM_GUI_COMPONENTINSPECTOR_JOINT_HH_ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class ComponentInspectorEditor; diff --git a/src/gui/plugins/component_inspector_editor/Lidar.cc b/src/gui/plugins/component_inspector_editor/Lidar.cc index 00cde19708..192ae3d6d9 100644 --- a/src/gui/plugins/component_inspector_editor/Lidar.cc +++ b/src/gui/plugins/component_inspector_editor/Lidar.cc @@ -24,8 +24,8 @@ #include "Lidar.hh" #include "Types.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// Lidar::Lidar(ComponentInspectorEditor *_inspector) @@ -78,7 +78,7 @@ Q_INVOKABLE void Lidar::OnLidarNoise( double _stdDevBias, double _dynamicBiasStdDev, double _dynamicBiasCorrelationTime) { - ignition::gazebo::UpdateCallback cb = + gz::sim::UpdateCallback cb = [=](EntityComponentManager &_ecm) { auto comp = _ecm.Component( @@ -96,11 +96,11 @@ Q_INVOKABLE void Lidar::OnLidarNoise( lidar->SetLidarNoise(noise); } else - ignerr << "Unable to get the lidar noise data.\n"; + gzerr << "Unable to get the lidar noise data.\n"; } else { - ignerr << "Unable to get the lidar component.\n"; + gzerr << "Unable to get the lidar component.\n"; } }; this->inspector->AddUpdateCallback(cb); @@ -116,7 +116,7 @@ Q_INVOKABLE void Lidar::OnLidarChange( double _verticalScanResolution, double _verticalScanMinAngle, double _verticalScanMaxAngle) { - ignition::gazebo::UpdateCallback cb = + gz::sim::UpdateCallback cb = [=](EntityComponentManager &_ecm) { auto comp = _ecm.Component( @@ -141,11 +141,11 @@ Q_INVOKABLE void Lidar::OnLidarChange( lidar->SetVerticalScanMaxAngle(_verticalScanMaxAngle); } else - ignerr << "Unable to get the lidar data.\n"; + gzerr << "Unable to get the lidar data.\n"; } else { - ignerr << "Unable to get the lidar component.\n"; + gzerr << "Unable to get the lidar component.\n"; } }; this->inspector->AddUpdateCallback(cb); diff --git a/src/gui/plugins/component_inspector_editor/Lidar.hh b/src/gui/plugins/component_inspector_editor/Lidar.hh index 9bcb174069..b81e4c0038 100644 --- a/src/gui/plugins/component_inspector_editor/Lidar.hh +++ b/src/gui/plugins/component_inspector_editor/Lidar.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_LIDAR_HH_ -#define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_LIDAR_HH_ +#ifndef GZ_SIM_GUI_COMPONENTINSPECTOR_LIDAR_HH_ +#define GZ_SIM_GUI_COMPONENTINSPECTOR_LIDAR_HH_ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class ComponentInspectorEditor; diff --git a/src/gui/plugins/component_inspector_editor/Magnetometer.cc b/src/gui/plugins/component_inspector_editor/Magnetometer.cc index 0c2fa64ef3..9459e4a686 100644 --- a/src/gui/plugins/component_inspector_editor/Magnetometer.cc +++ b/src/gui/plugins/component_inspector_editor/Magnetometer.cc @@ -23,8 +23,8 @@ #include "Magnetometer.hh" #include "Types.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// Magnetometer::Magnetometer(ComponentInspectorEditor *_inspector) @@ -95,11 +95,11 @@ Q_INVOKABLE void Magnetometer::OnMagnetometerXNoise( mag->SetXNoise(noise); } else - ignerr << "Unable to get the magnetometer data.\n"; + gzerr << "Unable to get the magnetometer data.\n"; } else { - ignerr << "Unable to get the magnetometer component.\n"; + gzerr << "Unable to get the magnetometer component.\n"; } }; this->inspector->AddUpdateCallback(cb); @@ -129,11 +129,11 @@ Q_INVOKABLE void Magnetometer::OnMagnetometerYNoise( mag->SetYNoise(noise); } else - ignerr << "Unable to get the magnetometer data.\n"; + gzerr << "Unable to get the magnetometer data.\n"; } else { - ignerr << "Unable to get the magnetometer component.\n"; + gzerr << "Unable to get the magnetometer component.\n"; } }; this->inspector->AddUpdateCallback(cb); @@ -163,11 +163,11 @@ Q_INVOKABLE void Magnetometer::OnMagnetometerZNoise( mag->SetZNoise(noise); } else - ignerr << "Unable to get the magnetometer data.\n"; + gzerr << "Unable to get the magnetometer data.\n"; } else { - ignerr << "Unable to get the magnetometer component.\n"; + gzerr << "Unable to get the magnetometer component.\n"; } }; this->inspector->AddUpdateCallback(cb); diff --git a/src/gui/plugins/component_inspector_editor/Magnetometer.hh b/src/gui/plugins/component_inspector_editor/Magnetometer.hh index d95cf4f341..7754ef078a 100644 --- a/src/gui/plugins/component_inspector_editor/Magnetometer.hh +++ b/src/gui/plugins/component_inspector_editor/Magnetometer.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_MAGNETOMETER_HH_ -#define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_MAGNETOMETER_HH_ +#ifndef GZ_SIM_GUI_COMPONENTINSPECTOR_MAGNETOMETER_HH_ +#define GZ_SIM_GUI_COMPONENTINSPECTOR_MAGNETOMETER_HH_ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class ComponentInspectorEditor; diff --git a/src/gui/plugins/component_inspector_editor/ModelEditor.cc b/src/gui/plugins/component_inspector_editor/ModelEditor.cc index 2f88fcd717..71c1449a0e 100644 --- a/src/gui/plugins/component_inspector_editor/ModelEditor.cc +++ b/src/gui/plugins/component_inspector_editor/ModelEditor.cc @@ -51,7 +51,7 @@ #include "ModelEditor.hh" -namespace ignition::gazebo +namespace gz::sim { class EntityToAdd { @@ -130,8 +130,8 @@ namespace ignition::gazebo }; } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// ModelEditor::ModelEditor() @@ -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); } ////////////////////////////////////////////////// @@ -170,7 +170,7 @@ void ModelEditor::Update(const UpdateInfo &, { if (eta.parentEntity == kNullEntity) { - ignerr << "Parent entity not defined." << std::endl; + gzerr << "Parent entity not defined." << std::endl; continue; } @@ -236,12 +236,12 @@ void ModelEditor::Update(const UpdateInfo &, } // use GuiNewRemovedEntities event to update other gui plugins - // note this event will be removed in Ignition Garden + // note this event will be removed in Gazebo Garden std::set removedEntities; - ignition::gazebo::gui::events::GuiNewRemovedEntities event( + gz::sim::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(); @@ -250,7 +250,7 @@ void ModelEditor::Update(const UpdateInfo &, ///////////////////////////////////////////////// bool ModelEditor::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == gazebo::gui::events::ModelEditorAddEntity::kType) + if (_event->type() == sim::gui::events::ModelEditorAddEntity::kType) { auto event = reinterpret_cast(_event); if (event) @@ -302,7 +302,7 @@ std::optional ModelEditorPrivate::CreateLight( } else { - ignwarn << "Light type not supported: " + gzwarn << "Light type not supported: " << _eta.geomOrLightType << std::endl; return std::nullopt; } @@ -362,7 +362,7 @@ std::optional ModelEditorPrivate::CreateGeom( } else { - ignwarn << "Geometry type not supported: " + gzwarn << "Geometry type not supported: " << _eta.geomOrLightType << std::endl; return std::nullopt; } @@ -377,7 +377,7 @@ std::optional ModelEditorPrivate::CreateLink( sdf::Link link; if (_eta.parentEntity == kNullEntity) { - ignerr << "Parent entity not defined." << std::endl; + gzerr << "Parent entity not defined." << std::endl; return std::nullopt; } @@ -432,7 +432,7 @@ std::optional ModelEditorPrivate::CreateSensor( // Exit early if there is no parent entity if (_eta.parentEntity == kNullEntity) { - ignerr << "Parent entity not defined." << std::endl; + gzerr << "Parent entity not defined." << std::endl; return std::nullopt; } @@ -500,7 +500,7 @@ std::optional ModelEditorPrivate::CreateJoint( joint.SetType(sdf::JointType::SCREW); else { - ignwarn << "Joint type not supported: " + gzwarn << "Joint type not supported: " << _eta.geomOrLightType << std::endl; return std::nullopt; diff --git a/src/gui/plugins/component_inspector_editor/ModelEditor.hh b/src/gui/plugins/component_inspector_editor/ModelEditor.hh index 8234dfb5ac..bd8b3ab57f 100644 --- a/src/gui/plugins/component_inspector_editor/ModelEditor.hh +++ b/src/gui/plugins/component_inspector_editor/ModelEditor.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_MODELEDITOR_HH_ -#define IGNITION_GAZEBO_GUI_MODELEDITOR_HH_ +#ifndef GZ_SIM_GUI_MODELEDITOR_HH_ +#define GZ_SIM_GUI_MODELEDITOR_HH_ #include @@ -24,9 +24,9 @@ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class ModelEditorPrivate; diff --git a/src/gui/plugins/component_inspector_editor/Pose3d.cc b/src/gui/plugins/component_inspector_editor/Pose3d.cc index e8a8d3d701..99c834ee8f 100644 --- a/src/gui/plugins/component_inspector_editor/Pose3d.cc +++ b/src/gui/plugins/component_inspector_editor/Pose3d.cc @@ -26,8 +26,8 @@ #include "Pose3d.hh" #include "Types.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// Pose3d::Pose3d(ComponentInspectorEditor *_inspector) @@ -70,7 +70,7 @@ Pose3d::Pose3d(ComponentInspectorEditor *_inspector) Q_INVOKABLE void Pose3d::PoseUpdate( double _x, double _y, double _z, double _roll, double _pitch, double _yaw) { - ignition::gazebo::UpdateCallback cb = + gz::sim::UpdateCallback cb = [=](EntityComponentManager &_ecm) { auto comp = _ecm.Component(this->inspector->GetEntity()); @@ -83,7 +83,7 @@ Q_INVOKABLE void Pose3d::PoseUpdate( _ecm.CreateComponent(modelEntity, components::Recreate()); } else - ignerr << "Unable to get the pose component.\n"; + gzerr << "Unable to get the pose component.\n"; }; this->inspector->AddUpdateCallback(cb); } diff --git a/src/gui/plugins/component_inspector_editor/Pose3d.hh b/src/gui/plugins/component_inspector_editor/Pose3d.hh index 2a4f27973a..f270dcf854 100644 --- a/src/gui/plugins/component_inspector_editor/Pose3d.hh +++ b/src/gui/plugins/component_inspector_editor/Pose3d.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_POSE3D_HH_ -#define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_POSE3D_HH_ +#ifndef GZ_SIM_GUI_COMPONENTINSPECTOR_POSE3D_HH_ +#define GZ_SIM_GUI_COMPONENTINSPECTOR_POSE3D_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class ComponentInspectorEditor; diff --git a/src/gui/plugins/component_inspector_editor/Types.cc b/src/gui/plugins/component_inspector_editor/Types.cc index fdef409818..06c6f784ce 100644 --- a/src/gui/plugins/component_inspector_editor/Types.cc +++ b/src/gui/plugins/component_inspector_editor/Types.cc @@ -17,7 +17,7 @@ #include "Types.hh" -void ignition::gazebo::setNoise(sdf::Noise &_noise, +void gz::sim::setNoise(sdf::Noise &_noise, double _mean, double _meanBias, double _stdDev, double _stdDevBias, double _dynamicBiasStdDev, double _dynamicBiasCorrelationTime) diff --git a/src/gui/plugins/component_inspector_editor/Types.hh b/src/gui/plugins/component_inspector_editor/Types.hh index 78e8463d1b..1493b439f9 100644 --- a/src/gui/plugins/component_inspector_editor/Types.hh +++ b/src/gui/plugins/component_inspector_editor/Types.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_TYPES_HH_ -#define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_TYPES_HH_ +#ifndef GZ_SIM_GUI_COMPONENTINSPECTOR_TYPES_HH_ +#define GZ_SIM_GUI_COMPONENTINSPECTOR_TYPES_HH_ #include #include @@ -25,9 +25,9 @@ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { /// \brief UpdateCallback is a function defition that is used by a /// component to manage ECM changes. diff --git a/src/gui/plugins/copy_paste/CopyPaste.cc b/src/gui/plugins/copy_paste/CopyPaste.cc index 52bb86b9ce..f26f7a8d74 100644 --- a/src/gui/plugins/copy_paste/CopyPaste.cc +++ b/src/gui/plugins/copy_paste/CopyPaste.cc @@ -31,7 +31,7 @@ #include "CopyPaste.hh" -namespace ignition::gazebo +namespace gz::sim { class CopyPastePrivate { @@ -59,8 +59,8 @@ namespace ignition::gazebo }; } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// CopyPaste::CopyPaste() @@ -69,14 +69,14 @@ CopyPaste::CopyPaste() if (!this->dataPtr->node.Advertise(this->dataPtr->copyService, &CopyPaste::CopyServiceCB, this)) { - ignerr << "Error advertising service [" << this->dataPtr->copyService + gzerr << "Error advertising service [" << this->dataPtr->copyService << "]" << std::endl; } if (!this->dataPtr->node.Advertise(this->dataPtr->pasteService, &CopyPaste::PasteServiceCB, this)) { - ignerr << "Error advertising service [" << this->dataPtr->pasteService + gzerr << "Error advertising service [" << this->dataPtr->pasteService << "]" << std::endl; } } @@ -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); } } @@ -133,7 +133,7 @@ void CopyPaste::OnPaste() ///////////////////////////////////////////////// bool CopyPaste::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gazebo::gui::events::EntitiesSelected::kType) + if (_event->type() == gz::sim::gui::events::EntitiesSelected::kType) { std::lock_guard guard(this->dataPtr->mutex); @@ -160,8 +160,8 @@ bool CopyPaste::eventFilter(QObject *_obj, QEvent *_event) } ///////////////////////////////////////////////// -bool CopyPaste::CopyServiceCB(const ignition::msgs::StringMsg &_req, - ignition::msgs::Boolean &_resp) +bool CopyPaste::CopyServiceCB(const gz::msgs::StringMsg &_req, + gz::msgs::Boolean &_resp) { { std::lock_guard guard(this->dataPtr->mutex); @@ -172,8 +172,8 @@ bool CopyPaste::CopyServiceCB(const ignition::msgs::StringMsg &_req, } ///////////////////////////////////////////////// -bool CopyPaste::PasteServiceCB(const ignition::msgs::Empty &/*_req*/, - ignition::msgs::Boolean &_resp) +bool CopyPaste::PasteServiceCB(const gz::msgs::Empty &/*_req*/, + gz::msgs::Boolean &_resp) { this->OnPaste(); _resp.set_data(true); @@ -181,5 +181,5 @@ bool CopyPaste::PasteServiceCB(const ignition::msgs::Empty &/*_req*/, } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::CopyPaste, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::CopyPaste, + gz::gui::Plugin) diff --git a/src/gui/plugins/copy_paste/CopyPaste.hh b/src/gui/plugins/copy_paste/CopyPaste.hh index 0ac3dc3301..ba9e47f5b5 100644 --- a/src/gui/plugins/copy_paste/CopyPaste.hh +++ b/src/gui/plugins/copy_paste/CopyPaste.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_COPYPASTE_HH_ -#define IGNITION_GAZEBO_GUI_COPYPASTE_HH_ +#ifndef GZ_SIM_GUI_COPYPASTE_HH_ +#define GZ_SIM_GUI_COPYPASTE_HH_ #include @@ -24,14 +24,14 @@ #include "gz/sim/gui/GuiSystem.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class CopyPastePrivate; /// \brief Plugin for copying/pasting entities in the GUI. - class CopyPaste : public ignition::gazebo::GuiSystem + class CopyPaste : public gz::sim::GuiSystem { Q_OBJECT @@ -63,15 +63,15 @@ namespace gazebo /// entity to be copied /// \param[out] _resp The service response /// \return Whether the service was successful (true) or not (false) - private: bool CopyServiceCB(const ignition::msgs::StringMsg &_req, - ignition::msgs::Boolean &_resp); + private: bool CopyServiceCB(const gz::msgs::StringMsg &_req, + gz::msgs::Boolean &_resp); /// \brief Callback for handling a paste service request /// \param[in] _req The service request /// \param[out] _resp The service response /// \return Whether the service was successful (true) or not (false) - private: bool PasteServiceCB(const ignition::msgs::Empty &_req, - ignition::msgs::Boolean &_resp); + private: bool PasteServiceCB(const gz::msgs::Empty &_req, + gz::msgs::Boolean &_resp); /// \internal /// \brief Pointer to private data diff --git a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc index ff916ff00b..dffa4c4020 100644 --- a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc +++ b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc @@ -35,7 +35,7 @@ #include #include -namespace ignition::gazebo +namespace gz::sim { class EntityContextMenuPrivate { @@ -53,8 +53,8 @@ namespace ignition::gazebo }; } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// void EntityContextMenuPrivate::OnRender() @@ -76,7 +76,7 @@ void EntityContextMenuPrivate::OnRender() { this->camera = cam; - igndbg << "Entity context menu plugin is using camera [" + gzdbg << "Entity context menu plugin is using camera [" << this->camera->Name() << "]" << std::endl; break; } @@ -101,7 +101,7 @@ void EntityContextMenu::LoadConfig(const tinyxml2::XMLElement *) this->PluginItem()->findChild(); if (!renderWindowOverlay) { - ignerr << "Unable to find Render Window Overlay item. " + gzerr << "Unable to find Render Window Overlay item. " << "Render window overlay will not be created" << std::endl; return; } @@ -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( @@ -204,5 +204,5 @@ void EntityContextMenuHandler::HandleMouseContextMenu( } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::EntityContextMenu, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::EntityContextMenu, + 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..91589ff4a1 100644 --- a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh +++ b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GUI_PLUGINS_ENTITY_CONTEXT_MENU_HH_ -#define IGNITION_GUI_PLUGINS_ENTITY_CONTEXT_MENU_HH_ +#ifndef GZ_GUI_PLUGINS_ENTITY_CONTEXT_MENU_HH_ +#define GZ_GUI_PLUGINS_ENTITY_CONTEXT_MENU_HH_ #include @@ -26,15 +26,15 @@ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class EntityContextMenuPrivate; /// \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 df5dace528..072920d3b5 100644 --- a/src/gui/plugins/entity_tree/EntityTree.cc +++ b/src/gui/plugins/entity_tree/EntityTree.cc @@ -50,7 +50,7 @@ #include "gz/sim/EntityComponentManager.hh" #include "gz/sim/Primitives.hh" -namespace ignition::gazebo +namespace gz::sim { class EntityTreePrivate { @@ -75,8 +75,8 @@ namespace ignition::gazebo }; } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ////////////////////////////////////////////////// QString entityType(Entity _entity, @@ -292,7 +292,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); } @@ -305,8 +305,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); } ////////////////////////////////////////////////// @@ -405,14 +405,14 @@ void EntityTree::Update(const UpdateInfo &, EntityComponentManager &_ecm) auto nameComp = _ecm.Component(entity); if (!nameComp) { - ignerr << "Could not add entity [" << entity << "] to the entity tree " + gzerr << "Could not add entity [" << entity << "] to the entity tree " << "because it does not have a name component.\n"; continue; } auto parentComp = _ecm.Component(entity); if (!parentComp) { - ignerr << "Could not add entity [" << entity << "] to the entity tree " + gzerr << "Could not add entity [" << entity << "] to the entity tree " << "because it does not have a parent entity component.\n"; continue; } @@ -450,8 +450,8 @@ void EntityTree::OnEntitySelectedFromQml(Entity _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); } @@ -459,8 +459,8 @@ void EntityTree::OnEntitySelectedFromQml(Entity _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); } @@ -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); } @@ -526,7 +526,7 @@ void EntityTree::OnLoadMesh(const QString &_mesh) ///////////////////////////////////////////////// bool EntityTree::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gazebo::gui::events::EntitiesSelected::kType) + if (_event->type() == gz::sim::gui::events::EntitiesSelected::kType) { auto selectedEvent = reinterpret_cast(_event); @@ -544,7 +544,7 @@ bool EntityTree::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::DeselectAllEntities::kType) + gz::sim::gui::events::DeselectAllEntities::kType) { auto deselectAllEvent = reinterpret_cast(_event); @@ -555,7 +555,7 @@ bool EntityTree::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::GuiNewRemovedEntities::kType) + gz::sim::gui::events::GuiNewRemovedEntities::kType) { std::lock_guard lock(this->dataPtr->newRemovedEntityMutex); auto addedRemovedEvent = @@ -577,5 +577,5 @@ bool EntityTree::eventFilter(QObject *_obj, QEvent *_event) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::EntityTree, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::EntityTree, + gz::gui::Plugin) diff --git a/src/gui/plugins/entity_tree/EntityTree.hh b/src/gui/plugins/entity_tree/EntityTree.hh index 06a9ca55d8..fcf469512f 100644 --- a/src/gui/plugins/entity_tree/EntityTree.hh +++ b/src/gui/plugins/entity_tree/EntityTree.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_ENTITYTREE_HH_ -#define IGNITION_GAZEBO_GUI_ENTITYTREE_HH_ +#ifndef GZ_SIM_GUI_ENTITYTREE_HH_ +#define GZ_SIM_GUI_ENTITYTREE_HH_ #include #include @@ -25,9 +25,9 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class EntityTreePrivate; @@ -107,7 +107,7 @@ namespace gazebo /// /// ## Configuration /// None - class EntityTree : public ignition::gazebo::GuiSystem + class EntityTree : public gz::sim::GuiSystem { Q_OBJECT diff --git a/src/gui/plugins/joint_position_controller/JointPositionController.cc b/src/gui/plugins/joint_position_controller/JointPositionController.cc index 5183d3e3b4..32829dea98 100644 --- a/src/gui/plugins/joint_position_controller/JointPositionController.cc +++ b/src/gui/plugins/joint_position_controller/JointPositionController.cc @@ -38,7 +38,7 @@ #include "JointPositionController.hh" -namespace ignition::gazebo::gui +namespace gz::sim::gui { class JointPositionControllerPrivate { @@ -62,9 +62,9 @@ namespace ignition::gazebo::gui }; } -using namespace ignition; -using namespace ignition::gazebo; -using namespace ignition::gazebo::gui; +using namespace gz; +using namespace gz::sim; +using namespace gz::sim::gui; ///////////////////////////////////////////////// JointsModel::JointsModel() : QStandardItemModel() @@ -162,8 +162,8 @@ void JointPositionController::LoadConfig( } } - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); // Connect model this->Context()->setContextProperty( @@ -189,7 +189,7 @@ void JointPositionController::Update(const UpdateInfo &, this->SetModelEntity(entity); this->SetLocked(true); this->dataPtr->xmlModelInitialized = true; - ignmsg << "Controller locked on [" << this->dataPtr->modelName.toStdString() + gzmsg << "Controller locked on [" << this->dataPtr->modelName.toStdString() << "]" << std::endl; } @@ -218,7 +218,7 @@ void JointPositionController::Update(const UpdateInfo &, auto typeComp = _ecm.Component(jointEntity); if (nullptr == typeComp) { - ignerr << "Joint [" << jointEntity << "] missing type" << std::endl; + gzerr << "Joint [" << jointEntity << "] missing type" << std::endl; continue; } @@ -246,7 +246,7 @@ void JointPositionController::Update(const UpdateInfo &, if (nullptr == item) { - ignerr << "Failed to get item for joint [" << jointEntity << "]" + gzerr << "Failed to get item for joint [" << jointEntity << "]" << std::endl; continue; } @@ -301,7 +301,7 @@ bool JointPositionController::eventFilter(QObject *_obj, QEvent *_event) { if (!this->dataPtr->locked) { - if (_event->type() == gazebo::gui::events::EntitiesSelected::kType) + if (_event->type() == sim::gui::events::EntitiesSelected::kType) { auto event = reinterpret_cast(_event); if (event && !event->Data().empty()) @@ -310,7 +310,7 @@ bool JointPositionController::eventFilter(QObject *_obj, QEvent *_event) } } - if (_event->type() == gazebo::gui::events::DeselectAllEntities::kType) + if (_event->type() == sim::gui::events::DeselectAllEntities::kType) { auto event = reinterpret_cast( _event); @@ -374,7 +374,7 @@ void JointPositionController::OnCommand(const QString &_jointName, double _pos) { std::string jointName = _jointName.toStdString(); - ignition::msgs::Double msg; + gz::msgs::Double msg; msg.set_data(_pos); auto topic = transport::TopicUtils::AsValidTopic("/model/" + this->dataPtr->modelName.toStdString() + "/joint/" + jointName + @@ -382,12 +382,12 @@ void JointPositionController::OnCommand(const QString &_jointName, double _pos) if (topic.empty()) { - ignerr << "Failed to create valid topic for joint [" << jointName << "]" + gzerr << "Failed to create valid topic for joint [" << jointName << "]" << std::endl; return; } - auto pub = this->dataPtr->node.Advertise(topic); + auto pub = this->dataPtr->node.Advertise(topic); pub.Publish(msg); } @@ -400,11 +400,11 @@ void JointPositionController::OnReset() .toString().toStdString(); if (jointName.empty()) { - ignerr << "Internal error: failed to get joint name." << std::endl; + gzerr << "Internal error: failed to get joint name." << std::endl; continue; } - ignition::msgs::Double msg; + gz::msgs::Double msg; msg.set_data(0); auto topic = transport::TopicUtils::AsValidTopic("/model/" + this->dataPtr->modelName.toStdString() + "/joint/" + jointName + @@ -412,16 +412,16 @@ void JointPositionController::OnReset() if (topic.empty()) { - ignerr << "Failed to create valid topic for joint [" << jointName << "]" + gzerr << "Failed to create valid topic for joint [" << jointName << "]" << std::endl; return; } - auto pub = this->dataPtr->node.Advertise(topic); + auto pub = this->dataPtr->node.Advertise(topic); pub.Publish(msg); } } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::gui::JointPositionController, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::gui::JointPositionController, + gz::gui::Plugin) diff --git a/src/gui/plugins/joint_position_controller/JointPositionController.hh b/src/gui/plugins/joint_position_controller/JointPositionController.hh index d51e855d16..0e23ca4bc9 100644 --- a/src/gui/plugins/joint_position_controller/JointPositionController.hh +++ b/src/gui/plugins/joint_position_controller/JointPositionController.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_JOINTPOSITIONCONTROLLER_HH_ -#define IGNITION_GAZEBO_GUI_JOINTPOSITIONCONTROLLER_HH_ +#ifndef GZ_SIM_GUI_JOINTPOSITIONCONTROLLER_HH_ +#define GZ_SIM_GUI_JOINTPOSITIONCONTROLLER_HH_ #include #include @@ -25,11 +25,11 @@ #include #include -Q_DECLARE_METATYPE(ignition::gazebo::Entity) +Q_DECLARE_METATYPE(gz::sim::Entity) -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace gui { @@ -71,10 +71,10 @@ namespace gui /// \brief Control position of all joints in the selected model. /// The model must have loaded an - /// `ignition::gazebo::systems::JointPositionController` + /// `gz::sim::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 sim::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 a4b7558cc6..ff3111a03e 100644 --- a/src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc +++ b/src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc @@ -47,7 +47,7 @@ int g_argc = 1; char **g_argv; -using namespace ignition; +using namespace gz; /// \brief Tests for the joint position controller GUI plugin class JointPositionControllerGui : public InternalFixture<::testing::Test> @@ -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 sim::gui plugins + auto runner = new sim::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 *>(); + sim::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(), sim::kNullEntity); EXPECT_EQ(plugin->ModelName(), QString("No model selected")) << plugin->ModelName().toStdString(); EXPECT_FALSE(plugin->Locked()); @@ -105,24 +105,24 @@ TEST_F(JointPositionControllerGui, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PublishCommand)) { // Create a model with a joint - gazebo::EntityComponentManager ecm; + sim::EntityComponentManager ecm; auto modelEntity = ecm.CreateEntity(); - ecm.CreateComponent(modelEntity, gazebo::components::Model()); - ecm.CreateComponent(modelEntity, gazebo::components::Name("model_name")); + ecm.CreateComponent(modelEntity, sim::components::Model()); + ecm.CreateComponent(modelEntity, sim::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, sim::components::Joint()); + ecm.CreateComponent(jointEntity, sim::components::Name("joint_name")); + ecm.CreateComponent(jointEntity, sim::components::ParentEntity( modelEntity)); - ecm.CreateComponent(jointEntity, gazebo::components::JointPosition({0.1})); - ecm.CreateComponent(jointEntity, gazebo::components::JointType( + ecm.CreateComponent(jointEntity, sim::components::JointPosition({0.1})); + ecm.CreateComponent(jointEntity, sim::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, sim::components::JointAxis(jointAxis)); // Populate state message msgs::SerializedStepMap stepMsg; @@ -146,8 +146,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 sim::gui plugins + auto runner = new sim::GuiRunner("test"); runner->setParent(gui::App()); // Load plugin @@ -172,7 +172,7 @@ TEST_F(JointPositionControllerGui, // Get plugin auto plugins = win->findChildren< - gazebo::gui::JointPositionController *>(); + sim::gui::JointPositionController *>(); EXPECT_EQ(plugins.size(), 1); auto plugin = plugins[0]; @@ -188,13 +188,13 @@ TEST_F(JointPositionControllerGui, } EXPECT_LT(sleep, maxSleep); - EXPECT_EQ(plugin->ModelEntity(), gazebo::kNullEntity); + EXPECT_EQ(plugin->ModelEntity(), sim::kNullEntity); EXPECT_EQ(plugin->ModelName(), QString("No model selected")) << plugin->ModelName().toStdString(); EXPECT_FALSE(plugin->Locked()); // Get model - auto models = win->findChildren(); + auto models = win->findChildren(); EXPECT_EQ(models.size(), 1); auto jointsModel = models[0]; diff --git a/src/gui/plugins/lights/Lights.cc b/src/gui/plugins/lights/Lights.cc index 395c4607d9..3fc0c2e55f 100644 --- a/src/gui/plugins/lights/Lights.cc +++ b/src/gui/plugins/lights/Lights.cc @@ -35,19 +35,19 @@ #include "gz/sim/EntityComponentManager.hh" #include "gz/sim/Primitives.hh" -namespace ignition::gazebo +namespace gz::sim { class LightsPrivate { }; } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// 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) +IGNITION_ADD_PLUGIN(gz::sim::Lights, + gz::gui::Plugin) diff --git a/src/gui/plugins/lights/Lights.hh b/src/gui/plugins/lights/Lights.hh index 49fd8dd063..ba468cafc6 100644 --- a/src/gui/plugins/lights/Lights.hh +++ b/src/gui/plugins/lights/Lights.hh @@ -15,22 +15,22 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_LIGHTS_HH_ -#define IGNITION_GAZEBO_GUI_LIGHTS_HH_ +#ifndef GZ_SIM_GUI_LIGHTS_HH_ +#define GZ_SIM_GUI_LIGHTS_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class LightsPrivate; /// \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/modules/CMakeLists.txt b/src/gui/plugins/modules/CMakeLists.txt index fb959d8d0c..1fa08538b1 100644 --- a/src/gui/plugins/modules/CMakeLists.txt +++ b/src/gui/plugins/modules/CMakeLists.txt @@ -7,6 +7,6 @@ gz_add_gui_library(EntityContextMenu QT_HEADERS EntityContextMenu.hh ) -install (TARGETS EntityContextMenu DESTINATION ${IGNITION_GAZEBO_GUI_PLUGIN_INSTALL_DIR}/${module_name}) -install (FILES qmldir DESTINATION ${IGNITION_GAZEBO_GUI_PLUGIN_INSTALL_DIR}/${module_name}) +install (TARGETS EntityContextMenu DESTINATION ${GZ_SIM_GUI_PLUGIN_INSTALL_DIR}/${module_name}) +install (FILES qmldir DESTINATION ${GZ_SIM_GUI_PLUGIN_INSTALL_DIR}/${module_name}) diff --git a/src/gui/plugins/modules/EntityContextMenu.cc b/src/gui/plugins/modules/EntityContextMenu.cc index 4e6d9dde0b..0a166113d8 100644 --- a/src/gui/plugins/modules/EntityContextMenu.cc +++ b/src/gui/plugins/modules/EntityContextMenu.cc @@ -30,7 +30,7 @@ #include #include -namespace ignition::gazebo +namespace gz::sim { /// \brief Private data class for EntityContextMenu class EntityContextMenuPrivate @@ -79,14 +79,14 @@ namespace ignition::gazebo }; } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// void GzSimPlugin::registerTypes(const char *_uri) { // Register our 'EntityContextMenuItem' in qml engine - qmlRegisterType(_uri, 1, 0, + qmlRegisterType(_uri, 1, 0, "EntityContextMenuItem"); } @@ -143,7 +143,7 @@ void EntityContextMenu::OnRemove( auto runners = gui::App()->findChildren(); if (runners.empty() || runners[0] == nullptr) { - ignerr << "Internal error: no GuiRunner found." << std::endl; + gzerr << "Internal error: no GuiRunner found." << std::endl; return; } @@ -151,7 +151,7 @@ void EntityContextMenu::OnRemove( auto worldNameVariant = runners[0]->property("worldName"); if (!worldNameVariant.isValid()) { - ignwarn << "GuiRunner's worldName not set, using[" + gzwarn << "GuiRunner's worldName not set, using[" << this->dataPtr->worldName << "]" << std::endl; } else @@ -163,14 +163,14 @@ void EntityContextMenu::OnRemove( "/world/" + this->dataPtr->worldName + "/remove"; } - std::function cb = - [](const ignition::msgs::Boolean &_rep, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &_rep, const bool _result) { if (!_result || !_rep.data()) - ignerr << "Error sending remove request" << std::endl; + gzerr << "Error sending remove request" << std::endl; }; - ignition::msgs::Entity req; + gz::msgs::Entity req; req.set_name(_data.toStdString()); req.set_type(convert(_type.toStdString())); @@ -180,81 +180,81 @@ void EntityContextMenu::OnRemove( ///////////////////////////////////////////////// void EntityContextMenu::OnRequest(const QString &_request, const QString &_data) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error sending move to request" << std::endl; + gzerr << "Error sending move to request" << std::endl; }; std::string request = _request.toStdString(); if (request == "move_to") { - ignition::msgs::StringMsg req; + gz::msgs::StringMsg req; req.set_data(_data.toStdString()); this->dataPtr->node.Request(this->dataPtr->moveToService, req, cb); } else if (request == "follow") { - ignition::msgs::StringMsg req; + gz::msgs::StringMsg req; req.set_data(_data.toStdString()); this->dataPtr->node.Request(this->dataPtr->followService, req, cb); } else if (request == "view_transparent") { - ignition::msgs::StringMsg req; + gz::msgs::StringMsg req; req.set_data(_data.toStdString()); this->dataPtr->node.Request(this->dataPtr->viewTransparentService, req, cb); } else if (request == "view_com") { - ignition::msgs::StringMsg req; + gz::msgs::StringMsg req; req.set_data(_data.toStdString()); this->dataPtr->node.Request(this->dataPtr->viewCOMService, req, cb); } else if (request == "view_inertia") { - ignition::msgs::StringMsg req; + gz::msgs::StringMsg req; req.set_data(_data.toStdString()); this->dataPtr->node.Request(this->dataPtr->viewInertiaService, req, cb); } else if (request == "view_joints") { - ignition::msgs::StringMsg req; + gz::msgs::StringMsg req; req.set_data(_data.toStdString()); this->dataPtr->node.Request(this->dataPtr->viewJointsService, req, cb); } else if (request == "view_wireframes") { - ignition::msgs::StringMsg req; + gz::msgs::StringMsg req; req.set_data(_data.toStdString()); this->dataPtr->node.Request(this->dataPtr->viewWireframesService, req, cb); } else if (request == "view_collisions") { - ignition::msgs::StringMsg req; + gz::msgs::StringMsg req; req.set_data(_data.toStdString()); this->dataPtr->node.Request(this->dataPtr->viewCollisionsService, req, cb); } else if (request == "view_frames") { - ignition::msgs::StringMsg req; + gz::msgs::StringMsg req; req.set_data(_data.toStdString()); this->dataPtr->node.Request(this->dataPtr->viewFramesService, req, cb); } else if (request == "copy") { - ignition::msgs::StringMsg req; + gz::msgs::StringMsg req; req.set_data(_data.toStdString()); this->dataPtr->node.Request(this->dataPtr->copyService, req, cb); } else if (request == "paste") { - ignition::msgs::Empty req; + gz::msgs::Empty req; this->dataPtr->node.Request(this->dataPtr->pasteService, req, cb); } else { - ignwarn << "Unknown request [" << request << "]" << std::endl; + gzwarn << "Unknown request [" << request << "]" << std::endl; } } diff --git a/src/gui/plugins/modules/EntityContextMenu.hh b/src/gui/plugins/modules/EntityContextMenu.hh index 9345bc4a76..381417f61e 100644 --- a/src/gui/plugins/modules/EntityContextMenu.hh +++ b/src/gui/plugins/modules/EntityContextMenu.hh @@ -15,16 +15,16 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_ENTITYCONTEXTMENU_HH_ -#define IGNITION_GAZEBO_GUI_ENTITYCONTEXTMENU_HH_ +#ifndef GZ_SIM_GUI_ENTITYCONTEXTMENU_HH_ +#define GZ_SIM_GUI_ENTITYCONTEXTMENU_HH_ #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class EntityContextMenuPrivate; diff --git a/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc b/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc index e1c198d14d..077b175e54 100644 --- a/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc +++ b/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc @@ -39,7 +39,7 @@ #include "gz/sim/EntityComponentManager.hh" #include "gz/sim/components/LogPlaybackStatistics.hh" -namespace ignition::gazebo +namespace gz::sim { class PlaybackScrubberPrivate { @@ -67,8 +67,8 @@ namespace ignition::gazebo }; } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// PlaybackScrubber::PlaybackScrubber() : GuiSystem(), @@ -148,7 +148,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(); @@ -198,7 +198,7 @@ void PlaybackScrubber::OnTimeEntered(const QString &_time) math::stringToTimePoint(time); if (enteredTime == math::secNsecToTimePoint(-1, 0)) { - ignwarn << "Invalid time entered. " + gzwarn << "Invalid time entered. " "The format is dd hh:mm:ss.nnn" << std::endl; return; } @@ -251,5 +251,5 @@ void PlaybackScrubber::OnDrop(double _value) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::PlaybackScrubber, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::PlaybackScrubber, + gz::gui::Plugin) diff --git a/src/gui/plugins/playback_scrubber/PlaybackScrubber.hh b/src/gui/plugins/playback_scrubber/PlaybackScrubber.hh index 3c763fd907..7b8c31772c 100644 --- a/src/gui/plugins/playback_scrubber/PlaybackScrubber.hh +++ b/src/gui/plugins/playback_scrubber/PlaybackScrubber.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_PLAYBACK_SCRUBBER_HH_ -#define IGNITION_GAZEBO_GUI_PLAYBACK_SCRUBBER_HH_ +#ifndef GZ_SIM_GUI_PLAYBACK_SCRUBBER_HH_ +#define GZ_SIM_GUI_PLAYBACK_SCRUBBER_HH_ #include #include @@ -24,15 +24,15 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class PlaybackScrubberPrivate; /// \brief Provides slider and functionality for log playback. /// to the scene - class PlaybackScrubber : public ignition::gazebo::GuiSystem + class PlaybackScrubber : public gz::sim::GuiSystem { Q_OBJECT diff --git a/src/gui/plugins/plot_3d/Plot3D.cc b/src/gui/plugins/plot_3d/Plot3D.cc index 1505b4e3da..7dfd30785c 100644 --- a/src/gui/plugins/plot_3d/Plot3D.cc +++ b/src/gui/plugins/plot_3d/Plot3D.cc @@ -39,7 +39,7 @@ #include "Plot3D.hh" -namespace ignition::gazebo::gui +namespace gz::sim::gui { /// \brief Private data class for Plot3D class Plot3DPrivate @@ -88,9 +88,9 @@ namespace ignition::gazebo::gui }; } -using namespace ignition; -using namespace ignition::gazebo; -using namespace ignition::gazebo::gui; +using namespace gz; +using namespace gz::sim; +using namespace gz::sim::gui; ///////////////////////////////////////////////// Plot3D::Plot3D() @@ -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); } ///////////////////////////////////////////////// @@ -165,7 +165,7 @@ void Plot3D::ClearPlot() // Clear previous plot if (this->dataPtr->markerMsg.point().size() > 0) { - this->dataPtr->markerMsg.set_action(ignition::msgs::Marker::DELETE_MARKER); + this->dataPtr->markerMsg.set_action(gz::msgs::Marker::DELETE_MARKER); this->dataPtr->node.Request("/marker", this->dataPtr->markerMsg); } } @@ -245,7 +245,7 @@ void Plot3D::Update(const UpdateInfo &, EntityComponentManager &_ecm) return; this->dataPtr->prevPos = point; - ignition::msgs::Set(this->dataPtr->markerMsg.add_point(), point); + gz::msgs::Set(this->dataPtr->markerMsg.add_point(), point); // Reduce message array if (this->dataPtr->markerMsg.point_size() > this->dataPtr->maxPoints) @@ -265,7 +265,7 @@ bool Plot3D::eventFilter(QObject *_obj, QEvent *_event) { if (!this->dataPtr->locked) { - if (_event->type() == gazebo::gui::events::EntitiesSelected::kType) + if (_event->type() == sim::gui::events::EntitiesSelected::kType) { auto event = reinterpret_cast(_event); if (event && !event->Data().empty()) @@ -274,7 +274,7 @@ bool Plot3D::eventFilter(QObject *_obj, QEvent *_event) } } - if (_event->type() == gazebo::gui::events::DeselectAllEntities::kType) + if (_event->type() == sim::gui::events::DeselectAllEntities::kType) { auto event = reinterpret_cast( _event); @@ -401,5 +401,5 @@ void Plot3D::SetMaxPoints(int _maxPoints) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::gui::Plot3D, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::gui::Plot3D, + gz::gui::Plugin) diff --git a/src/gui/plugins/plot_3d/Plot3D.hh b/src/gui/plugins/plot_3d/Plot3D.hh index b090abc171..d3d7836e5a 100644 --- a/src/gui/plugins/plot_3d/Plot3D.hh +++ b/src/gui/plugins/plot_3d/Plot3D.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_3DPLOT_HH_ -#define IGNITION_GAZEBO_GUI_3DPLOT_HH_ +#ifndef GZ_SIM_GUI_3DPLOT_HH_ +#define GZ_SIM_GUI_3DPLOT_HH_ #include @@ -24,9 +24,9 @@ #include "gz/gui/qt.h" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace gui { @@ -59,7 +59,7 @@ namespace gui /// After this number is reached, the older points start being deleted. /// Defaults to 1000. /// - class Plot3D : public ignition::gazebo::GuiSystem + class Plot3D : public gz::sim::GuiSystem { Q_OBJECT diff --git a/src/gui/plugins/plot_3d/Plot3D_TEST.cc b/src/gui/plugins/plot_3d/Plot3D_TEST.cc index 4b21eb7a0f..51ed796bf7 100644 --- a/src/gui/plugins/plot_3d/Plot3D_TEST.cc +++ b/src/gui/plugins/plot_3d/Plot3D_TEST.cc @@ -52,7 +52,7 @@ char* g_argv[] = reinterpret_cast(const_cast("dummy")), }; -using namespace ignition; +using namespace gz; /// \brief Tests for the joint position controller GUI plugin class Plot3D : public InternalFixture<::testing::Test> @@ -67,9 +67,9 @@ 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 + // Create GUI runner to handle sim::gui plugins IGN_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION - auto runner = new gazebo::GuiRunner("test"); + auto runner = new sim::GuiRunner("test"); IGN_UTILS_WARN_RESUME__DEPRECATED_DECLARATION runner->setParent(gui::App()); @@ -96,12 +96,12 @@ TEST_F(Plot3D, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Load)) ASSERT_NE(nullptr, win); // Get plugin - auto plugins = win->findChildren(); + auto plugins = win->findChildren(); ASSERT_EQ(plugins.size(), 1); auto plugin = plugins[0]; EXPECT_EQ("Plot3D!", plugin->Title()); - EXPECT_EQ(gazebo::kNullEntity, plugin->TargetEntity()); + EXPECT_EQ(sim::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/plotting/Plotting.cc b/src/gui/plugins/plotting/Plotting.cc index 902e0e5962..17892f0de2 100644 --- a/src/gui/plugins/plotting/Plotting.cc +++ b/src/gui/plugins/plotting/Plotting.cc @@ -39,7 +39,7 @@ #include "gz/sim/components/World.hh" #include "gz/sim/EntityComponentManager.hh" -namespace ignition::gazebo +namespace gz::sim { class PlottingPrivate { @@ -69,17 +69,17 @@ 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; +using namespace gz::sim; +using namespace gz::gui; ////////////////////////////////////////////////// PlotComponent::PlotComponent(const std::string &_type, - ignition::gazebo::Entity _entity, + gz::sim::Entity _entity, ComponentTypeId _typeId) : dataPtr(std::make_unique()) { @@ -140,7 +140,7 @@ PlotComponent::PlotComponent(const std::string &_type, this->dataPtr->data["heading"] = std::make_shared(); } else - ignwarn << "Invalid Plot Component Type:" << _type << std::endl; + gzwarn << "Invalid Plot Component Type:" << _type << std::endl; } ////////////////////////////////////////////////// @@ -153,7 +153,7 @@ void PlotComponent::RegisterChart(std::string _attribute, int _chart) { if (this->dataPtr->data.count(_attribute) == 0) { - ignwarn << "Invalid Plot Component Attribute" << std::endl; + gzwarn << "Invalid Plot Component Attribute" << std::endl; return; } this->dataPtr->data[_attribute]->AddChart(_chart); @@ -164,7 +164,7 @@ void PlotComponent::UnRegisterChart(std::string _attribute, int _chart) { if (this->dataPtr->data.count(_attribute) == 0) { - ignwarn << "Invalid Plot Component Attribute" << std::endl; + gzwarn << "Invalid Plot Component Attribute" << std::endl; return; } this->dataPtr->data[_attribute]->RemoveChart(_chart); @@ -239,7 +239,7 @@ void Plotting::LoadConfig(const tinyxml2::XMLElement *) } ////////////////////////////////////////////////// -void Plotting::SetData(std::string _Id, const ignition::math::Vector3d &_vector) +void Plotting::SetData(std::string _Id, const gz::math::Vector3d &_vector) { std::lock_guard lock(this->dataPtr->componentsMutex); this->dataPtr->components[_Id]->SetAttributeValue("x", _vector.X()); @@ -248,7 +248,7 @@ void Plotting::SetData(std::string _Id, const ignition::math::Vector3d &_vector) } ////////////////////////////////////////////////// -void Plotting::SetData(std::string _Id, const ignition::msgs::Light &_light) +void Plotting::SetData(std::string _Id, const gz::msgs::Light &_light) { std::lock_guard lock(this->dataPtr->componentsMutex); if (_light.has_specular()) @@ -303,7 +303,7 @@ void Plotting::SetData(std::string _Id, const ignition::msgs::Light &_light) } ////////////////////////////////////////////////// -void Plotting::SetData(std::string _Id, const ignition::math::Pose3d &_pose) +void Plotting::SetData(std::string _Id, const gz::math::Pose3d &_pose) { std::lock_guard lock(this->dataPtr->componentsMutex); this->dataPtr->components[_Id]->SetAttributeValue("x", _pose.Pos().X()); @@ -371,7 +371,7 @@ void Plotting::UnRegisterChartFromComponent(uint64_t _entity, uint64_t _typeId, { std::lock_guard lock(this->dataPtr->componentsMutex); std::string id = std::to_string(_entity) + "," + std::to_string(_typeId); - igndbg << "UnRegister [" << id << "]" << std::endl; + gzdbg << "UnRegister [" << id << "]" << std::endl; if (this->dataPtr->components.count(id) == 0) return; @@ -396,8 +396,8 @@ std::string Plotting::ComponentName(const uint64_t &_typeId) } ////////////////////////////////////////////////// -void Plotting::Update(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void Plotting::Update(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { std::lock_guard lock(this->dataPtr->componentsMutex); for (auto component : this->dataPtr->components) @@ -527,8 +527,8 @@ void Plotting::Update(const ignition::gazebo::UpdateInfo &_info, auto comp = _ecm.Component(entity); if (comp) { - ignition::msgs::Light lightMsgs = - convert(comp->Data()); + gz::msgs::Light lightMsgs = + convert(comp->Data()); this->SetData(component.first, lightMsgs); } } @@ -550,6 +550,6 @@ void Plotting::Update(const ignition::gazebo::UpdateInfo &_info, } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::Plotting, - ignition::gazebo::GuiSystem, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::Plotting, + gz::sim::GuiSystem, + gz::gui::Plugin) diff --git a/src/gui/plugins/plotting/Plotting.hh b/src/gui/plugins/plotting/Plotting.hh index 578bb7ff6c..2814df602d 100644 --- a/src/gui/plugins/plotting/Plotting.hh +++ b/src/gui/plugins/plotting/Plotting.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GUI_PLUGINS_PLOTTING_HH_ -#define IGNITION_GUI_PLUGINS_PLOTTING_HH_ +#ifndef GZ_GUI_PLUGINS_PLOTTING_HH_ +#define GZ_GUI_PLUGINS_PLOTTING_HH_ #include #include @@ -32,9 +32,9 @@ #include #include -namespace ignition { +namespace gz { -namespace gazebo { +namespace sim { class PlotComponentPrivate; @@ -47,7 +47,7 @@ class PlotComponent /// \param [in] _entity entity id of that component /// \param [in] _typeId type identifier unique to each component type public: PlotComponent(const std::string &_type, - ignition::gazebo::Entity _entity, + gz::sim::Entity _entity, ComponentTypeId _typeId); /// \brief Destructor @@ -76,12 +76,12 @@ 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 /// \return Entity ID - public: ignition::gazebo::Entity Entity(); + public: gz::sim::Entity Entity(); /// \brief Get the Component type ID /// \return component type ID @@ -95,7 +95,7 @@ class PlottingPrivate; /// \brief Physics data plotting handler that keeps track of the /// registered components, update them and update the plot -class Plotting : public ignition::gazebo::GuiSystem +class Plotting : public gz::sim::GuiSystem { Q_OBJECT /// \brief Constructor @@ -108,14 +108,14 @@ class Plotting : public ignition::gazebo::GuiSystem public: void LoadConfig(const tinyxml2::XMLElement *) override; // Documentation inherited - 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 Set the Component data of given id to the given vector /// \param [in] _Id Component Key of the components map /// \param [in] _vector Vector Data to be set to the component public: void SetData(std::string _Id, - const ignition::math::Vector3d &_vector); + const gz::math::Vector3d &_vector); /// \brief Set the Component data of given id to the given light /// \param [in] _Id Component Key of the components map @@ -127,7 +127,7 @@ class Plotting : public ignition::gazebo::GuiSystem /// \param [in] _Id Component Key of the components map /// \param [in] _pose Position Data to be set to the component public: void SetData(std::string _Id, - const ignition::math::Pose3d &_pose); + const gz::math::Pose3d &_pose); /// \brief Set the Component data of given id to the given spherical /// coordinates. diff --git a/src/gui/plugins/resource_spawner/ResourceSpawner.cc b/src/gui/plugins/resource_spawner/ResourceSpawner.cc index 045dbc07fd..6ec469d1ef 100644 --- a/src/gui/plugins/resource_spawner/ResourceSpawner.cc +++ b/src/gui/plugins/resource_spawner/ResourceSpawner.cc @@ -41,7 +41,7 @@ #include "gz/sim/EntityComponentManager.hh" -namespace ignition::gazebo +namespace gz::sim { class ResourceSpawnerPrivate { @@ -59,8 +59,8 @@ namespace ignition::gazebo /// resources public: PathModel ownerModel; - /// \brief Client used to download resources from Ignition Fuel. - public: std::unique_ptr + /// \brief Client used to download resources from Gazebo Fuel. + public: std::unique_ptr fuelClient = nullptr; /// \brief The map to cache resources after a search is made on an owner, @@ -74,8 +74,8 @@ namespace ignition::gazebo }; } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// PathModel::PathModel() : QStandardItemModel() @@ -207,17 +207,17 @@ 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(); + std::make_unique(); } ///////////////////////////////////////////////// @@ -482,7 +482,7 @@ void ResourceSpawner::OnDownloadFuelResource(const QString &_path, // Set the waiting cursor while the resource downloads QGuiApplication::setOverrideCursor(Qt::WaitCursor); if (this->dataPtr->fuelClient->DownloadModel( - ignition::common::URI(_path.toStdString()), localPath)) + gz::common::URI(_path.toStdString()), localPath)) { // Successful download, set thumbnail std::string thumbnailPath = common::joinPaths(localPath, "thumbnails"); @@ -515,7 +515,7 @@ void ResourceSpawner::OnDownloadFuelResource(const QString &_path, } else { - ignwarn << "Download failed. Try again." << std::endl; + gzwarn << "Download failed. Try again." << std::endl; } QGuiApplication::restoreOverrideCursor(); } @@ -540,7 +540,7 @@ void ResourceSpawner::LoadConfig(const tinyxml2::XMLElement *) "/gazebo/resource_paths/get", 5000, res, result); if (!executed || !result || res.data_size() < 1) { - ignwarn << "No paths found in IGN_GAZEBO_RESOURCE_PATH.\n"; + gzwarn << "No paths found in IGN_GAZEBO_RESOURCE_PATH.\n"; } // Add all local paths found in `IGN_GAZEBO_RESOURCE_PATH` to the qml list @@ -551,7 +551,7 @@ void ResourceSpawner::LoadConfig(const tinyxml2::XMLElement *) } auto servers = this->dataPtr->fuelClient->Config().Servers(); - ignmsg << "Please wait... Loading models from Fuel.\n"; + gzmsg << "Please wait... Loading models from Fuel.\n"; // Add notice for the user that fuel resources are being loaded this->dataPtr->ownerModel.AddPath("Please wait... Loading models from Fuel."); @@ -564,7 +564,7 @@ void ResourceSpawner::LoadConfig(const tinyxml2::XMLElement *) std::set ownerSet; for (auto const &server : servers) { - std::vector models; + std::vector models; for (auto iter = this->dataPtr->fuelClient->Models(server); iter; ++iter) { models.push_back(iter->Identification()); @@ -584,10 +584,10 @@ void ResourceSpawner::LoadConfig(const tinyxml2::XMLElement *) // If the resource is cached, we can go ahead and populate the // respective information if (this->dataPtr->fuelClient->CachedModel( - ignition::common::URI(id.UniqueName()), path)) + gz::common::URI(id.UniqueName()), path)) { resource.isDownloaded = true; - resource.sdfPath = ignition::common::joinPaths(path, "model.sdf"); + resource.sdfPath = gz::common::joinPaths(path, "model.sdf"); std::string thumbnailPath = common::joinPaths(path, "thumbnails"); this->SetThumbnail(thumbnailPath, resource); } @@ -604,7 +604,7 @@ void ResourceSpawner::LoadConfig(const tinyxml2::XMLElement *) { this->dataPtr->ownerModel.AddPath(resource); } - ignmsg << "Fuel resources loaded.\n"; + gzmsg << "Fuel resources loaded.\n"; }); t.detach(); } @@ -626,12 +626,12 @@ void ResourceSpawner::OnSortChosen(const QString &_sortType) ///////////////////////////////////////////////// void ResourceSpawner::OnResourceSpawn(const QString &_sdfPath) { - ignition::gui::events::SpawnFromPath event(_sdfPath.toStdString()); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::events::SpawnFromPath event(_sdfPath.toStdString()); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &event); } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::ResourceSpawner, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::ResourceSpawner, + gz::gui::Plugin) diff --git a/src/gui/plugins/resource_spawner/ResourceSpawner.hh b/src/gui/plugins/resource_spawner/ResourceSpawner.hh index 3e824e6a0f..879545a943 100644 --- a/src/gui/plugins/resource_spawner/ResourceSpawner.hh +++ b/src/gui/plugins/resource_spawner/ResourceSpawner.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_RESOURCE_SPAWNER_HH_ -#define IGNITION_GAZEBO_GUI_RESOURCE_SPAWNER_HH_ +#ifndef GZ_SIM_GUI_RESOURCE_SPAWNER_HH_ +#define GZ_SIM_GUI_RESOURCE_SPAWNER_HH_ #include #include @@ -25,9 +25,9 @@ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class ResourceSpawnerPrivate; @@ -141,7 +141,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 fd76d44ff8..cd2dbf6ace 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -77,13 +77,13 @@ std::condition_variable g_renderCv; Q_DECLARE_METATYPE(std::string) -Q_DECLARE_METATYPE(ignition::gazebo::RenderSync*) +Q_DECLARE_METATYPE(gz::sim::RenderSync*) -namespace ignition +namespace gz { -namespace gazebo +namespace sim { -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { /// \brief Helper to store selection requests to be handled in the render /// thread by `IgnRenderer::HandleEntitySelection`. // SelectEntities @@ -157,7 +157,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public: bool zPressed = false; /// \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. @@ -208,7 +208,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 follow public: std::string followTarget; @@ -284,8 +284,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 visual generated from the spawnSdfString / spawnSdfPath public: rendering::NodePtr spawnPreview = nullptr; @@ -396,7 +396,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// /// /// For more info see - /// https://github.com/ignitionrobotics/ign-rendering/issues/304 + /// https://github.com/gazebosim/gz-rendering/issues/304 class RenderSync { /// \brief Cond. variable to synchronize rendering on specific events @@ -567,8 +567,8 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { } } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; QList RenderWindowItemPrivate::threads; @@ -640,7 +640,7 @@ IgnRenderer::IgnRenderer() std::string recorderStatsTopic = "/gui/record_video/stats"; this->dataPtr->recorderStatsPub = this->dataPtr->node.Advertise(recorderStatsTopic); - ignmsg << "Video recorder stats topic advertised on [" + gzmsg << "Video recorder stats topic advertised on [" << recorderStatsTopic << "]" << std::endl; } @@ -660,7 +660,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) rendering::ScenePtr scene = this->dataPtr->renderUtil.Scene(); if (!scene) { - ignwarn << "Scene is null. The render step will not occur in Scene3D." + gzwarn << "Scene is null. The render step will not occur in Scene3D." << std::endl; return; } @@ -794,7 +794,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) std::chrono::steady_clock::duration dt; dt = t - this->dataPtr->recordStartTime; int64_t sec, nsec; - std::tie(sec, nsec) = ignition::math::durationToSecNsec(dt); + std::tie(sec, nsec) = gz::math::durationToSecNsec(dt); msgs::Time msg; msg.set_sec(sec); msg.set_nsec(nsec); @@ -805,17 +805,17 @@ void IgnRenderer::Render(RenderSync *_renderSync) else { if (this->dataPtr->recordVideoUseSimTime) - ignmsg << "Recording video using sim time." << std::endl; + gzmsg << "Recording video using sim time." << std::endl; if (this->dataPtr->recordVideoLockstep) { - ignmsg << "Recording video in lockstep mode" << std::endl; + gzmsg << "Recording video in lockstep mode" << std::endl; if (!this->dataPtr->recordVideoUseSimTime) { - ignwarn << "It is recommended to set to true " + gzwarn << "It is recommended to set to true " << "when recording video in lockstep mode." << std::endl; } } - ignmsg << "Recording video using bitrate: " + gzmsg << "Recording video using bitrate: " << this->dataPtr->recordVideoBitrate << std::endl; this->dataPtr->videoEncoder.Start(this->dataPtr->recordVideoFormat, this->dataPtr->recordVideoSavePath, width, height, 25, @@ -847,7 +847,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) } else { - ignerr << "Unable to move to target. Target: '" + gzerr << "Unable to move to target. Target: '" << this->dataPtr->moveToTarget << "' not found" << std::endl; this->dataPtr->moveToTarget.clear(); } @@ -926,7 +926,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) } else if (!this->dataPtr->followTargetWait) { - ignerr << "Unable to follow target. Target: '" + gzerr << "Unable to follow target. Target: '" << this->dataPtr->followTarget << "' not found" << std::endl; this->dataPtr->followTarget.clear(); } @@ -999,7 +999,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) } else { - ignwarn << "Failed to spawn: no SDF string or path" << std::endl; + gzwarn << "Failed to spawn: no SDF string or path" << std::endl; } this->dataPtr->isPlacing = this->GeneratePreview(root); this->dataPtr->isSpawning = false; @@ -1034,7 +1034,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) } else { - ignerr << "Unable to find node name [" + gzerr << "Unable to find node name [" << this->dataPtr->viewTransparentTarget << "] to view as transparent" << std::endl; } @@ -1060,7 +1060,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) } else { - ignerr << "Unable to find node name [" + gzerr << "Unable to find node name [" << this->dataPtr->viewCOMTarget << "] to view center of mass" << std::endl; } @@ -1086,7 +1086,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) } else { - ignerr << "Unable to find node name [" + gzerr << "Unable to find node name [" << this->dataPtr->viewInertiaTarget << "] to view inertia" << std::endl; } @@ -1112,7 +1112,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) } else { - ignerr << "Unable to find node name [" + gzerr << "Unable to find node name [" << this->dataPtr->viewJointsTarget << "] to view joints" << std::endl; } @@ -1138,7 +1138,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) } else { - ignerr << "Unable to find node name [" + gzerr << "Unable to find node name [" << this->dataPtr->viewWireframesTarget << "] to view wireframes" << std::endl; } @@ -1164,7 +1164,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) } else { - ignerr << "Unable to find node name [" + gzerr << "Unable to find node name [" << this->dataPtr->viewCollisionsTarget << "] to view collisions" << std::endl; } @@ -1173,11 +1173,11 @@ void IgnRenderer::Render(RenderSync *_renderSync) } } - 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); } @@ -1186,7 +1186,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) g_renderCv.notify_one(); // TODO(anyone) implement a SwapFromThread for parallel command generation - // See https://github.com/ignitionrobotics/ign-rendering/issues/304 + // See https://github.com/gazebosim/gz-rendering/issues/304 // if( bForcedSerialization ) // this->dataPtr->camera->SwapFromThread(); // else @@ -1202,7 +1202,7 @@ bool IgnRenderer::GeneratePreview(const sdf::Root &_sdf) if (nullptr == _sdf.Model() && nullptr == _sdf.Light()) { - ignwarn << "Only model entities can be spawned at the moment." << std::endl; + gzwarn << "Only model entities can be spawned at the moment." << std::endl; this->TerminateSpawnPreview(); return false; } @@ -1212,7 +1212,7 @@ bool IgnRenderer::GeneratePreview(const sdf::Root &_sdf) // Only preview first model sdf::Model model = *(_sdf.Model()); this->dataPtr->spawnPreviewPose = model.RawPose(); - model.SetName(ignition::common::Uuid().String()); + model.SetName(gz::common::Uuid().String()); Entity modelId = this->UniqueId(); if (!modelId) { @@ -1228,7 +1228,7 @@ bool IgnRenderer::GeneratePreview(const sdf::Root &_sdf) for (auto j = 0u; j < model.LinkCount(); j++) { sdf::Link link = *(model.LinkByIndex(j)); - link.SetName(ignition::common::Uuid().String()); + link.SetName(gz::common::Uuid().String()); Entity linkId = this->UniqueId(); if (!linkId) { @@ -1241,7 +1241,7 @@ bool IgnRenderer::GeneratePreview(const sdf::Root &_sdf) for (auto k = 0u; k < link.VisualCount(); k++) { sdf::Visual visual = *(link.VisualByIndex(k)); - visual.SetName(ignition::common::Uuid().String()); + visual.SetName(gz::common::Uuid().String()); Entity visualId = this->UniqueId(); if (!visualId) { @@ -1259,7 +1259,7 @@ bool IgnRenderer::GeneratePreview(const sdf::Root &_sdf) // Only preview first model sdf::Light light = *(_sdf.Light()); this->dataPtr->spawnPreviewPose = light.RawPose(); - light.SetName(ignition::common::Uuid().String()); + light.SetName(gz::common::Uuid().String()); Entity lightVisualId = this->UniqueId(); if (!lightVisualId) { @@ -1327,9 +1327,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); } } @@ -1343,9 +1343,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); } } @@ -1363,9 +1363,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); } } @@ -1443,17 +1443,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(); } } @@ -1550,11 +1550,11 @@ void IgnRenderer::HandleModelPlacement() this->TerminateSpawnPreview(); math::Pose3d modelPose = this->dataPtr->spawnPreviewPose; - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error creating model" << std::endl; + gzerr << "Error creating model" << std::endl; }; math::Vector3d pos = this->ScreenToPlane(this->dataPtr->mouseEvent.Pos()); pos.Z(modelPose.Pos().Z()); @@ -1569,7 +1569,7 @@ void IgnRenderer::HandleModelPlacement() } else { - ignwarn << "Failed to find SDF string or file path" << std::endl; + gzwarn << "Failed to find SDF string or file path" << std::endl; } req.set_allow_renaming(true); msgs::Set(req.mutable_pose(), math::Pose3d(pos, modelPose.Rot())); @@ -1583,7 +1583,7 @@ void IgnRenderer::HandleModelPlacement() this->dataPtr->createCmdService); if (this->dataPtr->createCmdService.empty()) { - ignerr << "Failed to create valid create command service for world [" + gzerr << "Failed to create valid create command service for world [" << this->worldName <<"]" << std::endl; return; } @@ -1621,7 +1621,7 @@ void IgnRenderer::DeselectAllEntities(bool _sendEvent) { if (this->dataPtr->renderThreadId != std::this_thread::get_id()) { - ignwarn << "Making render calls from outside the render thread" + gzwarn << "Making render calls from outside the render thread" << std::endl; } @@ -1629,9 +1629,9 @@ void IgnRenderer::DeselectAllEntities(bool _sendEvent) if (_sendEvent) { - ignition::gazebo::gui::events::DeselectAllEntities deselectEvent; - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::sim::gui::events::DeselectAllEntities deselectEvent; + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &deselectEvent); } } @@ -1665,19 +1665,19 @@ double IgnRenderer::SnapValue( ///////////////////////////////////////////////// void IgnRenderer::SnapPoint( - ignition::math::Vector3d &_point, math::Vector3d &_snapVals, + gz::math::Vector3d &_point, math::Vector3d &_snapVals, double _sensitivity) const { if (_snapVals.X() <= 0 || _snapVals.Y() <= 0 || _snapVals.Z() <= 0) { - ignerr << "Interval distance must be greater than 0" + gzerr << "Interval distance must be greater than 0" << std::endl; return; } if (_sensitivity < 0 || _sensitivity > 1.0) { - ignerr << "Sensitivity must be between 0 and 1" << std::endl; + gzerr << "Sensitivity must be between 0 and 1" << std::endl; return; } @@ -1717,7 +1717,7 @@ void IgnRenderer::HandleMouseTransformControl() { if (this->dataPtr->renderThreadId != std::this_thread::get_id()) { - ignwarn << "Making render calls from outside the render thread" + gzwarn << "Making render calls from outside the render thread" << std::endl; } @@ -1772,7 +1772,7 @@ void IgnRenderer::HandleMouseTransformControl() // check if the visual is an axis in the gizmo visual math::Vector3d axis = this->dataPtr->transformControl.AxisById(visual->Id()); - if (axis != ignition::math::Vector3d::Zero) + if (axis != gz::math::Vector3d::Zero) { // start the transform process this->dataPtr->transformControl.SetActiveAxis(axis); @@ -1790,14 +1790,14 @@ void IgnRenderer::HandleMouseTransformControl() { if (this->dataPtr->transformControl.Node()) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error setting pose" << std::endl; + gzerr << "Error setting pose" << std::endl; }; rendering::NodePtr node = this->dataPtr->transformControl.Node(); - ignition::msgs::Pose req; + gz::msgs::Pose req; req.set_name(node->Name()); msgs::Set(req.mutable_position(), node->WorldPosition()); msgs::Set(req.mutable_orientation(), node->WorldRotation()); @@ -1810,7 +1810,7 @@ void IgnRenderer::HandleMouseTransformControl() this->dataPtr->poseCmdService); if (this->dataPtr->poseCmdService.empty()) { - ignerr << "Failed to create valid pose command service for world [" + gzerr << "Failed to create valid pose command service for world [" << this->worldName <<"]" << std::endl; return; } @@ -1840,7 +1840,7 @@ void IgnRenderer::HandleMouseTransformControl() // check if the visual is an axis in the gizmo visual math::Vector3d axis = this->dataPtr->transformControl.AxisById(visual->Id()); - if (axis == ignition::math::Vector3d::Zero) + if (axis == gz::math::Vector3d::Zero) { auto topVis = this->dataPtr->renderUtil.SceneManager().TopLevelVisual(visual); @@ -1897,7 +1897,7 @@ void IgnRenderer::HandleMouseTransformControl() this->dataPtr->renderUtil.SceneManager().NodeById(nodeId); if (!target) { - ignwarn << "Failed to find node with ID [" << nodeId << "]" + gzwarn << "Failed to find node with ID [" << nodeId << "]" << std::endl; return; } @@ -2006,7 +2006,7 @@ void IgnRenderer::HandleMouseViewControl() if (this->dataPtr->renderThreadId != std::this_thread::get_id()) { - ignwarn << "Making render calls from outside the render thread" + gzwarn << "Making render calls from outside the render thread" << std::endl; } @@ -2023,7 +2023,7 @@ void IgnRenderer::HandleMouseViewControl() } else { - ignerr << "Unknown view controller: " << this->dataPtr->viewController + gzerr << "Unknown view controller: " << this->dataPtr->viewController << ". Defaulting to orbit view controller" << std::endl; this->dataPtr->viewController = "orbit"; this->dataPtr->viewControl = &this->dataPtr->orbitViewControl; @@ -2058,7 +2058,7 @@ void IgnRenderer::HandleMouseViewControl() // unset the target on release (by setting to inf) else if (this->dataPtr->mouseEvent.Type() == common::MouseEvent::RELEASE) { - this->dataPtr->target = ignition::math::INF_D; + this->dataPtr->target = gz::math::INF_D; } // Pan with left button @@ -2110,7 +2110,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(); @@ -2160,7 +2160,7 @@ void IgnRenderer::Destroy() // If that was the last sensor, destroy scene if (scene->SensorCount() == 0) { - igndbg << "Destroy scene [" << scene->Name() << "]" << std::endl; + gzdbg << "Destroy scene [" << scene->Name() << "]" << std::endl; engine->DestroyScene(scene); // TODO(anyone) If that was the last scene, terminate engine? @@ -2211,7 +2211,7 @@ void IgnRenderer::UpdateSelectedEntity(const rendering::NodePtr &_node, if (this->dataPtr->renderThreadId != std::this_thread::get_id()) { - ignwarn << "Making render calls from outside the render thread" + gzwarn << "Making render calls from outside the render thread" << std::endl; } @@ -2256,10 +2256,10 @@ void IgnRenderer::UpdateSelectedEntity(const rendering::NodePtr &_node, // Notify other widgets of the currently selected entities if (_sendEvent || deselectedAll) { - ignition::gazebo::gui::events::EntitiesSelected selectEvent( + gz::sim::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); } } @@ -2277,7 +2277,7 @@ void IgnRenderer::SetTransformMode(const std::string &_mode) else if (_mode == "scale") this->dataPtr->transformMode = rendering::TransformMode::TM_SCALE; else - ignerr << "Unknown transform mode: [" << _mode << "]" << std::endl; + gzerr << "Unknown transform mode: [" << _mode << "]" << std::endl; // Update selected entities if transform control is changed if (!this->dataPtr->renderUtil.SelectedEntities().empty()) @@ -2530,7 +2530,7 @@ math::Vector3d IgnRenderer::ScreenToPlane( this->dataPtr->rayQuery->SetFromCamera( this->dataPtr->camera, math::Vector2d(nx, ny)); - ignition::math::Planed plane(ignition::math::Vector3d(0, 0, 1), 0); + gz::math::Planed plane(gz::math::Vector3d(0, 0, 1), 0); math::Vector3d origin = this->dataPtr->rayQuery->Origin(); math::Vector3d direction = this->dataPtr->rayQuery->Direction(); @@ -2610,7 +2610,7 @@ void RenderThread::RenderNext(RenderSync *_renderSync) // check if engine has been successfully initialized if (!this->ignRenderer.initialized) { - ignerr << "Unable to initialize renderer" << std::endl; + gzerr << "Unable to initialize renderer" << std::endl; return; } @@ -2650,7 +2650,7 @@ void RenderThread::SizeChanged() auto item = qobject_cast(this->sender()); if (!item) { - ignerr << "Internal error, sender is not QQuickItem." << std::endl; + gzerr << "Internal error, sender is not QQuickItem." << std::endl; return; } @@ -2714,7 +2714,7 @@ void TextureNode::PrepareNode() newId, sz, QQuickWindow::TextureIsOpaque); #else // TODO(anyone) Use createTextureFromNativeObject - // https://github.com/ignitionrobotics/ign-gui/issues/113 + // https://github.com/gazebosim/gz-gui/issues/113 #ifndef _WIN32 # pragma GCC diagnostic push # pragma GCC diagnostic ignored "-Wdeprecated-declarations" @@ -2742,7 +2742,7 @@ void TextureNode::PrepareNode() // However we need to synchronize the threads when resolution changes, // and we're also currently doing everything in lockstep (i.e. both Qt // and worker thread are serialized, - // see https://github.com/ignitionrobotics/ign-rendering/issues/304 ) + // see https://github.com/gazebosim/gz-rendering/issues/304 ) // // We need to emit even if newId == 0 because it's safe as long as both // threads are forcefully serialized and otherwise we may get a @@ -2768,7 +2768,7 @@ RenderWindowItem::RenderWindowItem(QQuickItem *_parent) // is non-trivial since the plugin's internals have changed. Keeping this // shortcut here for now, and revisiting later specifically for ign-gazebo5 // onwards. - // See https://github.com/ignitionrobotics/ign-gazebo/issues/1254 + // See https://github.com/gazebosim/gz-sim/issues/1254 static bool done{false}; if (done) { @@ -2936,7 +2936,7 @@ RenderUtil *RenderWindowItem::RenderUtil() const Scene3D::Scene3D() : GuiSystem(), dataPtr(new Scene3DPrivate) { - ignwarn << "The GzScene3D plugin is deprecated on v6 and will be removed on " + gzwarn << "The GzScene3D plugin is deprecated on v6 and will be removed on " << "v7. Use MinimalScene together with other plugins as needed." << std::endl; qmlRegisterType("RenderWindow", 1, 0, "RenderWindow"); @@ -2952,11 +2952,11 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem) // is non-trivial since the plugin's internals have changed. Keeping this // shortcut here for now, and revisiting later specifically for ign-gazebo5 // onwards. - // See https://github.com/ignitionrobotics/ign-gazebo/issues/1254 + // See https://github.com/gazebosim/gz-sim/issues/1254 static bool done{false}; if (done) { - ignerr << "Only one Scene3D is supported per process at the moment." + gzerr << "Only one Scene3D is supported per process at the moment." << std::endl; return; } @@ -2965,7 +2965,7 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem) auto renderWindow = this->PluginItem()->findChild(); if (!renderWindow) { - ignerr << "Unable to find Render Window item. " + gzerr << "Unable to find Render Window item. " << "Render window will not be created" << std::endl; return; } @@ -3025,7 +3025,7 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem) { this->dataPtr->renderUtil->SetSkyEnabled(true); if (!elem->NoChildren()) - ignwarn << "Child elements of are not supported yet" << std::endl; + gzwarn << "Child elements of are not supported yet" << std::endl; } if (auto elem = _pluginElem->FirstChildElement("camera_pose")) @@ -3049,7 +3049,7 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem) if (gain >= 0 && gain <= 1.0) renderWindow->SetFollowPGain(gain); else - ignerr << "Camera follow p gain outside of range [0, 1]" << std::endl; + gzerr << "Camera follow p gain outside of range [0, 1]" << std::endl; } if (auto targetElem = elem->FirstChildElement("target")) @@ -3069,7 +3069,7 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem) renderWindow->SetFollowWorldFrame(false); else { - ignerr << "Faild to parse value: " << worldFrameStr + gzerr << "Faild to parse value: " << worldFrameStr << std::endl; } } @@ -3091,7 +3091,7 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem) bool useSimTime = false; if (useSimTimeElem->QueryBoolText(&useSimTime) != tinyxml2::XML_SUCCESS) { - ignerr << "Faild to parse value: " + gzerr << "Faild to parse value: " << useSimTimeElem->GetText() << std::endl; } else @@ -3104,7 +3104,7 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem) bool lockstep = false; if (lockstepElem->QueryBoolText(&lockstep) != tinyxml2::XML_SUCCESS) { - ignerr << "Failed to parse value: " + gzerr << "Failed to parse value: " << lockstepElem->GetText() << std::endl; } else @@ -3124,7 +3124,7 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem) } else { - ignerr << "Video recorder bitrate must be larger than 0" + gzerr << "Video recorder bitrate must be larger than 0" << std::endl; } } @@ -3136,8 +3136,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(); } } @@ -3161,7 +3161,7 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem) "/gui/transform_mode"; this->dataPtr->node.Advertise(this->dataPtr->transformModeService, &Scene3D::OnTransformMode, this); - ignmsg << "Transform mode service on [" + gzmsg << "Transform mode service on [" << this->dataPtr->transformModeService << "]" << std::endl; // video recorder @@ -3169,28 +3169,28 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem) "/gui/record_video"; this->dataPtr->node.Advertise(this->dataPtr->recordVideoService, &Scene3D::OnRecordVideo, this); - ignmsg << "Record video service on [" + gzmsg << "Record video service on [" << this->dataPtr->recordVideoService << "]" << std::endl; // move to this->dataPtr->moveToService = "/gui/move_to"; this->dataPtr->node.Advertise(this->dataPtr->moveToService, &Scene3D::OnMoveTo, this); - ignmsg << "Move to service on [" + gzmsg << "Move to service on [" << this->dataPtr->moveToService << "]" << std::endl; // follow this->dataPtr->followService = "/gui/follow"; this->dataPtr->node.Advertise(this->dataPtr->followService, &Scene3D::OnFollow, this); - ignmsg << "Follow service on [" + gzmsg << "Follow service on [" << this->dataPtr->followService << "]" << std::endl; // follow offset this->dataPtr->followOffsetService = "/gui/follow/offset"; this->dataPtr->node.Advertise(this->dataPtr->followOffsetService, &Scene3D::OnFollowOffset, this); - ignmsg << "Follow offset service on [" + gzmsg << "Follow offset service on [" << this->dataPtr->followOffsetService << "]" << std::endl; // view angle @@ -3198,7 +3198,7 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem) "/gui/view_angle"; this->dataPtr->node.Advertise(this->dataPtr->viewAngleService, &Scene3D::OnViewAngle, this); - ignmsg << "View angle service on [" + gzmsg << "View angle service on [" << this->dataPtr->viewAngleService << "]" << std::endl; // move to pose service @@ -3206,69 +3206,69 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem) "/gui/move_to/pose"; this->dataPtr->node.Advertise(this->dataPtr->moveToPoseService, &Scene3D::OnMoveToPose, this); - ignmsg << "Move to pose service on [" + gzmsg << "Move to pose service on [" << this->dataPtr->moveToPoseService << "]" << std::endl; // camera position topic this->dataPtr->cameraPoseTopic = "/gui/camera/pose"; this->dataPtr->cameraPosePub = this->dataPtr->node.Advertise(this->dataPtr->cameraPoseTopic); - ignmsg << "Camera pose topic advertised on [" + gzmsg << "Camera pose topic advertised on [" << this->dataPtr->cameraPoseTopic << "]" << std::endl; // view as transparent service this->dataPtr->viewTransparentService = "/gui/view/transparent"; this->dataPtr->node.Advertise(this->dataPtr->viewTransparentService, &Scene3D::OnViewTransparent, this); - ignmsg << "View as transparent service on [" + gzmsg << "View as transparent service on [" << this->dataPtr->viewTransparentService << "]" << std::endl; // view center of mass service this->dataPtr->viewCOMService = "/gui/view/com"; this->dataPtr->node.Advertise(this->dataPtr->viewCOMService, &Scene3D::OnViewCOM, this); - ignmsg << "View center of mass service on [" + gzmsg << "View center of mass service on [" << this->dataPtr->viewCOMService << "]" << std::endl; // view inertia service this->dataPtr->viewInertiaService = "/gui/view/inertia"; this->dataPtr->node.Advertise(this->dataPtr->viewInertiaService, &Scene3D::OnViewInertia, this); - ignmsg << "View inertia service on [" + gzmsg << "View inertia service on [" << this->dataPtr->viewInertiaService << "]" << std::endl; // view joints service this->dataPtr->viewJointsService = "/gui/view/joints"; this->dataPtr->node.Advertise(this->dataPtr->viewJointsService, &Scene3D::OnViewJoints, this); - ignmsg << "View joints service on [" + gzmsg << "View joints service on [" << this->dataPtr->viewJointsService << "]" << std::endl; // view wireframes service this->dataPtr->viewWireframesService = "/gui/view/wireframes"; this->dataPtr->node.Advertise(this->dataPtr->viewWireframesService, &Scene3D::OnViewWireframes, this); - ignmsg << "View wireframes service on [" + gzmsg << "View wireframes service on [" << this->dataPtr->viewWireframesService << "]" << std::endl; // view collisions service this->dataPtr->viewCollisionsService = "/gui/view/collisions"; this->dataPtr->node.Advertise(this->dataPtr->viewCollisionsService, &Scene3D::OnViewCollisions, this); - ignmsg << "View collisions service on [" + gzmsg << "View collisions service on [" << this->dataPtr->viewCollisionsService << "]" << std::endl; // camera view control mode this->dataPtr->cameraViewControlService = "/gui/camera/view_control"; this->dataPtr->node.Advertise(this->dataPtr->cameraViewControlService, &Scene3D::OnViewControl, this); - ignmsg << "Camera view controller topic advertised on [" + gzmsg << "Camera view controller topic advertised on [" << this->dataPtr->cameraViewControlService << "]" << 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); } ////////////////////////////////////////////////// @@ -3305,7 +3305,7 @@ void Scene3D::Update(const UpdateInfo &_info, } else { - igndbg << "RenderEngineGuiPlugin component not found, " + gzdbg << "RenderEngineGuiPlugin component not found, " "render engine won't be set from the ECM " << std::endl; } } @@ -3534,11 +3534,11 @@ void Scene3D::OnDropped(const QString &_drop, int _mouseX, int _mouseY) return; } - std::function cb = - [](const ignition::msgs::Boolean &_res, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &_res, const bool _result) { if (!_result || !_res.data()) - ignerr << "Error creating dropped entity." << std::endl; + gzerr << "Error creating dropped entity." << std::endl; }; auto renderWindow = this->PluginItem()->findChild(); @@ -3677,10 +3677,10 @@ bool Scene3D::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::EntitiesSelected::kType) + gz::sim::gui::events::EntitiesSelected::kType) { auto selectedEvent = - reinterpret_cast( + reinterpret_cast( _event); if (selectedEvent) { @@ -3711,10 +3711,10 @@ bool Scene3D::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::DeselectAllEntities::kType) + gz::sim::gui::events::DeselectAllEntities::kType) { auto deselectEvent = - reinterpret_cast( + reinterpret_cast( _event); // If the event is from the user, update render util state @@ -3725,9 +3725,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) { @@ -3738,20 +3738,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(); @@ -3759,10 +3759,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(); @@ -3965,7 +3965,7 @@ void RenderWindowItem::SetVisibilityMask(uint32_t _mask) } ///////////////////////////////////////////////// -void RenderWindowItem::OnHovered(const ignition::math::Vector2i &_hoverPos) +void RenderWindowItem::OnHovered(const gz::math::Vector2i &_hoverPos) { this->dataPtr->renderThread->ignRenderer.NewHoverEvent(_hoverPos); } @@ -3981,7 +3981,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); @@ -3993,7 +3993,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 @@ -4010,7 +4010,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; @@ -4084,5 +4084,5 @@ void RenderWindowItem::HandleKeyRelease(QKeyEvent *_e) // // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::Scene3D, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::Scene3D, + gz::gui::Plugin) diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index a81bf20f9b..0e0ffe87b7 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_SCENE3D_HH_ -#define IGNITION_GAZEBO_GUI_SCENE3D_HH_ +#ifndef GZ_SIM_GUI_SCENE3D_HH_ +#define GZ_SIM_GUI_SCENE3D_HH_ #include #include @@ -45,12 +45,12 @@ #include "gz/gui/qt.h" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { class IgnRendererPrivate; class RenderWindowItemPrivate; class Scene3DPrivate; @@ -60,7 +60,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// It is possible to orbit the camera around the scene with /// the mouse. Use other plugins to manage objects in the scene. /// - /// Only one plugin displaying an Ignition Rendering scene can be used at a + /// Only one plugin displaying a Gazebo Rendering scene can be used at a /// time. /// /// ## Configuration @@ -79,7 +79,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// * \ : Camera follow movement p gain. /// * \ : Target to follow. /// * \ : Optional starting the window in fullscreen. - class Scene3D : public ignition::gazebo::GuiSystem + class Scene3D : public gz::sim::GuiSystem { Q_OBJECT @@ -825,7 +825,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/scene_manager/GzSceneManager.cc b/src/gui/plugins/scene_manager/GzSceneManager.cc index b7b3982ff3..3ae1e74e81 100644 --- a/src/gui/plugins/scene_manager/GzSceneManager.cc +++ b/src/gui/plugins/scene_manager/GzSceneManager.cc @@ -41,11 +41,11 @@ #include "gz/sim/gui/GuiEvents.hh" #include "gz/sim/rendering/RenderUtil.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { /// \brief Private data class for GzSceneManager class GzSceneManagerPrivate { @@ -78,8 +78,8 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { } } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// GzSceneManager::GzSceneManager() @@ -100,15 +100,15 @@ void GzSceneManager::LoadConfig(const tinyxml2::XMLElement *) if (done) { std::string msg{"Only one GzSceneManager is supported at a time."}; - ignerr << msg << std::endl; + gzerr << msg << std::endl; QQmlProperty::write(this->PluginItem(), "message", QString::fromStdString(msg)); return; } done = true; - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); this->dataPtr->initialized = true; } @@ -162,10 +162,10 @@ void GzSceneManager::Update(const UpdateInfo &_info, } for (const auto &it : pluginElems) { - ignition::gazebo::gui::events::VisualPlugin visualPluginEvent( + gz::sim::gui::events::VisualPlugin visualPluginEvent( it.first, it.second); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &visualPluginEvent); } @@ -186,22 +186,22 @@ void GzSceneManager::Update(const UpdateInfo &_info, return true; }); - ignition::gazebo::gui::events::NewRemovedEntities removedEvent( + gz::sim::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(); } else if (_event->type() == - ignition::gazebo::gui::events::GuiNewRemovedEntities::kType) + gz::sim::gui::events::GuiNewRemovedEntities::kType) { std::lock_guard lock(this->dataPtr->newRemovedEntityMutex); auto addedRemovedEvent = @@ -231,10 +231,10 @@ 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; + gzerr << "Internal error: no GuiRunner found." << std::endl; } else { @@ -246,5 +246,5 @@ void GzSceneManagerPrivate::OnRender() } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::GzSceneManager, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::GzSceneManager, + gz::gui::Plugin) diff --git a/src/gui/plugins/scene_manager/GzSceneManager.hh b/src/gui/plugins/scene_manager/GzSceneManager.hh index c84f33322e..0124d1d725 100644 --- a/src/gui/plugins/scene_manager/GzSceneManager.hh +++ b/src/gui/plugins/scene_manager/GzSceneManager.hh @@ -15,25 +15,25 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_GZSCENEMANAGER_HH_ -#define IGNITION_GAZEBO_GUI_GZSCENEMANAGER_HH_ +#ifndef GZ_SIM_GUI_GZSCENEMANAGER_HH_ +#define GZ_SIM_GUI_GZSCENEMANAGER_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { class GzSceneManagerPrivate; /// \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 51ca28c907..f8be006db9 100644 --- a/src/gui/plugins/select_entities/SelectEntities.cc +++ b/src/gui/plugins/select_entities/SelectEntities.cc @@ -40,9 +40,9 @@ #include "SelectEntities.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace gui { @@ -64,7 +64,7 @@ struct SelectionHelper } /// \brief Private data class for SelectEntities -class ignition::gazebo::gui::SelectEntitiesPrivate +class gz::sim::gui::SelectEntitiesPrivate { /// \brief Initialize the plugin, attaching to a camera. public: void Initialize(); @@ -121,10 +121,10 @@ class ignition::gazebo::gui::SelectEntitiesPrivate /// \brief A map of entity ids and wire boxes public: std::unordered_map wireBoxes; + gz::rendering::WireBoxPtr> wireBoxes; /// \brief MouseEvent - public: ignition::common::MouseEvent mouseEvent; + public: gz::common::MouseEvent mouseEvent; /// \brief is the mouse modify ? public: bool mouseDirty = false; @@ -142,9 +142,9 @@ class ignition::gazebo::gui::SelectEntitiesPrivate public: bool isSpawning{false}; }; -using namespace ignition; -using namespace gazebo; -using namespace gazebo::gui; +using namespace gz; +using namespace sim; +using namespace sim::gui; ///////////////////////////////////////////////// void SelectEntitiesPrivate::HandleEntitySelection() @@ -163,7 +163,7 @@ void SelectEntitiesPrivate::HandleEntitySelection() if (nullptr == visualToHighLight) { - ignerr << "Failed to get visual with ID [" + gzerr << "Failed to get visual with ID [" << this->selectedEntitiesIDNew[i] << "]" << std::endl; continue; } @@ -185,10 +185,10 @@ void SelectEntitiesPrivate::HandleEntitySelection() this->HighlightNode(visualToHighLight); - ignition::gazebo::gui::events::EntitiesSelected selectEvent( + gz::sim::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; @@ -254,7 +254,7 @@ void SelectEntitiesPrivate::LowlightNode(const rendering::VisualPtr &_visual) } if (this->wireBoxes.find(entityId) != this->wireBoxes.end()) { - ignition::rendering::WireBoxPtr wireBox = this->wireBoxes[entityId]; + gz::rendering::WireBoxPtr wireBox = this->wireBoxes[entityId]; auto visParent = wireBox->Parent(); if (visParent) visParent->SetVisible(false); @@ -266,7 +266,7 @@ void SelectEntitiesPrivate::HighlightNode(const rendering::VisualPtr &_visual) { if (nullptr == _visual) { - ignerr << "Failed to highlight null visual." << std::endl; + gzerr << "Failed to highlight null visual." << std::endl; return; } @@ -294,12 +294,12 @@ void SelectEntitiesPrivate::HighlightNode(const rendering::VisualPtr &_visual) white->SetEmissive(1.0, 1.0, 1.0); } - ignition::rendering::WireBoxPtr wireBox = this->scene->CreateWireBox(); - ignition::math::AxisAlignedBox aabb = _visual->LocalBoundingBox(); + gz::rendering::WireBoxPtr wireBox = this->scene->CreateWireBox(); + gz::math::AxisAlignedBox aabb = _visual->LocalBoundingBox(); wireBox->SetBox(aabb); // Create visual and add wire box - ignition::rendering::VisualPtr wireBoxVis = this->scene->CreateVisual(); + gz::rendering::VisualPtr wireBoxVis = this->scene->CreateVisual(); wireBoxVis->SetInheritScale(false); wireBoxVis->AddGeometry(wireBox); wireBoxVis->SetMaterial(white, false); @@ -308,12 +308,12 @@ void SelectEntitiesPrivate::HighlightNode(const rendering::VisualPtr &_visual) // Add wire box to map for setting visibility this->wireBoxes.insert( - std::pair(entityId, wireBox)); + std::pair(entityId, wireBox)); } else { - ignition::rendering::WireBoxPtr wireBox = wireBoxIt->second; - ignition::math::AxisAlignedBox aabb = _visual->LocalBoundingBox(); + gz::rendering::WireBoxPtr wireBox = wireBoxIt->second; + gz::math::AxisAlignedBox aabb = _visual->LocalBoundingBox(); wireBox->SetBox(aabb); auto visParent = wireBox->Parent(); if (visParent) @@ -346,7 +346,7 @@ void SelectEntitiesPrivate::SetSelectedEntity( { if (nullptr == _visual) { - ignerr << "Failed to select null visual" << std::endl; + gzerr << "Failed to select null visual" << std::endl; return; } @@ -374,10 +374,10 @@ void SelectEntitiesPrivate::SetSelectedEntity( this->selectedEntities.push_back(entityId); this->selectedEntitiesID.push_back(topLevelVisual->Id()); this->HighlightNode(topLevelVisual); - ignition::gazebo::gui::events::EntitiesSelected entitiesSelected( + gz::sim::gui::events::EntitiesSelected entitiesSelected( this->selectedEntities); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &entitiesSelected); } @@ -396,9 +396,9 @@ void SelectEntitiesPrivate::DeselectAllEntities() this->selectedEntities.clear(); this->selectedEntitiesID.clear(); - ignition::gazebo::gui::events::DeselectAllEntities deselectEvent(true); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::sim::gui::events::DeselectAllEntities deselectEvent(true); + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &deselectEvent); } @@ -424,10 +424,10 @@ void SelectEntitiesPrivate::UpdateSelectedEntity( // Notify other widgets of the currently selected entities if (_sendEvent || deselectedAll) { - ignition::gazebo::gui::events::EntitiesSelected selectEvent( + gz::sim::gui::events::EntitiesSelected selectEvent( this->selectedEntities); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), + gz::gui::App()->sendEvent( + gz::gui::App()->findChild(), &selectEvent); } } @@ -449,7 +449,7 @@ void SelectEntitiesPrivate::Initialize() std::get(cam->UserData("user-camera"))) { this->camera = cam; - igndbg << "SelectEntities plugin is using camera [" + gzdbg << "SelectEntities plugin is using camera [" << this->camera->Name() << "]" << std::endl; break; } @@ -457,7 +457,7 @@ void SelectEntitiesPrivate::Initialize() if (!this->camera) { - ignerr << "TransformControl camera is not available" << std::endl; + gzerr << "TransformControl camera is not available" << std::endl; return; } } @@ -482,24 +482,24 @@ void SelectEntities::LoadConfig(const tinyxml2::XMLElement *) if (done) { std::string msg{"Only one SelectEntities plugin is supported at a time."}; - ignerr << msg << std::endl; + gzerr << msg << std::endl; QQmlProperty::write(this->PluginItem(), "message", QString::fromStdString(msg)); return; } 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 && @@ -515,22 +515,22 @@ 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(); } else if (_event->type() == - ignition::gazebo::gui::events::TransformControlModeActive::kType) + gz::sim::gui::events::TransformControlModeActive::kType) { auto transformControlMode = - reinterpret_cast( + reinterpret_cast( _event); this->dataPtr->transformControlActive = transformControlMode->TransformControlActive(); } else if (_event->type() == - ignition::gazebo::gui::events::EntitiesSelected::kType) + gz::sim::gui::events::EntitiesSelected::kType) { auto selectedEvent = reinterpret_cast(_event); @@ -564,22 +564,22 @@ bool SelectEntities::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::DeselectAllEntities::kType) + gz::sim::gui::events::DeselectAllEntities::kType) { this->dataPtr->selectedEntitiesID.clear(); 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; @@ -588,7 +588,7 @@ bool SelectEntities::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::NewRemovedEntities::kType) + gz::sim::gui::events::NewRemovedEntities::kType) { if (!this->dataPtr->wireBoxes.empty()) { @@ -612,5 +612,5 @@ bool SelectEntities::eventFilter(QObject *_obj, QEvent *_event) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::gui::SelectEntities, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::gui::SelectEntities, + gz::gui::Plugin) diff --git a/src/gui/plugins/select_entities/SelectEntities.hh b/src/gui/plugins/select_entities/SelectEntities.hh index 6643ab539e..f2a0cf88f0 100644 --- a/src/gui/plugins/select_entities/SelectEntities.hh +++ b/src/gui/plugins/select_entities/SelectEntities.hh @@ -15,16 +15,16 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_SELECTENTITIES_HH_ -#define IGNITION_GAZEBO_GUI_SELECTENTITIES_HH_ +#ifndef GZ_SIM_GUI_SELECTENTITIES_HH_ +#define GZ_SIM_GUI_SELECTENTITIES_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace gui { @@ -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 11bfa2534a..a7a7505646 100644 --- a/src/gui/plugins/shapes/Shapes.cc +++ b/src/gui/plugins/shapes/Shapes.cc @@ -34,19 +34,19 @@ #include -namespace ignition::gazebo +namespace gz::sim { class ShapesPrivate { }; } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// Shapes::Shapes() - : ignition::gui::Plugin(), + : gz::gui::Plugin(), dataPtr(std::make_unique()) { } @@ -61,8 +61,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); } ///////////////////////////////////////////////// @@ -73,13 +73,13 @@ 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); } } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::Shapes, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::Shapes, + gz::gui::Plugin) diff --git a/src/gui/plugins/shapes/Shapes.hh b/src/gui/plugins/shapes/Shapes.hh index a5f635b8a2..5628d1a3f1 100644 --- a/src/gui/plugins/shapes/Shapes.hh +++ b/src/gui/plugins/shapes/Shapes.hh @@ -15,22 +15,22 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_SHAPES_HH_ -#define IGNITION_GAZEBO_GUI_SHAPES_HH_ +#ifndef GZ_SIM_GUI_SHAPES_HH_ +#define GZ_SIM_GUI_SHAPES_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class ShapesPrivate; /// \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/spawn/Spawn.cc b/src/gui/plugins/spawn/Spawn.cc index cc33737aa4..c8ab164029 100644 --- a/src/gui/plugins/spawn/Spawn.cc +++ b/src/gui/plugins/spawn/Spawn.cc @@ -57,7 +57,7 @@ #include "gz/sim/rendering/RenderUtil.hh" #include "gz/sim/rendering/SceneManager.hh" -namespace ignition::gazebo +namespace gz::sim { class SpawnPrivate { @@ -149,12 +149,12 @@ namespace ignition::gazebo }; } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// Spawn::Spawn() - : ignition::gui::Plugin(), + : gz::gui::Plugin(), dataPtr(std::make_unique()) { } @@ -172,7 +172,7 @@ void Spawn::LoadConfig(const tinyxml2::XMLElement *) if (done) { std::string msg{"Only one Spawn plugin is supported at a time."}; - ignerr << msg << std::endl; + gzerr << msg << std::endl; QQmlProperty::write(this->PluginItem(), "message", QString::fromStdString(msg)); return; @@ -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); } ///////////////////////////////////////////////// @@ -196,7 +196,7 @@ void SpawnPrivate::HandlePlacement() if (this->spawnPreview && this->hoverDirty) { - math::Vector3d pos = ignition::rendering::screenToPlane( + math::Vector3d pos = gz::rendering::screenToPlane( this->mouseHoverPos, this->camera, this->rayQuery); pos.Z(this->spawnPreview->WorldPosition().Z()); this->spawnPreview->SetWorldPosition(pos); @@ -214,9 +214,9 @@ void SpawnPrivate::HandlePlacement() [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error creating entity" << std::endl; + gzerr << "Error creating entity" << std::endl; }; - math::Vector3d pos = ignition::rendering::screenToPlane( + math::Vector3d pos = gz::rendering::screenToPlane( this->mouseEvent.Pos(), this->camera, this->rayQuery); pos.Z(pose.Pos().Z()); msgs::EntityFactory req; @@ -234,7 +234,7 @@ void SpawnPrivate::HandlePlacement() } else { - ignwarn << "Failed to find SDF string or file path" << std::endl; + gzwarn << "Failed to find SDF string or file path" << std::endl; } req.set_allow_renaming(true); msgs::Set(req.mutable_pose(), math::Pose3d(pos, pose.Rot())); @@ -248,7 +248,7 @@ void SpawnPrivate::HandlePlacement() this->createCmdService); if (this->createCmdService.empty()) { - ignerr << "Failed to create valid create command service for world [" + gzerr << "Failed to create valid create command service for world [" << this->worldName <<"]" << std::endl; return; } @@ -286,7 +286,7 @@ void SpawnPrivate::OnRender() // Ray Query this->rayQuery = this->camera->Scene()->CreateRayQuery(); - igndbg << "Spawn plugin is using camera [" + gzdbg << "Spawn plugin is using camera [" << this->camera->Name() << "]" << std::endl; break; } @@ -317,7 +317,7 @@ void SpawnPrivate::OnRender() } else { - ignwarn << "Failed to spawn: no SDF string, path, or name of resource " + gzwarn << "Failed to spawn: no SDF string, path, or name of resource " << "to clone" << std::endl; } @@ -359,7 +359,7 @@ bool SpawnPrivate::GeneratePreview(const sdf::Root &_sdf) if (nullptr == _sdf.Model() && nullptr == _sdf.Light()) { - ignwarn << "Only model or light entities can be spawned at the moment." + gzwarn << "Only model or light entities can be spawned at the moment." << std::endl; return false; } @@ -453,7 +453,7 @@ bool SpawnPrivate::GeneratePreview(const std::string &_name) this->sceneManager.WorldId()); if (!visualChildrenPair.first) { - ignerr << "Copying a visual named " << _name << "failed.\n"; + gzerr << "Copying a visual named " << _name << "failed.\n"; return false; } @@ -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) @@ -558,14 +558,14 @@ void Spawn::OnDropped(const ignition::gui::events::DropOnScene *_event) return; } - std::function cb = - [](const ignition::msgs::Boolean &_res, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &_res, const bool _result) { if (!_result || !_res.data()) - ignerr << "Error creating dropped entity." << std::endl; + gzerr << "Error creating dropped entity." << std::endl; }; - math::Vector3d pos = ignition::rendering::screenToScene( + math::Vector3d pos = gz::rendering::screenToScene( _event->Mouse(), this->dataPtr->camera, this->dataPtr->rayQuery); @@ -646,5 +646,5 @@ void Spawn::SetErrorPopupText(const QString &_errorTxt) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::Spawn, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::Spawn, + gz::gui::Plugin) diff --git a/src/gui/plugins/spawn/Spawn.hh b/src/gui/plugins/spawn/Spawn.hh index 43e5844919..5a0f4bbe9f 100644 --- a/src/gui/plugins/spawn/Spawn.hh +++ b/src/gui/plugins/spawn/Spawn.hh @@ -15,23 +15,23 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_SPAWN_HH_ -#define IGNITION_GAZEBO_GUI_SPAWN_HH_ +#ifndef GZ_SIM_GUI_SPAWN_HH_ +#define GZ_SIM_GUI_SPAWN_HH_ #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class SpawnPrivate; /// \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 501b0d1853..689f36aad1 100644 --- a/src/gui/plugins/transform_control/TransformControl.cc +++ b/src/gui/plugins/transform_control/TransformControl.cc @@ -47,7 +47,7 @@ #include "gz/sim/gui/GuiEvents.hh" -namespace ignition::gazebo +namespace gz::sim { class TransformControlPrivate { @@ -62,7 +62,7 @@ namespace ignition::gazebo /// \param[in] _sensitivity Sensitivity of a point snapping, in terms of a /// percentage of the interval. public: void SnapPoint( - ignition::math::Vector3d &_point, math::Vector3d &_snapVals, + gz::math::Vector3d &_point, math::Vector3d &_snapVals, double _sensitivity = 0.4) const; /// \brief Constraints the passed in axis to the currently selected axes. @@ -147,10 +147,10 @@ namespace ignition::gazebo public: std::vector selectedEntities; /// \brief Holds the latest mouse event - public: ignition::common::MouseEvent mouseEvent; + public: gz::common::MouseEvent mouseEvent; /// \brief Holds the latest key event - public: ignition::common::KeyEvent keyEvent; + public: gz::common::KeyEvent keyEvent; /// \brief Flag to indicate whether the x key is currently being pressed public: bool xPressed = false; @@ -171,7 +171,7 @@ namespace ignition::gazebo public: bool isStartWorldPosSet = false; /// \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 Block orbit public: bool blockOrbit = false; @@ -182,12 +182,12 @@ namespace ignition::gazebo }; } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// TransformControl::TransformControl() - : ignition::gui::Plugin(), + : gz::gui::Plugin(), dataPtr(std::make_unique()) { } @@ -211,18 +211,18 @@ void TransformControl::LoadConfig(const tinyxml2::XMLElement *_pluginElem) if (this->dataPtr->legacy) { - igndbg << "Legacy mode is enabled; this plugin must be used with " + gzdbg << "Legacy mode is enabled; this plugin must be used with " << "GzScene3D." << std::endl; } else { - igndbg << "Legacy mode is disabled; this plugin must be used with " + gzdbg << "Legacy mode is disabled; this plugin must be used with " << "MinimalScene." << std::endl; } - ignition::gui::App()->findChild + gz::gui::App()->findChild ()->installEventFilter(this); - ignition::gui::App()->findChild + gz::gui::App()->findChild ()->QuickWindow()->installEventFilter(this); } @@ -239,12 +239,12 @@ void TransformControl::OnSnapUpdate( // Emit event to GzScene3D in legacy mode if (this->dataPtr->legacy) { - ignition::gui::events::SnapIntervals event( + gz::gui::events::SnapIntervals event( 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(); @@ -258,14 +258,14 @@ void TransformControl::OnMode(const QString &_mode) // Legacy behaviour: send request to GzScene3D if (this->dataPtr->legacy) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error setting transform mode" << std::endl; + gzerr << "Error setting transform mode" << std::endl; }; - ignition::msgs::StringMsg req; + gz::msgs::StringMsg req; req.set_data(modeStr); this->dataPtr->node.Request(this->dataPtr->service, req, cb); } @@ -282,12 +282,12 @@ void TransformControl::OnMode(const QString &_mode) else if (modeStr == "scale") this->dataPtr->transformMode = rendering::TransformMode::TM_SCALE; else - ignerr << "Unknown transform mode: [" << modeStr << "]" << std::endl; + gzerr << "Unknown transform mode: [" << modeStr << "]" << std::endl; - ignition::gazebo::gui::events::TransformControlModeActive + gz::sim::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; } @@ -347,7 +347,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 @@ -361,48 +361,48 @@ bool TransformControl::eventFilter(QObject *_obj, QEvent *_event) this->dataPtr->HandleTransform(); } else if (_event->type() == - ignition::gazebo::gui::events::EntitiesSelected::kType) + gz::sim::gui::events::EntitiesSelected::kType) { if (!this->dataPtr->blockOrbit) { - ignition::gazebo::gui::events::EntitiesSelected *_e = - static_cast(_event); + gz::sim::gui::events::EntitiesSelected *_e = + static_cast(_event); this->dataPtr->selectedEntities = _e->Data(); } } else if (_event->type() == - ignition::gazebo::gui::events::DeselectAllEntities::kType) + gz::sim::gui::events::DeselectAllEntities::kType) { if (!this->dataPtr->blockOrbit) { 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) @@ -414,10 +414,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) { @@ -525,7 +525,7 @@ void TransformControlPrivate::HandleTransform() std::get(cam->UserData("user-camera"))) { this->camera = cam; - igndbg << "TransformControl plugin is using camera [" + gzdbg << "TransformControl plugin is using camera [" << this->camera->Name() << "]" << std::endl; break; } @@ -580,9 +580,9 @@ void TransformControlPrivate::HandleTransform() return; // handle mouse movements - if (this->mouseEvent.Button() == ignition::common::MouseEvent::LEFT) + if (this->mouseEvent.Button() == gz::common::MouseEvent::LEFT) { - if (this->mouseEvent.Type() == ignition::common::MouseEvent::PRESS + if (this->mouseEvent.Type() == gz::common::MouseEvent::PRESS && this->transformControl.Node()) { this->mousePressPos = this->mouseEvent.Pos(); @@ -597,7 +597,7 @@ void TransformControlPrivate::HandleTransform() // check if the visual is an axis in the gizmo visual math::Vector3d axis = this->transformControl.AxisById(visual->Id()); - if (axis != ignition::math::Vector3d::Zero) + if (axis != gz::math::Vector3d::Zero) { this->blockOrbit = true; // start the transform process @@ -624,7 +624,7 @@ void TransformControlPrivate::HandleTransform() } } } - else if (this->mouseEvent.Type() == ignition::common::MouseEvent::RELEASE) + else if (this->mouseEvent.Type() == gz::common::MouseEvent::RELEASE) { this->blockOrbit = false; @@ -633,8 +633,8 @@ void TransformControlPrivate::HandleTransform() { if (this->transformControl.Node()) { - std::function cb = - [this](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [this](const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (this->transformControl.Node()) { @@ -649,12 +649,12 @@ void TransformControlPrivate::HandleTransform() } } if (!_result) - ignerr << "Error setting pose" << std::endl; + gzerr << "Error setting pose" << std::endl; }; rendering::NodePtr nodeTmp = this->transformControl.Node(); auto topVisual = std::dynamic_pointer_cast( nodeTmp); - ignition::msgs::Pose req; + gz::msgs::Pose req; req.set_name(topVisual->Name()); msgs::Set(req.mutable_position(), nodeTmp->WorldPosition()); msgs::Set(req.mutable_orientation(), nodeTmp->WorldRotation()); @@ -663,7 +663,7 @@ void TransformControlPrivate::HandleTransform() if (this->poseCmdService.empty()) { std::string worldName; - auto worldNames = ignition::gui::worldNames(); + auto worldNames = gz::gui::worldNames(); if (!worldNames.empty()) worldName = worldNames[0].toStdString(); @@ -673,7 +673,7 @@ void TransformControlPrivate::HandleTransform() this->poseCmdService); if (this->poseCmdService.empty()) { - ignerr << "Failed to create valid pose command service " + gzerr << "Failed to create valid pose command service " << "for world [" << worldName << "]" << std::endl; return; } @@ -698,7 +698,7 @@ void TransformControlPrivate::HandleTransform() // check if the visual is an axis in the gizmo visual math::Vector3d axis = this->transformControl.AxisById(visual->Id()); - if (axis == ignition::math::Vector3d::Zero) + if (axis == gz::math::Vector3d::Zero) { auto topNode = this->TopLevelNode(visual); if (!topNode) @@ -816,7 +816,7 @@ void TransformControlPrivate::HandleTransform() } if (!target) { - ignwarn << "Failed to find node with ID [" << nodeId << "]" + gzwarn << "Failed to find node with ID [" << nodeId << "]" << std::endl; return; } @@ -913,9 +913,9 @@ void TransformControlPrivate::HandleTransform() this->mouseDirty = false; } - 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); } @@ -993,19 +993,19 @@ void TransformControlPrivate::XYZConstraint(math::Vector3d &_axis) ///////////////////////////////////////////////// void TransformControlPrivate::SnapPoint( - ignition::math::Vector3d &_point, math::Vector3d &_snapVals, + gz::math::Vector3d &_point, math::Vector3d &_snapVals, double _sensitivity) const { if (_snapVals.X() <= 0 || _snapVals.Y() <= 0 || _snapVals.Z() <= 0) { - ignerr << "Interval distance must be greater than 0" + gzerr << "Interval distance must be greater than 0" << std::endl; return; } if (_sensitivity < 0 || _sensitivity > 1.0) { - ignerr << "Sensitivity must be between 0 and 1" << std::endl; + gzerr << "Sensitivity must be between 0 and 1" << std::endl; return; } @@ -1015,5 +1015,5 @@ void TransformControlPrivate::SnapPoint( } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::TransformControl, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::TransformControl, + gz::gui::Plugin) diff --git a/src/gui/plugins/transform_control/TransformControl.hh b/src/gui/plugins/transform_control/TransformControl.hh index 5b0670fcab..79e5cb8291 100644 --- a/src/gui/plugins/transform_control/TransformControl.hh +++ b/src/gui/plugins/transform_control/TransformControl.hh @@ -15,16 +15,16 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_TRANSFORMCONTROL_HH_ -#define IGNITION_GAZEBO_GUI_TRANSFORMCONTROL_HH_ +#ifndef GZ_SIM_GUI_TRANSFORMCONTROL_HH_ +#define GZ_SIM_GUI_TRANSFORMCONTROL_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class TransformControlPrivate; @@ -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 01a913d796..356f9b244c 100644 --- a/src/gui/plugins/video_recorder/VideoRecorder.cc +++ b/src/gui/plugins/video_recorder/VideoRecorder.cc @@ -42,7 +42,7 @@ /// multiple viewports in the future. std::condition_variable g_renderCv; -namespace ignition::gazebo +namespace gz::sim { class VideoRecorderPrivate { @@ -121,8 +121,8 @@ namespace ignition::gazebo }; } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// void VideoRecorderPrivate::Initialize() @@ -148,7 +148,7 @@ void VideoRecorderPrivate::Initialize() std::get(cam->UserData("user-camera"))) { this->camera = cam; - igndbg << "Video Recorder plugin is recoding camera [" + gzdbg << "Video Recorder plugin is recoding camera [" << this->camera->Name() << "]" << std::endl; break; } @@ -156,14 +156,14 @@ void VideoRecorderPrivate::Initialize() if (!this->camera) { - ignerr << "Camera is not available" << std::endl; + gzerr << "Camera is not available" << std::endl; return; } // recorder stats topic this->recorderStatsPub = this->node.Advertise(this->recorderStatsTopic); - ignmsg << "Video recorder stats topic advertised on [" + gzmsg << "Video recorder stats topic advertised on [" << this->recorderStatsTopic << "]" << std::endl; } @@ -219,7 +219,7 @@ void VideoRecorderPrivate::OnRender() std::chrono::steady_clock::duration dt; dt = t - this->startTime; int64_t sec, nsec; - std::tie(sec, nsec) = ignition::math::durationToSecNsec(dt); + std::tie(sec, nsec) = gz::math::durationToSecNsec(dt); msgs::Time msg; msg.set_sec(sec); msg.set_nsec(nsec); @@ -230,17 +230,17 @@ void VideoRecorderPrivate::OnRender() else { if (this->useSimTime) - ignmsg << "Recording video using sim time." << std::endl; + gzmsg << "Recording video using sim time." << std::endl; if (this->lockstep) { - ignmsg << "Recording video in lockstep mode" << std::endl; + gzmsg << "Recording video in lockstep mode" << std::endl; if (!this->useSimTime) { - ignwarn << "It is recommended to set to true " + gzwarn << "It is recommended to set to true " << "when recording video in lockstep mode." << std::endl; } } - ignmsg << "Recording video using bitrate: " + gzmsg << "Recording video using bitrate: " << this->bitrate << std::endl; this->videoEncoder.Start(this->format, this->filename, width, height, 25, @@ -304,7 +304,7 @@ void VideoRecorder::LoadConfig(const tinyxml2::XMLElement * _pluginElem) bool useSimTime = false; if (useSimTimeElem->QueryBoolText(&useSimTime) != tinyxml2::XML_SUCCESS) { - ignerr << "Faild to parse value: " + gzerr << "Faild to parse value: " << useSimTimeElem->GetText() << std::endl; } else @@ -317,7 +317,7 @@ void VideoRecorder::LoadConfig(const tinyxml2::XMLElement * _pluginElem) bool lockstep = false; if (lockstepElem->QueryBoolText(&lockstep) != tinyxml2::XML_SUCCESS) { - ignerr << "Failed to parse value: " + gzerr << "Failed to parse value: " << lockstepElem->GetText() << std::endl; } else @@ -337,7 +337,7 @@ void VideoRecorder::LoadConfig(const tinyxml2::XMLElement * _pluginElem) } else { - ignerr << "Video recorder bitrate must be larger than 0" + gzerr << "Video recorder bitrate must be larger than 0" << std::endl; } } @@ -351,23 +351,23 @@ void VideoRecorder::LoadConfig(const tinyxml2::XMLElement * _pluginElem) if (this->dataPtr->legacy) { - igndbg << "Legacy mode is enabled; this plugin must be used with " + gzdbg << "Legacy mode is enabled; this plugin must be used with " << "GzScene3D." << std::endl; } else { - igndbg << "Legacy mode is disabled; this plugin must be used with " + gzdbg << "Legacy mode is disabled; this plugin must be used with " << "MinimalScene." << std::endl; } - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); + gz::gui::App()->findChild< + gz::gui::MainWindow *>()->installEventFilter(this); } ///////////////////////////////////////////////// bool VideoRecorder::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gz::gui::events::Render::kType) { this->dataPtr->OnRender(); } @@ -386,13 +386,13 @@ void VideoRecorder::OnStart(const QString &_format) if (this->dataPtr->legacy) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error sending video record start request" << std::endl; + gzerr << "Error sending video record start request" << std::endl; }; - ignition::msgs::VideoRecord req; + gz::msgs::VideoRecord req; req.set_start(this->dataPtr->recordVideo); req.set_format(this->dataPtr->format); req.set_save_filename(this->dataPtr->filename); @@ -408,14 +408,14 @@ void VideoRecorder::OnStop() if (this->dataPtr->legacy) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error sending video record stop request" << std::endl; + gzerr << "Error sending video record stop request" << std::endl; }; - ignition::msgs::VideoRecord req; + gz::msgs::VideoRecord req; req.set_stop(true); this->dataPtr->node.Request(this->dataPtr->service, req, cb); } @@ -445,12 +445,12 @@ void VideoRecorder::OnSave(const QString &_url) if (!result) { - ignerr << "Unable to rename file from[" << this->dataPtr->filename + gzerr << "Unable to rename file from[" << this->dataPtr->filename << "] to [" << path << "]" << std::endl; } else { - ignmsg << "Video saved to: " << path << std::endl; + gzmsg << "Video saved to: " << path << std::endl; } } @@ -462,5 +462,5 @@ void VideoRecorder::OnCancel() } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::VideoRecorder, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::VideoRecorder, + gz::gui::Plugin) diff --git a/src/gui/plugins/video_recorder/VideoRecorder.hh b/src/gui/plugins/video_recorder/VideoRecorder.hh index bd7cb90aef..8aac7f557c 100644 --- a/src/gui/plugins/video_recorder/VideoRecorder.hh +++ b/src/gui/plugins/video_recorder/VideoRecorder.hh @@ -15,21 +15,21 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_VIDEORECORDER_HH_ -#define IGNITION_GAZEBO_GUI_VIDEORECORDER_HH_ +#ifndef GZ_SIM_GUI_VIDEORECORDER_HH_ +#define GZ_SIM_GUI_VIDEORECORDER_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class VideoRecorderPrivate; /// \brief Provides video recording cababilities to the 3D scene. - class VideoRecorder : public ignition::gazebo::GuiSystem + class VideoRecorder : public gz::sim::GuiSystem { Q_OBJECT diff --git a/src/gui/plugins/view_angle/ViewAngle.cc b/src/gui/plugins/view_angle/ViewAngle.cc index 2cb89f391e..fad630921a 100644 --- a/src/gui/plugins/view_angle/ViewAngle.cc +++ b/src/gui/plugins/view_angle/ViewAngle.cc @@ -38,7 +38,7 @@ #include "gz/sim/Entity.hh" #include "gz/sim/gui/GuiEvents.hh" -namespace ignition::gazebo +namespace gz::sim { class ViewAnglePrivate { @@ -108,12 +108,12 @@ namespace ignition::gazebo }; } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// ViewAngle::ViewAngle() - : ignition::gui::Plugin(), dataPtr(std::make_unique()) + : gz::gui::Plugin(), dataPtr(std::make_unique()) { } @@ -148,14 +148,14 @@ void ViewAngle::LoadConfig(const tinyxml2::XMLElement *_pluginElem) // Move to pose service this->dataPtr->moveToPoseService = "/gui/move_to/pose"; - 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(); @@ -166,10 +166,10 @@ bool ViewAngle::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::EntitiesSelected::kType) + gz::sim::gui::events::EntitiesSelected::kType) { auto selectedEvent = - reinterpret_cast( + reinterpret_cast( _event); if (selectedEvent && !selectedEvent->Data().empty()) @@ -185,7 +185,7 @@ bool ViewAngle::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::DeselectAllEntities::kType) + gz::sim::gui::events::DeselectAllEntities::kType) { this->dataPtr->selectedEntities.clear(); } @@ -204,7 +204,7 @@ void ViewAngle::OnAngleMode(int _x, int _y, int _z) [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error setting view angle mode" << std::endl; + gzerr << "Error setting view angle mode" << std::endl; }; msgs::Vector3d req; @@ -229,7 +229,7 @@ void ViewAngle::OnViewControl(const QString &_controller) [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error setting view controller" << std::endl; + gzerr << "Error setting view controller" << std::endl; }; msgs::StringMsg req; @@ -240,7 +240,7 @@ void ViewAngle::OnViewControl(const QString &_controller) req.set_data("ortho"); else { - ignerr << "Unknown view controller selected: " << str << std::endl; + gzerr << "Unknown view controller selected: " << str << std::endl; return; } @@ -273,7 +273,7 @@ void ViewAngle::SetCamPose(double _x, double _y, double _z, [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error sending move camera to pose request" << std::endl; + gzerr << "Error sending move camera to pose request" << std::endl; }; msgs::GUICamera req; @@ -343,7 +343,7 @@ void ViewAnglePrivate::OnRender() { this->camera = cam; this->moveToHelper.SetInitCameraPose(this->camera->WorldPose()); - igndbg << "ViewAngle plugin is moving camera [" + gzdbg << "ViewAngle plugin is moving camera [" << this->camera->Name() << "]" << std::endl; break; } @@ -352,7 +352,7 @@ void ViewAnglePrivate::OnRender() if (!this->camera) { - ignerr << "ViewAngle camera is not available" << std::endl; + gzerr << "ViewAngle camera is not available" << std::endl; return; } } @@ -462,5 +462,5 @@ bool ViewAnglePrivate::UpdateQtCamClipDist() } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::ViewAngle, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::ViewAngle, + gz::gui::Plugin) diff --git a/src/gui/plugins/view_angle/ViewAngle.hh b/src/gui/plugins/view_angle/ViewAngle.hh index f803366b15..4a1b2f23b8 100644 --- a/src/gui/plugins/view_angle/ViewAngle.hh +++ b/src/gui/plugins/view_angle/ViewAngle.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_VIEWANGLE_HH_ -#define IGNITION_GAZEBO_GUI_VIEWANGLE_HH_ +#ifndef GZ_SIM_GUI_VIEWANGLE_HH_ +#define GZ_SIM_GUI_VIEWANGLE_HH_ #include @@ -24,9 +24,9 @@ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class ViewAnglePrivate; @@ -36,7 +36,7 @@ namespace gazebo /// \ : Set the service to receive view angle requests. /// \ : Set to true to use with GzScene3D, false to use with /// MinimalScene. Defaults to true. - class ViewAngle : public ignition::gui::Plugin + class ViewAngle : public gz::gui::Plugin { Q_OBJECT diff --git a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc index 498fd1bd3e..a6755bfcb4 100644 --- a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc +++ b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc @@ -93,7 +93,7 @@ #include "gz/sim/rendering/RenderUtil.hh" #include "gz/sim/rendering/SceneManager.hh" -namespace ignition::gazebo +namespace gz::sim { class VisualizationCapabilitiesPrivate { @@ -103,15 +103,15 @@ namespace ignition::gazebo /// \brief Helper function to get all child links of a model entity. /// \param[in] _entity Entity to find child links /// \return Vector of child links found for the parent entity - public: std::vector - FindChildLinks(const ignition::gazebo::Entity &_entity); + public: std::vector + FindChildLinks(const gz::sim::Entity &_entity); /// \brief Helper function to get all children of an entity that have a /// pose. /// \param[in] _entity Entity to find children /// \return Vector of children found for the parent entity - public: std::unordered_set - FindChildFrames(const ignition::gazebo::Entity &_entity); + public: std::unordered_set + FindChildFrames(const gz::sim::Entity &_entity); /// \brief Finds the links (collision parent) that are used to create child /// collision visuals in RenderUtil::Update @@ -122,15 +122,15 @@ namespace ignition::gazebo /// \param[in] _ecm The entity-component manager /// \param[in] _entity Entity to find child links /// \return A vector of child links found for the entity - public: std::vector FindChildLinksFromECM( - const ignition::gazebo::EntityComponentManager &_ecm, - const ignition::gazebo::Entity &_entity); + public: std::vector FindChildLinksFromECM( + const gz::sim::EntityComponentManager &_ecm, + const gz::sim::Entity &_entity); /// \brief Finds the links (visual parent) that are used to toggle wireframe /// and transparent view for visuals in RenderUtil::Update /// \param[in] _ecm The entity-component manager public: void PopulateViewModeVisualLinks( - const ignition::gazebo::EntityComponentManager &_ecm); + const gz::sim::EntityComponentManager &_ecm); /// \brief Finds the links (inertial parent) that are used to create child /// inertia and center of mass visuals in RenderUtil::Update @@ -149,7 +149,7 @@ namespace ignition::gazebo /// \param[in] _parent Parent link's visual /// \return Pointer to created visual public: rendering::VisualPtr CreateCollisionVisual( - ignition::gazebo::Entity _id, + gz::sim::Entity _id, const sdf::Visual &_visual, rendering::VisualPtr &_parent); @@ -173,7 +173,7 @@ namespace ignition::gazebo ///////////////////////////////////////////////// /// \brief View an entity as transparent /// \param[in] _entity Entity to view as transparent - public: void ViewTransparent(const ignition::gazebo::Entity &_entity); + public: void ViewTransparent(const gz::sim::Entity &_entity); /// \brief Callback for view as transparent request /// \param[in] _msg Request message to set the target to view as @@ -188,7 +188,7 @@ namespace ignition::gazebo ///////////////////////////////////////////////// /// \brief View wireframes of specified entity /// \param[in] _entity Entity to view wireframes - public: void ViewWireframes(const ignition::gazebo::Entity &_entity); + public: void ViewWireframes(const gz::sim::Entity &_entity); /// \brief Callback for view wireframes request /// \param[in] _msg Request message to set the target to view wireframes @@ -217,9 +217,9 @@ namespace ignition::gazebo /// \param[in] _collision SDF description of collision /// \param[in] _parent Parent link's visual public: rendering::VisualPtr CreateCollision( - ignition::gazebo::Entity _id, + gz::sim::Entity _id, const sdf::Collision &_collision, - ignition::rendering::VisualPtr &_parent); + gz::rendering::VisualPtr &_parent); ///////////////////////////////////////////////// // COM @@ -241,10 +241,10 @@ namespace ignition::gazebo /// \param[in] _inertial Inertial component of the link /// \param[in] _parent Visual parent /// \return Visual (center of mass) object created from the inertial - public: ignition::rendering::VisualPtr CreateCOMVisual( - ignition::gazebo::Entity _id, + public: gz::rendering::VisualPtr CreateCOMVisual( + gz::sim::Entity _id, const math::Inertiald &_inertia, - ignition::rendering::VisualPtr &_parent); + gz::rendering::VisualPtr &_parent); ///////////////////////////////////////////////// // Inertia @@ -265,10 +265,10 @@ namespace ignition::gazebo /// \param[in] _inertial Inertial component of the link /// \param[in] _parent Visual parent /// \return Visual (center of mass) object created from the inertial - public: ignition::rendering::VisualPtr CreateInertiaVisual( - ignition::gazebo::Entity _id, + public: gz::rendering::VisualPtr CreateInertiaVisual( + gz::sim::Entity _id, const math::Inertiald &_inertia, - ignition::rendering::VisualPtr &_parent); + gz::rendering::VisualPtr &_parent); ///////////////////////////////////////////////// // Joints @@ -334,10 +334,10 @@ namespace ignition::gazebo public: Entity worldId{kNullEntity}; /// \brief Pointer to the rendering scene - public: ignition::rendering::ScenePtr scene{nullptr}; + public: gz::rendering::ScenePtr scene{nullptr}; /// \brief Scene manager - public: ignition::gazebo::SceneManager sceneManager; + public: gz::sim::SceneManager sceneManager; /// True if the rendering component is initialized public: bool initialized = false; @@ -349,11 +349,11 @@ namespace ignition::gazebo public: std::map> modelToModelEntities; /// \brief New wireframe visuals to be toggled - public: std::vector newTransparentEntities; + public: std::vector newTransparentEntities; /// \brief A map of link entities and their corresponding children visuals - public: std::map> linkToVisualEntities; + public: std::map> linkToVisualEntities; /// \brief Map of visual entity in Gazebo to visual pointers. public: std::map visuals; @@ -369,7 +369,7 @@ namespace ignition::gazebo /// \brief A map of created transparent visuals and if they are currently /// visible - public: std::map viewingTransparent; + public: std::map viewingTransparent; /// \brief View transparent service public: std::string viewTransparentService; @@ -538,8 +538,8 @@ namespace ignition::gazebo }; } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// void VisualizationCapabilitiesPrivate::OnRender() @@ -811,7 +811,7 @@ void VisualizationCapabilitiesPrivate::OnRender() } else { - ignerr << "Unable to find node name [" + gzerr << "Unable to find node name [" << this->viewCOMTarget << "] to view center of mass" << std::endl; } @@ -837,7 +837,7 @@ void VisualizationCapabilitiesPrivate::OnRender() } else { - ignerr << "Unable to find node name [" + gzerr << "Unable to find node name [" << this->viewInertiaTarget << "] to view inertia" << std::endl; } @@ -863,7 +863,7 @@ void VisualizationCapabilitiesPrivate::OnRender() } else { - ignerr << "Unable to find node name [" + gzerr << "Unable to find node name [" << this->viewTransparentTarget << "] to view as transparent" << std::endl; } @@ -889,7 +889,7 @@ void VisualizationCapabilitiesPrivate::OnRender() } else { - ignerr << "Unable to find node name [" + gzerr << "Unable to find node name [" << this->viewCollisionsTarget << "] to view collisions" << std::endl; } @@ -915,7 +915,7 @@ void VisualizationCapabilitiesPrivate::OnRender() } else { - ignerr << "Unable to find node name [" + gzerr << "Unable to find node name [" << this->viewJointsTarget << "] to view joints" << std::endl; } @@ -941,7 +941,7 @@ void VisualizationCapabilitiesPrivate::OnRender() } else { - ignerr << "Unable to find node name [" + gzerr << "Unable to find node name [" << this->viewWireframesTarget << "] to view wireframes" << std::endl; } @@ -966,7 +966,7 @@ void VisualizationCapabilitiesPrivate::OnRender() } else { - ignerr << "Unable to find node name [" + gzerr << "Unable to find node name [" << this->viewFramesTarget << "] to view frame" << std::endl; } @@ -1080,7 +1080,7 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::CreateJointVisual( // For fixed joint type, scale joint visual to the joint child link double childSize = std::max(0.1, parent->BoundingBox().Size().Length()); - auto scale = ignition::math::Vector3d(childSize * 0.2, + auto scale = gz::math::Vector3d(childSize * 0.2, childSize * 0.2, childSize * 0.2); jointVisual->SetLocalScale(scale); } @@ -1118,9 +1118,9 @@ void VisualizationCapabilitiesPrivate::UpdateJointParentPose(Entity _jointId) ///////////////////////////////////////////////// rendering::VisualPtr VisualizationCapabilitiesPrivate::CreateInertiaVisual( - ignition::gazebo::Entity _id, + gz::sim::Entity _id, const math::Inertiald &_inertia, - ignition::rendering::VisualPtr &_parent) + gz::rendering::VisualPtr &_parent) { std::string name = "Inertia_" + std::to_string(_id); if (_parent) @@ -1146,7 +1146,7 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::CreateInertiaVisual( ///////////////////////////////////////////////// rendering::VisualPtr VisualizationCapabilitiesPrivate::CreateCollision( - ignition::gazebo::Entity _id, + gz::sim::Entity _id, const sdf::Collision &_collision, rendering::VisualPtr &_parent) { @@ -1230,7 +1230,7 @@ rendering::GeometryPtr VisualizationCapabilitiesPrivate::CreateGeometry( _geom.MeshShape()->FilePath()); if (fullPath.empty()) { - ignerr << "Mesh geometry missing uri" << std::endl; + gzerr << "Mesh geometry missing uri" << std::endl; return geom; } rendering::MeshDescriptor descriptor; @@ -1240,8 +1240,8 @@ rendering::GeometryPtr VisualizationCapabilitiesPrivate::CreateGeometry( descriptor.subMeshName = _geom.MeshShape()->Submesh(); descriptor.centerSubMesh = _geom.MeshShape()->CenterSubmesh(); - ignition::common::MeshManager *meshManager = - ignition::common::MeshManager::Instance(); + gz::common::MeshManager *meshManager = + gz::common::MeshManager::Instance(); descriptor.mesh = meshManager->Load(descriptor.meshName); geom = this->scene->CreateMesh(descriptor); scale = _geom.MeshShape()->Scale(); @@ -1252,7 +1252,7 @@ rendering::GeometryPtr VisualizationCapabilitiesPrivate::CreateGeometry( _geom.HeightmapShape()->FilePath()); if (fullPath.empty()) { - ignerr << "Heightmap geometry missing URI" << std::endl; + gzerr << "Heightmap geometry missing URI" << std::endl; return geom; } @@ -1266,7 +1266,7 @@ rendering::GeometryPtr VisualizationCapabilitiesPrivate::CreateGeometry( auto img = std::make_shared(); if (img->Load(fullPath) < 0) { - ignerr << "Failed to load heightmap image data from [" + gzerr << "Failed to load heightmap image data from [" << fullPath << "]" << std::endl; return geom; } @@ -1278,7 +1278,7 @@ rendering::GeometryPtr VisualizationCapabilitiesPrivate::CreateGeometry( auto dem = std::make_shared(); if (dem->Load(fullPath) < 0) { - ignerr << "Failed to load heightmap dem data from [" + gzerr << "Failed to load heightmap dem data from [" << fullPath << "]" << std::endl; return geom; } @@ -1314,13 +1314,13 @@ rendering::GeometryPtr VisualizationCapabilitiesPrivate::CreateGeometry( geom = this->scene->CreateHeightmap(descriptor); if (nullptr == geom) { - ignerr << "Failed to create heightmap [" << fullPath << "]" << std::endl; + gzerr << "Failed to create heightmap [" << fullPath << "]" << std::endl; } scale = _geom.HeightmapShape()->Size(); } else { - ignerr << "Unsupported geometry type" << std::endl; + gzerr << "Unsupported geometry type" << std::endl; } _scale = scale; _localPose = localPose; @@ -1364,7 +1364,7 @@ rendering::MaterialPtr VisualizationCapabilitiesPrivate::CreateMaterial( if (!fullPath.empty()) material->SetRoughnessMap(fullPath); else - ignerr << "Unable to find file [" << roughnessMap << "]\n"; + gzerr << "Unable to find file [" << roughnessMap << "]\n"; } // metalness map @@ -1376,13 +1376,13 @@ rendering::MaterialPtr VisualizationCapabilitiesPrivate::CreateMaterial( if (!fullPath.empty()) material->SetMetalnessMap(fullPath); else - ignerr << "Unable to find file [" << metalnessMap << "]\n"; + gzerr << "Unable to find file [" << metalnessMap << "]\n"; } workflow = const_cast(metal); } else { - ignerr << "PBR material: currently only metal workflow is supported" + gzerr << "PBR material: currently only metal workflow is supported" << std::endl; } @@ -1399,7 +1399,7 @@ rendering::MaterialPtr VisualizationCapabilitiesPrivate::CreateMaterial( material->SetAlphaFromTexture(true, 0.5, _material.DoubleSided()); } else - ignerr << "Unable to find file [" << albedoMap << "]\n"; + gzerr << "Unable to find file [" << albedoMap << "]\n"; } // normal map @@ -1411,7 +1411,7 @@ rendering::MaterialPtr VisualizationCapabilitiesPrivate::CreateMaterial( if (!fullPath.empty()) material->SetNormalMap(fullPath); else - ignerr << "Unable to find file [" << normalMap << "]\n"; + gzerr << "Unable to find file [" << normalMap << "]\n"; } @@ -1424,7 +1424,7 @@ rendering::MaterialPtr VisualizationCapabilitiesPrivate::CreateMaterial( if (!fullPath.empty()) material->SetEnvironmentMap(fullPath); else - ignerr << "Unable to find file [" << environmentMap << "]\n"; + gzerr << "Unable to find file [" << environmentMap << "]\n"; } // emissive map @@ -1436,7 +1436,7 @@ rendering::MaterialPtr VisualizationCapabilitiesPrivate::CreateMaterial( if (!fullPath.empty()) material->SetEmissiveMap(fullPath); else - ignerr << "Unable to find file [" << emissiveMap << "]\n"; + gzerr << "Unable to find file [" << emissiveMap << "]\n"; } // light map @@ -1452,7 +1452,7 @@ rendering::MaterialPtr VisualizationCapabilitiesPrivate::CreateMaterial( } else { - ignerr << "Unable to find file [" << lightMap << "]\n"; + gzerr << "Unable to find file [" << lightMap << "]\n"; } } } @@ -1461,7 +1461,7 @@ rendering::MaterialPtr VisualizationCapabilitiesPrivate::CreateMaterial( ///////////////////////////////////////////////// rendering::VisualPtr VisualizationCapabilitiesPrivate::CreateCollisionVisual( - ignition::gazebo::Entity _id, + gz::sim::Entity _id, const sdf::Visual &_visual, rendering::VisualPtr &_parent) { @@ -1580,7 +1580,7 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::CreateCollisionVisual( } else { - ignerr << "Failed to load geometry for visual: " << _visual.Name() + gzerr << "Failed to load geometry for visual: " << _visual.Name() << std::endl; } @@ -1597,7 +1597,7 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::CreateCollisionVisual( ///////////////////////////////////////////////// rendering::VisualPtr VisualizationCapabilitiesPrivate::CreateCOMVisual( - ignition::gazebo::Entity _id, + gz::sim::Entity _id, const math::Inertiald &_inertia, rendering::VisualPtr &_parent) { @@ -1647,7 +1647,7 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::CreateFrameVisual( // Add frame name auto textGeom = this->scene->CreateText(); // Ogre 2 doesn't support Text, see - // https://github.com/ignitionrobotics/ign-rendering/issues/487 + // https://github.com/gazebosim/gz-rendering/issues/487 if (nullptr != textGeom) { textGeom->SetFontName("Liberation Sans"); @@ -1945,7 +1945,7 @@ void VisualizationCapabilitiesPrivate::ViewJoints(const Entity &_entity) this->VisualByEntity(jointEntity); if (jointVisual == nullptr) { - ignerr << "Could not find visual for entity [" << jointEntity + gzerr << "Could not find visual for entity [" << jointEntity << "]" << std::endl; continue; } @@ -2087,7 +2087,7 @@ void VisualizationCapabilitiesPrivate::ViewFrames(const Entity &_entity) auto frameVisual = this->scene->VisualById(frameVisualId); if (frameVisual == nullptr) { - ignerr << "Failed to find frame visual with ID [" << frameVisualId + gzerr << "Failed to find frame visual with ID [" << frameVisualId << "] for entity [" << descendant << "]" << std::endl; continue; } @@ -2263,7 +2263,7 @@ void VisualizationCapabilitiesPrivate::FindJointModels( } else { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] for viewing joints must be a model" << std::endl; continue; @@ -2292,7 +2292,7 @@ void VisualizationCapabilitiesPrivate::FindInertialLinks( } else { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] for viewing inertia must be a model or link" << std::endl; continue; @@ -2316,7 +2316,7 @@ void VisualizationCapabilitiesPrivate::FindInertialLinks( } else { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] for viewing center of mass must be a model or link" << std::endl; continue; @@ -2348,7 +2348,7 @@ void VisualizationCapabilitiesPrivate::FindCollisionLinks( } else { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] for viewing collision must be a model or link" << std::endl; continue; @@ -2378,7 +2378,7 @@ void VisualizationCapabilitiesPrivate::PopulateViewModeVisualLinks( } else { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] for viewing wireframe must be a model or link" << std::endl; continue; @@ -2403,7 +2403,7 @@ void VisualizationCapabilitiesPrivate::PopulateViewModeVisualLinks( } else { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] for viewing as transparent must be a model or link" << std::endl; continue; @@ -2798,7 +2798,7 @@ void VisualizationCapabilities::LoadConfig(const tinyxml2::XMLElement *) { std::string msg{ "Only one Visualization capabilities plugin is supported at a time."}; - ignerr << msg << std::endl; + gzerr << msg << std::endl; QQmlProperty::write(this->PluginItem(), "message", QString::fromStdString(msg)); return; @@ -2809,28 +2809,28 @@ void VisualizationCapabilities::LoadConfig(const tinyxml2::XMLElement *) this->dataPtr->viewTransparentService = "/gui/view/transparent"; this->dataPtr->node.Advertise(this->dataPtr->viewTransparentService, &VisualizationCapabilitiesPrivate::OnViewTransparent, this->dataPtr.get()); - ignmsg << "View as transparent service on [" + gzmsg << "View as transparent service on [" << this->dataPtr->viewTransparentService << "]" << std::endl; // view wireframes service this->dataPtr->viewWireframesService = "/gui/view/wireframes"; this->dataPtr->node.Advertise(this->dataPtr->viewWireframesService, &VisualizationCapabilitiesPrivate::OnViewWireframes, this->dataPtr.get()); - ignmsg << "View as wireframes service on [" + gzmsg << "View as wireframes service on [" << this->dataPtr->viewWireframesService << "]" << std::endl; // view center of mass service this->dataPtr->viewCOMService = "/gui/view/com"; this->dataPtr->node.Advertise(this->dataPtr->viewCOMService, &VisualizationCapabilitiesPrivate::OnViewCOM, this->dataPtr.get()); - ignmsg << "View center of mass service on [" + gzmsg << "View center of mass service on [" << this->dataPtr->viewCOMService << "]" << std::endl; // view inertia service this->dataPtr->viewInertiaService = "/gui/view/inertia"; this->dataPtr->node.Advertise(this->dataPtr->viewInertiaService, &VisualizationCapabilitiesPrivate::OnViewInertia, this->dataPtr.get()); - ignmsg << "View inertia service on [" + gzmsg << "View inertia service on [" << this->dataPtr->viewInertiaService << "]" << std::endl; // view collisions service @@ -2838,7 +2838,7 @@ void VisualizationCapabilities::LoadConfig(const tinyxml2::XMLElement *) this->dataPtr->node.Advertise(this->dataPtr->viewCollisionsService, &VisualizationCapabilitiesPrivate::OnViewCollisions, this->dataPtr.get()); - ignmsg << "View collisions service on [" + gzmsg << "View collisions service on [" << this->dataPtr->viewCollisionsService << "]" << std::endl; // view joints service @@ -2846,24 +2846,24 @@ void VisualizationCapabilities::LoadConfig(const tinyxml2::XMLElement *) this->dataPtr->node.Advertise(this->dataPtr->viewJointsService, &VisualizationCapabilitiesPrivate::OnViewJoints, this->dataPtr.get()); - ignmsg << "View joints service on [" + gzmsg << "View joints service on [" << this->dataPtr->viewJointsService << "]" << std::endl; // view frames service this->dataPtr->viewFramesService = "/gui/view/frames"; this->dataPtr->node.Advertise(this->dataPtr->viewFramesService, &VisualizationCapabilitiesPrivate::OnViewFrames, this->dataPtr.get()); - ignmsg << "View frames service on [" + gzmsg << "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(); } @@ -2872,5 +2872,5 @@ bool VisualizationCapabilities::eventFilter(QObject *_obj, QEvent *_event) // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::VisualizationCapabilities, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::VisualizationCapabilities, + gz::gui::Plugin) diff --git a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.hh b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.hh index 9d9d646448..8e1c87ce34 100644 --- a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.hh +++ b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.hh @@ -15,22 +15,22 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_VISUALIZATIONCAPABILITIES_HH_ -#define IGNITION_GAZEBO_GUI_VISUALIZATIONCAPABILITIES_HH_ +#ifndef GZ_SIM_GUI_VISUALIZATIONCAPABILITIES_HH_ +#define GZ_SIM_GUI_VISUALIZATIONCAPABILITIES_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { class VisualizationCapabilitiesPrivate; /// \brief Allows to visualize transparent, collisions, inertial, /// CoM and more. - class VisualizationCapabilities : public ignition::gazebo::GuiSystem + class VisualizationCapabilities : public gz::sim::GuiSystem { Q_OBJECT diff --git a/src/gui/plugins/visualize_contacts/VisualizeContacts.cc b/src/gui/plugins/visualize_contacts/VisualizeContacts.cc index 58b4339c4a..fbd13e037c 100644 --- a/src/gui/plugins/visualize_contacts/VisualizeContacts.cc +++ b/src/gui/plugins/visualize_contacts/VisualizeContacts.cc @@ -48,11 +48,11 @@ #include "VisualizeContacts.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { /// \brief Private data class for VisualizeContacts class VisualizeContactsPrivate @@ -72,7 +72,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE public: bool checkboxPrevState{false}; /// \brief Message for visualizing contact positions - public: ignition::msgs::Marker positionMarkerMsg; + public: gz::msgs::Marker positionMarkerMsg; /// \brief Radius of the visualized contact sphere public: double contactRadius{0.10}; @@ -98,8 +98,8 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE } } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// VisualizeContacts::VisualizeContacts() @@ -123,11 +123,11 @@ void VisualizeContacts::LoadConfig(const tinyxml2::XMLElement *) // Create the marker message this->dataPtr->positionMarkerMsg.set_ns("positions"); this->dataPtr->positionMarkerMsg.set_action( - ignition::msgs::Marker::ADD_MODIFY); + gz::msgs::Marker::ADD_MODIFY); this->dataPtr->positionMarkerMsg.set_type( - ignition::msgs::Marker::SPHERE); + gz::msgs::Marker::SPHERE); this->dataPtr->positionMarkerMsg.set_visibility( - ignition::msgs::Marker::GUI); + gz::msgs::Marker::GUI); this->dataPtr-> positionMarkerMsg.mutable_lifetime()-> set_sec(0); @@ -136,16 +136,16 @@ void VisualizeContacts::LoadConfig(const tinyxml2::XMLElement *) set_nsec(this->dataPtr->markerLifetime * 1000000); // Set material properties - ignition::msgs::Set( + gz::msgs::Set( this->dataPtr->positionMarkerMsg.mutable_material()->mutable_ambient(), - ignition::math::Color(0, 0, 1, 1)); - ignition::msgs::Set( + gz::math::Color(0, 0, 1, 1)); + gz::msgs::Set( this->dataPtr->positionMarkerMsg.mutable_material()->mutable_diffuse(), - ignition::math::Color(0, 0, 1, 1)); + gz::math::Color(0, 0, 1, 1)); // Set contact position scale - ignition::msgs::Set(this->dataPtr->positionMarkerMsg.mutable_scale(), - ignition::math::Vector3d(this->dataPtr->contactRadius, + gz::msgs::Set(this->dataPtr->positionMarkerMsg.mutable_scale(), + gz::math::Vector3d(this->dataPtr->contactRadius, this->dataPtr->contactRadius, this->dataPtr->contactRadius)); } @@ -190,15 +190,15 @@ void VisualizeContacts::Update(const UpdateInfo &_info, { // Remove the markers this->dataPtr->positionMarkerMsg.set_action( - ignition::msgs::Marker::DELETE_ALL); + gz::msgs::Marker::DELETE_ALL); - igndbg << "Removing markers..." << std::endl; + gzdbg << "Removing markers..." << std::endl; this->dataPtr->node.Request( "/marker", this->dataPtr->positionMarkerMsg); // Change action in case checkbox is checked again this->dataPtr->positionMarkerMsg.set_action( - ignition::msgs::Marker::ADD_MODIFY); + gz::msgs::Marker::ADD_MODIFY); } this->dataPtr->checkboxPrevState = this->dataPtr->checkboxState; @@ -233,8 +233,8 @@ void VisualizeContacts::Update(const UpdateInfo &_info, { // Set marker id, poses and request service this->dataPtr->positionMarkerMsg.set_id(markerID++); - ignition::msgs::Set(this->dataPtr->positionMarkerMsg.mutable_pose(), - ignition::math::Pose3d(contact.position(i).x(), + gz::msgs::Set(this->dataPtr->positionMarkerMsg.mutable_pose(), + gz::math::Pose3d(contact.position(i).x(), contact.position(i).y(), contact.position(i).z(), 0, 0, 0)); @@ -264,7 +264,7 @@ void VisualizeContactsPrivate::CreateCollisionData( if (collisionHasContactSensor) { - igndbg << "ContactSensorData detected in collision [" << _entity << "]" + gzdbg << "ContactSensorData detected in collision [" << _entity << "]" << std::endl; return true; } @@ -292,8 +292,8 @@ void VisualizeContacts::UpdateRadius(double _radius) this->dataPtr->contactRadius = _radius; // Set scale - ignition::msgs::Set(this->dataPtr->positionMarkerMsg.mutable_scale(), - ignition::math::Vector3d(this->dataPtr->contactRadius, + gz::msgs::Set(this->dataPtr->positionMarkerMsg.mutable_scale(), + gz::math::Vector3d(this->dataPtr->contactRadius, this->dataPtr->contactRadius, this->dataPtr->contactRadius)); } @@ -310,5 +310,5 @@ void VisualizeContacts::UpdatePeriod(double _period) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::VisualizeContacts, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::VisualizeContacts, + gz::gui::Plugin) diff --git a/src/gui/plugins/visualize_contacts/VisualizeContacts.hh b/src/gui/plugins/visualize_contacts/VisualizeContacts.hh index 333d8edf60..884216dccf 100644 --- a/src/gui/plugins/visualize_contacts/VisualizeContacts.hh +++ b/src/gui/plugins/visualize_contacts/VisualizeContacts.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_VISUALIZECONTACTS_HH_ -#define IGNITION_GAZEBO_GUI_VISUALIZECONTACTS_HH_ +#ifndef GZ_SIM_GUI_VISUALIZECONTACTS_HH_ +#define GZ_SIM_GUI_VISUALIZECONTACTS_HH_ #include @@ -24,19 +24,19 @@ #include "gz/gui/qt.h" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { class VisualizeContactsPrivate; /// \brief Visualize the contacts returned by the Physics plugin. Use the /// checkbox to turn visualization on or off and spin boxes to change /// the size of the markers. - class VisualizeContacts : public ignition::gazebo::GuiSystem + class VisualizeContacts : public gz::sim::GuiSystem { Q_OBJECT diff --git a/src/gui/plugins/visualize_lidar/VisualizeLidar.cc b/src/gui/plugins/visualize_lidar/VisualizeLidar.cc index e9ea786e3e..2bbc2d9be8 100644 --- a/src/gui/plugins/visualize_lidar/VisualizeLidar.cc +++ b/src/gui/plugins/visualize_lidar/VisualizeLidar.cc @@ -60,11 +60,11 @@ #include "gz/msgs/laserscan.pb.h" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { /// \brief Private data class for VisualizeLidar class VisualizeLidarPrivate @@ -98,7 +98,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE public: QStringList topicList; /// \brief Entity representing the sensor in the world - public: gazebo::Entity lidarEntity; + public: sim::Entity lidarEntity; /// \brief Minimum range for the visual public: double minVisualRange{0.0}; @@ -128,8 +128,8 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE } } -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// VisualizeLidar::VisualizeLidar() @@ -156,14 +156,14 @@ void VisualizeLidar::LoadLidar() auto engineName = loadedEngNames[0]; if (loadedEngNames.size() > 1) { - igndbg << "More than one engine is available. " + gzdbg << "More than one engine is available. " << "VisualizeLidar plugin will use engine [" << engineName << "]" << std::endl; } auto engine = rendering::engine(engineName); if (!engine) { - ignerr << "Internal error: failed to load engine [" << engineName + gzerr << "Internal error: failed to load engine [" << engineName << "]. VisualizeLidar plugin won't work." << std::endl; return; } @@ -176,7 +176,7 @@ void VisualizeLidar::LoadLidar() auto scene = engine->SceneByIndex(0); if (!scene) { - ignerr << "Internal error: scene is null." << std::endl; + gzerr << "Internal error: scene is null." << std::endl; return; } @@ -186,19 +186,19 @@ void VisualizeLidar::LoadLidar() } // Create lidar visual - igndbg << "Creating lidar visual" << std::endl; + gzdbg << "Creating lidar visual" << std::endl; auto root = scene->RootVisual(); this->dataPtr->lidar = scene->CreateLidarVisual(); if (!this->dataPtr->lidar) { - ignwarn << "Failed to create lidar, visualize lidar plugin won't work." + gzwarn << "Failed to create lidar, visualize lidar plugin won't work." << std::endl; 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 @@ -248,7 +248,7 @@ bool VisualizeLidar::eventFilter(QObject *_obj, QEvent *_event) } else { - ignerr << "Lidar pointer is not set" << std::endl; + gzerr << "Lidar pointer is not set" << std::endl; } } @@ -274,7 +274,7 @@ void VisualizeLidar::Update(const UpdateInfo &, components::Name(lidarURIVec[0])); if (!baseEntity) { - ignerr << "Error entity " << lidarURIVec[0] + gzerr << "Error entity " << lidarURIVec[0] << " doesn't exist and cannot be used to set lidar visual pose" << std::endl; return; @@ -311,7 +311,7 @@ void VisualizeLidar::Update(const UpdateInfo &, } if (!foundChild) { - ignerr << "The entity could not be found." + gzerr << "The entity could not be found." << "Error displaying lidar visual" <dataPtr->topicName.empty() && !this->dataPtr->node.Unsubscribe(this->dataPtr->topicName)) { - ignerr << "Unable to unsubscribe from topic [" + gzerr << "Unable to unsubscribe from topic [" << this->dataPtr->topicName <<"]" <dataPtr->topicName = _topicName.toStdString(); @@ -395,12 +395,12 @@ void VisualizeLidar::OnTopic(const QString &_topicName) if (!this->dataPtr->node.Subscribe(this->dataPtr->topicName, &VisualizeLidar::OnScan, this)) { - ignerr << "Unable to subscribe to topic [" + gzerr << "Unable to subscribe to topic [" << this->dataPtr->topicName << "]\n"; return; } this->dataPtr->visualDirty = false; - ignmsg << "Subscribed to " << this->dataPtr->topicName << std::endl; + gzmsg << "Subscribed to " << this->dataPtr->topicName << std::endl; } ////////////////////////////////////////////////// @@ -415,7 +415,7 @@ void VisualizeLidar::DisplayVisual(bool _value) { std::lock_guard(this->dataPtr->serviceMutex); this->dataPtr->lidar->SetVisible(_value); - ignmsg << "Lidar Visual Display " << ((_value) ? "ON." : "OFF.") + gzmsg << "Lidar Visual Display " << ((_value) ? "ON." : "OFF.") << std::endl; } @@ -423,7 +423,7 @@ void VisualizeLidar::DisplayVisual(bool _value) void VisualizeLidar::OnRefresh() { std::lock_guard(this->dataPtr->serviceMutex); - ignmsg << "Refreshing topic list for LaserScan messages." << std::endl; + gzmsg << "Refreshing topic list for LaserScan messages." << std::endl; // Clear this->dataPtr->topicList.clear(); @@ -437,7 +437,7 @@ void VisualizeLidar::OnRefresh() this->dataPtr->node.TopicInfo(topic, publishers); for (auto pub : publishers) { - if (pub.MsgTypeName() == "ignition.msgs.LaserScan") + if (pub.MsgTypeName() == "gz.msgs.LaserScan") { this->dataPtr->topicList.push_back(QString::fromStdString(topic)); break; @@ -526,5 +526,5 @@ QString VisualizeLidar::MinRange() const } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::VisualizeLidar, - ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(gz::sim::VisualizeLidar, + gz::gui::Plugin) diff --git a/src/gui/plugins/visualize_lidar/VisualizeLidar.hh b/src/gui/plugins/visualize_lidar/VisualizeLidar.hh index fe0bcdbad8..6841a929c7 100644 --- a/src/gui/plugins/visualize_lidar/VisualizeLidar.hh +++ b/src/gui/plugins/visualize_lidar/VisualizeLidar.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_GUI_VISUALIZELIDAR_HH_ -#define IGNITION_GAZEBO_GUI_VISUALIZELIDAR_HH_ +#ifndef GZ_SIM_GUI_VISUALIZELIDAR_HH_ +#define GZ_SIM_GUI_VISUALIZELIDAR_HH_ #include @@ -24,12 +24,12 @@ #include "gz/sim/gui/GuiSystem.hh" #include "gz/gui/qt.h" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { class VisualizeLidarPrivate; @@ -37,7 +37,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE /// checkbox to turn visualization of non-hitting rays on or off and /// the textfield to select the message to be visualised. The combobox is /// used to select the type of visual for the sensor data. - class VisualizeLidar : public ignition::gazebo::GuiSystem + class VisualizeLidar : public gz::sim::GuiSystem { Q_OBJECT @@ -99,7 +99,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE public: Q_INVOKABLE QStringList TopicList() const; /// \brief Set the topic list from a string, for example - /// 'ignition.msgs.StringMsg' + /// 'gz.msgs.StringMsg' /// \param[in] _topicList Message type public: Q_INVOKABLE void SetTopicList(const QStringList &_topicList); diff --git a/src/gui/resources/GazeboDrawer.qml b/src/gui/resources/GazeboDrawer.qml index dc1ffa922f..d6441b9973 100644 --- a/src/gui/resources/GazeboDrawer.qml +++ b/src/gui/resources/GazeboDrawer.qml @@ -80,7 +80,7 @@ Rectangle { type: "world" } - // Actions provided by Ignition GUI, with custom titles + // Actions provided by Gazebo GUI, with custom titles ListElement { title: "Load client configuration" actionElement: "loadConfig" @@ -146,7 +146,7 @@ Rectangle { */ Dialog { id: aboutDialog - title: "Ignition Gazebo" + title: "Gazebo Sim" modal: true focus: true diff --git a/src/ign.cc b/src/ign.cc index 6af2eb573e..2c03c1a813 100644 --- a/src/ign.cc +++ b/src/ign.cc @@ -37,26 +37,26 @@ ////////////////////////////////////////////////// extern "C" char *ignitionGazeboVersion() { - return strdup(IGNITION_GAZEBO_VERSION_FULL); + return strdup(GZ_SIM_VERSION_FULL); } ////////////////////////////////////////////////// extern "C" char *gazeboVersionHeader() { - return strdup(IGNITION_GAZEBO_VERSION_HEADER); + return strdup(GZ_SIM_VERSION_HEADER); } ////////////////////////////////////////////////// extern "C" void cmdVerbosity( const char *_verbosity) { - ignition::common::Console::SetVerbosity(std::atoi(_verbosity)); + gz::common::Console::SetVerbosity(std::atoi(_verbosity)); } ////////////////////////////////////////////////// extern "C" const char *worldInstallDir() { - return IGN_GAZEBO_WORLD_INSTALL_DIR; + return GZ_SIM_WORLD_INSTALL_DIR; } ////////////////////////////////////////////////// @@ -65,43 +65,43 @@ extern "C" const char *findFuelResource( { std::string path; std::string worldPath; - ignition::fuel_tools::FuelClient fuelClient; + gz::fuel_tools::FuelClient fuelClient; // Attempt to find cached copy, and then attempt download - if (fuelClient.CachedWorld(ignition::common::URI(_pathToResource), path)) + if (fuelClient.CachedWorld(gz::common::URI(_pathToResource), path)) { - ignmsg << "Cached world found." << std::endl; + gzmsg << "Cached world found." << std::endl; worldPath = path; } // cppcheck-suppress syntaxError - else if (ignition::fuel_tools::Result result = - fuelClient.DownloadWorld(ignition::common::URI(_pathToResource), path); + else if (gz::fuel_tools::Result result = + fuelClient.DownloadWorld(gz::common::URI(_pathToResource), path); result) { - ignmsg << "Successfully downloaded world from fuel." << std::endl; + gzmsg << "Successfully downloaded world from fuel." << std::endl; worldPath = path; } else { - ignwarn << "Fuel world download failed because " << result.ReadableResult() + gzwarn << "Fuel world download failed because " << result.ReadableResult() << std::endl; return ""; } - if (!ignition::common::exists(worldPath)) + if (!gz::common::exists(worldPath)) return ""; // Find the first sdf file in the world path for now, the later intention is // to load an optional world config file first and if that does not exist, // continue to load the first sdf file found as done below - for (ignition::common::DirIter file(worldPath); - file != ignition::common::DirIter(); ++file) + for (gz::common::DirIter file(worldPath); + file != gz::common::DirIter(); ++file) { std::string current(*file); - if (ignition::common::isFile(current)) + if (gz::common::isFile(current)) { - std::string fileName = ignition::common::basename(current); + std::string fileName = gz::common::basename(current); std::string::size_type fileExtensionIndex = fileName.rfind("."); std::string fileExtension = fileName.substr(fileExtensionIndex + 1); @@ -124,14 +124,14 @@ extern "C" int runServer(const char *_sdfString, const char *_file, const char *_recordTopics, int _headless) { - ignition::gazebo::ServerConfig serverConfig; + gz::sim::ServerConfig serverConfig; // Path for logs std::string recordPathMod = serverConfig.LogRecordPath(); // Path for compressed log, used to check for duplicates std::string cmpPath = std::string(recordPathMod); - if (!std::string(1, cmpPath.back()).compare(ignition::common::separator(""))) + if (!std::string(1, cmpPath.back()).compare(gz::common::separator(""))) { // Remove the separator at end of path cmpPath = cmpPath.substr(0, cmpPath.length() - 1); @@ -145,7 +145,7 @@ extern "C" int runServer(const char *_sdfString, { if (_playback != nullptr && std::strlen(_playback) > 0) { - ignerr << "Both record and playback are specified. Only specify one.\n"; + gzerr << "Both record and playback are specified. Only specify one.\n"; return -1; } @@ -159,7 +159,7 @@ extern "C" int runServer(const char *_sdfString, // Update compressed file path to name of recording directory path cmpPath = std::string(recordPathMod); - if (!std::string(1, cmpPath.back()).compare(ignition::common::separator( + if (!std::string(1, cmpPath.back()).compare(gz::common::separator( ""))) { // Remove the separator at end of path @@ -168,8 +168,8 @@ extern "C" int runServer(const char *_sdfString, cmpPath += ".zip"; // Check if path or compressed file with same prefix exists - if (ignition::common::exists(recordPathMod) || - ignition::common::exists(cmpPath)) + if (gz::common::exists(recordPathMod) || + gz::common::exists(cmpPath)) { // Overwrite if flag specified if (_logOverwrite > 0) @@ -177,34 +177,34 @@ extern "C" int runServer(const char *_sdfString, bool recordMsg = false; bool cmpMsg = false; // Remove files before initializing console log files on top of them - if (ignition::common::exists(recordPathMod)) + if (gz::common::exists(recordPathMod)) { recordMsg = true; - ignition::common::removeAll(recordPathMod); + gz::common::removeAll(recordPathMod); } - if (ignition::common::exists(cmpPath)) + if (gz::common::exists(cmpPath)) { cmpMsg = true; - ignition::common::removeFile(cmpPath); + gz::common::removeFile(cmpPath); } // Create log file before printing any messages so they can be logged - ignLogInit(recordPathMod, "server_console.log"); + gzLogInit(recordPathMod, "server_console.log"); if (recordMsg) { - ignmsg << "Log path already exists on disk! Existing files will " + gzmsg << "Log path already exists on disk! Existing files will " << "be overwritten." << std::endl; - ignmsg << "Removing existing path [" << recordPathMod << "]\n"; + gzmsg << "Removing existing path [" << recordPathMod << "]\n"; } if (cmpMsg) { if (_logCompress > 0) { - ignwarn << "Compressed log path already exists on disk! Existing " + gzwarn << "Compressed log path already exists on disk! Existing " << "files will be overwritten." << std::endl; } - ignmsg << "Removing existing compressed file [" << cmpPath << "]\n"; + gzmsg << "Removing existing compressed file [" << cmpPath << "]\n"; } } // Otherwise rename to unique path @@ -212,7 +212,7 @@ extern "C" int runServer(const char *_sdfString, { // Remove the separator at end of path if (!std::string(1, recordPathMod.back()).compare( - ignition::common::separator(""))) + gz::common::separator(""))) { recordPathMod = recordPathMod.substr(0, recordPathMod.length() - 1); @@ -223,8 +223,8 @@ extern "C" int runServer(const char *_sdfString, // Keep renaming until path does not exist for both directory and // compressed file - while (ignition::common::exists(recordPathMod) || - ignition::common::exists(cmpPath)) + while (gz::common::exists(recordPathMod) || + gz::common::exists(cmpPath)) { recordPathMod = recordOrigPrefix + "(" + std::to_string(count++) + ")"; @@ -232,39 +232,39 @@ extern "C" int runServer(const char *_sdfString, cmpPath = std::string(recordPathMod); // Remove the separator at end of path if (!std::string(1, cmpPath.back()).compare( - ignition::common::separator(""))) + gz::common::separator(""))) { cmpPath = cmpPath.substr(0, cmpPath.length() - 1); } cmpPath += ".zip"; } - ignLogInit(recordPathMod, "server_console.log"); - ignwarn << "Log path already exists on disk! " + gzLogInit(recordPathMod, "server_console.log"); + gzwarn << "Log path already exists on disk! " << "Recording instead to [" << recordPathMod << "]" << std::endl; if (_logCompress > 0) { - ignwarn << "Compressed log path already exists on disk! " + gzwarn << "Compressed log path already exists on disk! " << "Recording instead to [" << cmpPath << "]" << std::endl; } } } else { - ignLogInit(recordPathMod, "server_console.log"); + gzLogInit(recordPathMod, "server_console.log"); } } // Empty record path specified. Use default. else { // Create log file before printing any messages so they can be logged - ignLogInit(recordPathMod, "server_console.log"); - ignmsg << "Recording states to default path [" << recordPathMod << "]" + gzLogInit(recordPathMod, "server_console.log"); + gzmsg << "Recording states to default path [" << recordPathMod << "]" << std::endl; } serverConfig.SetLogRecordPath(recordPathMod); - std::vector topics = ignition::common::split( + std::vector topics = gz::common::split( _recordTopics, ":"); for (const std::string &topic : topics) { @@ -273,7 +273,7 @@ extern "C" int runServer(const char *_sdfString, } else { - ignLogInit(serverConfig.LogRecordPath(), "server_console.log"); + gzLogInit(serverConfig.LogRecordPath(), "server_console.log"); } if (_logCompress > 0) @@ -281,7 +281,7 @@ extern "C" int runServer(const char *_sdfString, serverConfig.SetLogRecordCompressPath(cmpPath); } - ignmsg << "Ignition Gazebo Server v" << IGNITION_GAZEBO_VERSION_FULL + gzmsg << "Gazebo Sim Server v" << GZ_SIM_VERSION_FULL << std::endl; // Set the SDF string to user @@ -289,7 +289,7 @@ extern "C" int runServer(const char *_sdfString, { if (!serverConfig.SetSdfString(_sdfString)) { - ignerr << "Failed to set SDF string [" << _sdfString << "]" << std::endl; + gzerr << "Failed to set SDF string [" << _sdfString << "]" << std::endl; return -1; } } @@ -302,13 +302,13 @@ extern "C" int runServer(const char *_sdfString, // Set whether levels should be used. if (_levels > 0) { - ignmsg << "Using the level system\n"; + gzmsg << "Using the level system\n"; serverConfig.SetUseLevels(true); } if (_networkRole && std::strlen(_networkRole) > 0) { - ignmsg << "Using the distributed simulation and levels systems\n"; + gzmsg << "Using the distributed simulation and levels systems\n"; serverConfig.SetNetworkRole(_networkRole); serverConfig.SetNetworkSecondaries(_networkSecondaries); serverConfig.SetUseLevels(true); @@ -318,14 +318,14 @@ extern "C" int runServer(const char *_sdfString, { if (_sdfString != nullptr && std::strlen(_sdfString) > 0) { - ignerr << "Both an SDF file and playback flag are specified. " + gzerr << "Both an SDF file and playback flag are specified. " << "Only specify one.\n"; return -1; } else { - ignmsg << "Playing back states" << _playback << std::endl; - serverConfig.SetLogPlaybackPath(ignition::common::absPath( + gzmsg << "Playing back states" << _playback << std::endl; + serverConfig.SetLogPlaybackPath(gz::common::absPath( std::string(_playback))); } } @@ -348,12 +348,12 @@ extern "C" int runServer(const char *_sdfString, } // Create the Gazebo server - ignition::gazebo::Server server(serverConfig); + gz::sim::Server server(serverConfig); // Run the server server.Run(true, _iterations, _run == 0); - igndbg << "Shutting down ign-gazebo-server" << std::endl; + gzdbg << "Shutting down ign-gazebo-server" << std::endl; return 0; } @@ -371,6 +371,6 @@ extern "C" int runGui(const char *_guiConfig, const char *_renderEngine) // be converted to a const char *. The const cast is here to prevent a warning // since we do need to pass a char* to runGui char *argv = const_cast("ign-gazebo-gui"); - return ignition::gazebo::gui::runGui( + return gz::sim::gui::runGui( argc, &argv, _guiConfig, _renderEngine); } diff --git a/src/ign.hh b/src/ign.hh index 0cfffc5155..5def288328 100644 --- a/src/ign.hh +++ b/src/ign.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_IGN_HH_ -#define IGNITION_GAZEBO_IGN_HH_ +#ifndef GZ_SIM_IGN_HH_ +#define GZ_SIM_IGN_HH_ #include "gz/sim/Export.hh" @@ -66,7 +66,7 @@ extern "C" int runServer(const char *_sdfString, const char *_recordTopics, int _headless); /// \brief External hook to run simulation GUI. -/// \param[in] _guiConfig Path to Ignition GUI configuration file. +/// \param[in] _guiConfig Path to Gazebo GUI configuration file. /// \param[in] _renderEngine --render-engine-gui option /// \return 0 if successful, 1 if not. extern "C" int runGui(const char *_guiConfig, const char *_renderEngine); diff --git a/src/ign_TEST.cc b/src/ign_TEST.cc index eb69e187f0..e96730984c 100644 --- a/src/ign_TEST.cc +++ b/src/ign_TEST.cc @@ -28,7 +28,7 @@ static const std::string kBinPath(PROJECT_BINARY_PATH); static const std::string kIgnCommand( - std::string(BREW_RUBY) + std::string(IGN_PATH) + "/ign gazebo -s "); + std::string(BREW_RUBY) + std::string(GZ_PATH) + "/ign gazebo -s "); ///////////////////////////////////////////////// std::string customExecStr(std::string _cmd) @@ -55,7 +55,7 @@ std::string customExecStr(std::string _cmd) } ///////////////////////////////////////////////// -// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +// See https://github.com/gazebosim/gz-sim/issues/1175 TEST(CmdLine, IGN_UTILS_TEST_DISABLED_ON_WIN32(Server)) { std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 " + @@ -91,7 +91,7 @@ TEST(CmdLine, IGN_UTILS_TEST_DISABLED_ON_WIN32(Server)) TEST(CmdLine, IGN_UTILS_TEST_DISABLED_ON_WIN32(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.ignitionrobotics.org/1.0/OpenRobotics/worlds/Test%20world"; std::cout << "Running command [" << cmd << "]" << std::endl; diff --git a/src/msgs/peer_control.proto b/src/msgs/peer_control.proto index d7daa2d82d..96e5a9e4cd 100644 --- a/src/msgs/peer_control.proto +++ b/src/msgs/peer_control.proto @@ -17,9 +17,9 @@ syntax = "proto3"; -package ignition.gazebo.private_msgs; +package gz.sim.private_msgs; -import "ignition/msgs/header.proto"; +import "gz/msgs/header.proto"; /// \brief Message to control various aspects of peer execution. /// This message is only sent from NetworkPrimary to NetworkSecondary in order @@ -27,7 +27,7 @@ import "ignition/msgs/header.proto"; message PeerControl { /// \brief Optional header data - ignition.msgs.Header header = 1; + gz.msgs.Header header = 1; /// \brief Enable simulation on network secondary (True to enable) bool enable_sim = 2; diff --git a/src/msgs/peer_info.proto b/src/msgs/peer_info.proto index 5bd3834c35..c992f742d7 100644 --- a/src/msgs/peer_info.proto +++ b/src/msgs/peer_info.proto @@ -17,15 +17,15 @@ syntax = "proto3"; -package ignition.gazebo.private_msgs; +package gz.sim.private_msgs; -import "ignition/msgs/header.proto"; +import "gz/msgs/header.proto"; /// \brief Holds information about a peer in the network. message PeerInfo { /// \brief Optional header data - ignition.msgs.Header header = 1; + gz.msgs.Header header = 1; /// \brief ID of the peer string id = 2; diff --git a/src/msgs/performer_affinity.proto b/src/msgs/performer_affinity.proto index 730f709b71..c74a4cbf8f 100644 --- a/src/msgs/performer_affinity.proto +++ b/src/msgs/performer_affinity.proto @@ -17,16 +17,16 @@ syntax = "proto3"; -package ignition.gazebo.private_msgs; +package gz.sim.private_msgs; -import "ignition/msgs/entity.proto"; +import "gz/msgs/entity.proto"; /// \brief Message to contain information about one performer's distributed /// simulation affinity. message PerformerAffinity { /// \brief Information about the performer entity. - ignition.msgs.Entity entity = 1; + gz.msgs.Entity entity = 1; /// \brief Prefix used to communicate with the secondary. string secondary_prefix = 2; diff --git a/src/msgs/simulation_step.proto b/src/msgs/simulation_step.proto index ef686c0dbd..284380b305 100644 --- a/src/msgs/simulation_step.proto +++ b/src/msgs/simulation_step.proto @@ -17,9 +17,9 @@ syntax = "proto3"; -package ignition.gazebo.private_msgs; +package gz.sim.private_msgs; -import "ignition/msgs/world_stats.proto"; +import "gz/msgs/world_stats.proto"; import "performer_affinity.proto"; /// \brief Message to contain simulation step information for distributed @@ -29,7 +29,7 @@ import "performer_affinity.proto"; message SimulationStep { /// \brief Iteration information, such as sim time and paused state. - ignition.msgs.WorldStatistics stats = 1; + gz.msgs.WorldStatistics stats = 1; /// \brief Updated performer affinities. It will be empty if there are no /// affinity changes. diff --git a/src/network/NetworkConfig.cc b/src/network/NetworkConfig.cc index 2084c95b9d..e1e0f70e20 100644 --- a/src/network/NetworkConfig.cc +++ b/src/network/NetworkConfig.cc @@ -21,8 +21,8 @@ #include "gz/common/Console.hh" #include "gz/common/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// NetworkConfig NetworkConfig::FromValues(const std::string &_role, @@ -50,14 +50,14 @@ NetworkConfig NetworkConfig::FromValues(const std::string &_role, else { config.role = NetworkRole::None; - ignwarn << "Invalid setting for network role: " << role + gzwarn << "Invalid setting for network role: " << role << "(expected: PRIMARY, SECONDARY, READONLY)" << ", distributed sim disabled" << std::endl; } } else { - ignwarn << "Network role not set" + gzwarn << "Network role not set" << ", distributed sim disabled" << std::endl; } @@ -68,7 +68,7 @@ NetworkConfig NetworkConfig::FromValues(const std::string &_role, if (config.numSecondariesExpected == 0) { config.role = NetworkRole::None; - ignwarn << "Detected network role as PRIMARY, but " + gzwarn << "Detected network role as PRIMARY, but " << "network secondaries not set, " << "no distributed sim available" << std::endl; } diff --git a/src/network/NetworkConfig.hh b/src/network/NetworkConfig.hh index 85727bb2bd..acdbd38545 100644 --- a/src/network/NetworkConfig.hh +++ b/src/network/NetworkConfig.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_NETWORK_NETWORKCONFIG_HH_ -#define IGNITION_GAZEBO_NETWORK_NETWORKCONFIG_HH_ +#ifndef GZ_SIM_NETWORK_NETWORKCONFIG_HH_ +#define GZ_SIM_NETWORK_NETWORKCONFIG_HH_ #include #include @@ -25,18 +25,18 @@ #include "NetworkRole.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { /// \class NetworkConfig NetworkConfig.hh gz/sim/NetworkConfig.hh /// \brief Configuration parameters for a distributed simulation instance /// /// NetworkConfig can either be created programatically, or populated from /// environment variables set before the execution of the Gazebo server. - class IGNITION_GAZEBO_VISIBLE NetworkConfig + class GZ_GAZEBO_VISIBLE NetworkConfig { /// \brief Populate a new NetworkConfig object based on /// values. @@ -54,7 +54,7 @@ namespace ignition public: size_t numSecondariesExpected { 0 }; }; } - } // namespace gazebo -} // namespace ignition + } // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_NETWORKCONFIG_HH_ +#endif // GZ_SIM_NETWORKCONFIG_HH_ diff --git a/src/network/NetworkConfig_TEST.cc b/src/network/NetworkConfig_TEST.cc index 66c2baa987..b60ea77f48 100644 --- a/src/network/NetworkConfig_TEST.cc +++ b/src/network/NetworkConfig_TEST.cc @@ -22,11 +22,11 @@ #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 76514f9337..070264a2f3 100644 --- a/src/network/NetworkManager.cc +++ b/src/network/NetworkManager.cc @@ -28,8 +28,8 @@ #include "NetworkManagerPrimary.hh" #include "NetworkManagerSecondary.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; bool validateConfig(const NetworkConfig &_config) @@ -80,11 +80,11 @@ std::unique_ptr NetworkManager::Create( break; case NetworkRole::ReadOnly: // \todo(mjcarroll): Enable ReadOnly - ignwarn << "ReadOnly role not currently supported" << std::endl; + gzwarn << "ReadOnly role not currently supported" << std::endl; case NetworkRole::None: break; default: - ignwarn << "Cannot create NetworkManager, unrecognized role" + gzwarn << "Cannot create NetworkManager, unrecognized role" << std::endl; } @@ -119,7 +119,7 @@ NetworkManager::NetworkManager( { if (_info.Namespace() != this->Namespace()) { - ignmsg << "Peer [" << _info.Namespace() + gzmsg << "Peer [" << _info.Namespace() << "] removed, stopping simulation" << std::endl; this->dataPtr->eventMgr->Emit(); } @@ -130,7 +130,7 @@ NetworkManager::NetworkManager( { if (_info.Namespace() != this->Namespace()) { - ignerr << "Peer [" << _info.Namespace() + gzerr << "Peer [" << _info.Namespace() << "] went stale, stopping simulation" << std::endl; this->dataPtr->eventMgr->Emit(); } @@ -138,7 +138,7 @@ NetworkManager::NetworkManager( } else { - ignwarn << "NetworkManager started without EventManager. " + gzwarn << "NetworkManager started without EventManager. " << "Distributed environment may not terminate correctly" << std::endl; } } diff --git a/src/network/NetworkManager.hh b/src/network/NetworkManager.hh index 5ab356c246..65ba108d74 100644 --- a/src/network/NetworkManager.hh +++ b/src/network/NetworkManager.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_NETWORK_NETWORKMANAGER_HH_ -#define IGNITION_GAZEBO_NETWORK_NETWORKMANAGER_HH_ +#ifndef GZ_SIM_NETWORK_NETWORKMANAGER_HH_ +#define GZ_SIM_NETWORK_NETWORKMANAGER_HH_ #include #include @@ -29,12 +29,12 @@ #include "NetworkConfig.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { // Forward declarations class NetworkManagerPrivate; @@ -43,10 +43,10 @@ namespace ignition /// \brief The NetworkManager provides a common interface to derived /// objects that control the flow of information in the distributed /// simulation environment. - class IGNITION_GAZEBO_VISIBLE NetworkManager + class GZ_GAZEBO_VISIBLE 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 @@ -122,7 +122,7 @@ namespace ignition protected: std::unique_ptr dataPtr; }; } - } // namespace gazebo -} // namespace ignition + } // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_NETWORKMANAGER_HH_ +#endif // GZ_SIM_NETWORKMANAGER_HH_ diff --git a/src/network/NetworkManagerPrimary.cc b/src/network/NetworkManagerPrimary.cc index 8983415e8e..d3246d3058 100644 --- a/src/network/NetworkManagerPrimary.cc +++ b/src/network/NetworkManagerPrimary.cc @@ -40,8 +40,8 @@ #include "NetworkManagerPrivate.hh" #include "PeerTracker.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace std::chrono_literals; ////////////////////////////////////////////////// @@ -74,25 +74,25 @@ void NetworkManagerPrimary::Handshake() std::string topic {sc->prefix + "/control"}; unsigned int timeout = 5000; - igndbg << "Registering secondary [" << topic << "]" << std::endl; + gzdbg << "Registering secondary [" << topic << "]" << std::endl; bool executed = this->node.Request(topic, req, timeout, resp, result); if (executed) { if (result) { - ignmsg << "Peer initialized [" << sc->prefix << "]" << std::endl; + gzmsg << "Peer initialized [" << sc->prefix << "]" << std::endl; sc->ready = true; } else { - ignerr << "Peer service call failed [" << sc->prefix << "]" + gzerr << "Peer service call failed [" << sc->prefix << "]" << std::endl; } } else { - ignerr << "Peer service call timed out [" << sc->prefix << "], waited " + gzerr << "Peer service call timed out [" << sc->prefix << "], waited " << timeout << " ms" << std::endl; } @@ -124,7 +124,7 @@ bool NetworkManagerPrimary::Step(const UpdateInfo &_info) // TODO(louise) Wait for peers to be ready in a loop? if (!ready) { - ignerr << "Trying to step network primary before all peers are ready." + gzerr << "Trying to step network primary before all peers are ready." << std::endl; return false; } @@ -156,7 +156,7 @@ bool NetworkManagerPrimary::Step(const UpdateInfo &_info) if (std::future_status::ready != result) { - ignerr << "Waited 10 s and got only [" << this->secondaryStates.size() + gzerr << "Waited 10 s and got only [" << this->secondaryStates.size() << " / " << this->secondaries.size() << "] responses from secondaries. Stopping simulation." << std::endl; @@ -212,7 +212,7 @@ bool NetworkManagerPrimary::SecondariesCanStep() const // TODO(anyone) Ideally we'd check the number of connections against the // number of expected secondaries, but there's no interface for that // on ign-transport yet: - // https://github.com/ignitionrobotics/ign-transport/issues/39 + // https://github.com/gazebosim/gz-transport/issues/39 return this->simStepPub.HasConnections(); } diff --git a/src/network/NetworkManagerPrimary.hh b/src/network/NetworkManagerPrimary.hh index 60994d8d08..ff8a10cc24 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_SIM_NETWORK_NETWORKMANAGERPRIMARY_HH_ +#define GZ_SIM_NETWORK_NETWORKMANAGERPRIMARY_HH_ #include #include @@ -33,12 +33,12 @@ #include "NetworkManager.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { struct SecondaryControl { /// \brief indicate if the secondary is ready to execute @@ -57,7 +57,7 @@ namespace ignition /// \class NetworkManagerPrimary NetworkManagerPrimary.hh /// gz/sim/network/NetworkManagerPrimary.hh /// \brief Simulation primary specific behaviors - class IGNITION_GAZEBO_VISIBLE NetworkManagerPrimary: + class GZ_GAZEBO_VISIBLE NetworkManagerPrimary: public NetworkManager { // Documentation inherited @@ -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; @@ -123,8 +123,8 @@ namespace ignition private: std::promise secondaryStatesPromise; }; } - } // namespace gazebo -} // namespace ignition + } // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_NETWORKMANAGERPRIMARY_HH_ +#endif // GZ_SIM_NETWORKMANAGERPRIMARY_HH_ diff --git a/src/network/NetworkManagerPrivate.hh b/src/network/NetworkManagerPrivate.hh index 581eb72bd2..eb713a8c40 100644 --- a/src/network/NetworkManagerPrivate.hh +++ b/src/network/NetworkManagerPrivate.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_NETWORK_NETWORKMANAGERPRIVATE_HH_ -#define IGNITION_GAZEBO_NETWORK_NETWORKMANAGERPRIVATE_HH_ +#ifndef GZ_SIM_NETWORK_NETWORKMANAGERPRIVATE_HH_ +#define GZ_SIM_NETWORK_NETWORKMANAGERPRIVATE_HH_ #include #include @@ -27,15 +27,15 @@ #include "PeerInfo.hh" #include "PeerTracker.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { /// \class NetworkManagerPrivate NetworkManagerPrivate.hh /// gz/sim/NetworkManagerPrivate.hh - class IGNITION_GAZEBO_VISIBLE NetworkManagerPrivate + class GZ_GAZEBO_VISIBLE NetworkManagerPrivate { /// \brief Network Configuration public: NetworkConfig config; @@ -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,11 @@ 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 + } // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_NETWORKMANAGER_HH_ +#endif // GZ_SIM_NETWORKMANAGER_HH_ diff --git a/src/network/NetworkManagerSecondary.cc b/src/network/NetworkManagerSecondary.cc index 87cb24668b..1f45ffe3ef 100644 --- a/src/network/NetworkManagerSecondary.cc +++ b/src/network/NetworkManagerSecondary.cc @@ -34,8 +34,8 @@ #include "NetworkManagerSecondary.hh" #include "PeerTracker.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ////////////////////////////////////////////////// NetworkManagerSecondary::NetworkManagerSecondary( @@ -50,12 +50,12 @@ NetworkManagerSecondary::NetworkManagerSecondary( if (!this->node.Advertise(controlService, &NetworkManagerSecondary::OnControl, this)) { - ignerr << "Error advertising PeerControl service [" << controlService + gzerr << "Error advertising PeerControl service [" << controlService << "]" << std::endl; } else { - igndbg << "Advertised PeerControl service on [" << controlService << "]" + gzdbg << "Advertised PeerControl service on [" << controlService << "]" << std::endl; } @@ -105,7 +105,7 @@ void NetworkManagerSecondary::OnStep( // Throttle the number of step messages going to the debug output. if (!_msg.stats().paused() && _msg.stats().iterations() % 1000 == 0) { - igndbg << "Network iterations: " << _msg.stats().iterations() + gzdbg << "Network iterations: " << _msg.stats().iterations() << std::endl; } @@ -119,7 +119,7 @@ void NetworkManagerSecondary::OnStep( { this->performers.insert(entityId); - ignmsg << "Secondary [" << this->Namespace() + gzmsg << "Secondary [" << this->Namespace() << "] assigned affinity to performer [" << entityId << "]." << std::endl; } @@ -132,7 +132,7 @@ void NetworkManagerSecondary::OnStep( if (this->performers.find(entityId) != this->performers.end()) { - ignmsg << "Secondary [" << this->Namespace() + gzmsg << "Secondary [" << this->Namespace() << "] unassigned affinity to performer [" << entityId << "]." << std::endl; this->performers.erase(entityId); @@ -154,7 +154,7 @@ void NetworkManagerSecondary::OnStep( auto parent = this->dataPtr->ecm->Component(perf); if (parent == nullptr) { - ignerr << "Failed to get parent for performer [" << perf << "]" + gzerr << "Failed to get parent for performer [" << perf << "]" << std::endl; continue; } diff --git a/src/network/NetworkManagerSecondary.hh b/src/network/NetworkManagerSecondary.hh index 14f35f929f..b6adf6ccae 100644 --- a/src/network/NetworkManagerSecondary.hh +++ b/src/network/NetworkManagerSecondary.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_NETWORK_NETWORKMANAGERSECONDARY_HH_ -#define IGNITION_GAZEBO_NETWORK_NETWORKMANAGERSECONDARY_HH_ +#ifndef GZ_SIM_NETWORK_NETWORKMANAGERSECONDARY_HH_ +#define GZ_SIM_NETWORK_NETWORKMANAGERSECONDARY_HH_ #include #include @@ -31,16 +31,16 @@ #include "NetworkManager.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { /// \class NetworkManagerSecondary NetworkManagerSecondary.hh /// gz/sim/network/NetworkManagerSecondary.hh /// \brief Secondary specific behaviors - class IGNITION_GAZEBO_VISIBLE NetworkManagerSecondary: + class GZ_GAZEBO_VISIBLE NetworkManagerSecondary: public NetworkManager { // Documentation inherited @@ -74,17 +74,17 @@ 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; }; } - } // namespace gazebo -} // namespace ignition + } // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_NETWORKMANAGERSECONDARY_HH_ +#endif // GZ_SIM_NETWORKMANAGERSECONDARY_HH_ diff --git a/src/network/NetworkManager_TEST.cc b/src/network/NetworkManager_TEST.cc index c913a5ace7..1d2ba162ca 100644 --- a/src/network/NetworkManager_TEST.cc +++ b/src/network/NetworkManager_TEST.cc @@ -25,7 +25,7 @@ #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 bfee9c7fd0..17f1bcfefc 100644 --- a/src/network/NetworkRole.hh +++ b/src/network/NetworkRole.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_NETWORK_NETWORKROLE_HH_ -#define IGNITION_GAZEBO_NETWORK_NETWORKROLE_HH_ +#ifndef GZ_SIM_NETWORK_NETWORKROLE_HH_ +#define GZ_SIM_NETWORK_NETWORKROLE_HH_ #include #include -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { /// \brief Enumeration of roles that a network participant can take. enum class NetworkRole { @@ -47,8 +47,8 @@ namespace ignition SimulationSecondary = 3, }; } - } // namespace gazebo -} // namespace ignition + } // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_NETWORKROLE_HH_ +#endif // GZ_SIM_NETWORKROLE_HH_ diff --git a/src/network/PeerInfo.cc b/src/network/PeerInfo.cc index 1b5f85a548..d234d72a6b 100644 --- a/src/network/PeerInfo.cc +++ b/src/network/PeerInfo.cc @@ -19,13 +19,13 @@ #include "gz/common/Uuid.hh" #include "gz/transport/NetUtils.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// PeerInfo::PeerInfo(const NetworkRole &_role): - id(ignition::common::Uuid().String()), - hostname(ignition::transport::hostname()), + id(gz::common::Uuid().String()), + hostname(gz::transport::hostname()), role(_role) { } @@ -42,36 +42,36 @@ std::string PeerInfo::Namespace() const } ///////////////////////////////////////////////// -ignition::gazebo::private_msgs::PeerInfo ignition::gazebo::toProto( +gz::sim::private_msgs::PeerInfo gz::sim::toProto( const PeerInfo &_info) { - ignition::gazebo::private_msgs::PeerInfo proto; + gz::sim::private_msgs::PeerInfo proto; proto.set_id(_info.id); proto.set_hostname(_info.hostname); switch (_info.role) { case NetworkRole::ReadOnly: - proto.set_role(ignition::gazebo::private_msgs::PeerInfo::READ_ONLY); + proto.set_role(gz::sim::private_msgs::PeerInfo::READ_ONLY); break; case NetworkRole::SimulationPrimary: proto.set_role( - ignition::gazebo::private_msgs::PeerInfo::SIMULATION_PRIMARY); + gz::sim::private_msgs::PeerInfo::SIMULATION_PRIMARY); break; case NetworkRole::SimulationSecondary: proto.set_role( - ignition::gazebo::private_msgs::PeerInfo::SIMULATION_SECONDARY); + gz::sim::private_msgs::PeerInfo::SIMULATION_SECONDARY); break; case NetworkRole::None: default: - proto.set_role(ignition::gazebo::private_msgs::PeerInfo::NONE); + proto.set_role(gz::sim::private_msgs::PeerInfo::NONE); } return proto; } ///////////////////////////////////////////////// -PeerInfo ignition::gazebo::fromProto( - const ignition::gazebo::private_msgs::PeerInfo& _proto) +PeerInfo gz::sim::fromProto( + const gz::sim::private_msgs::PeerInfo& _proto) { PeerInfo info; info.id = _proto.id(); @@ -79,16 +79,16 @@ PeerInfo ignition::gazebo::fromProto( switch (_proto.role()) { - case ignition::gazebo::private_msgs::PeerInfo::READ_ONLY: + case gz::sim::private_msgs::PeerInfo::READ_ONLY: info.role = NetworkRole::ReadOnly; break; - case ignition::gazebo::private_msgs::PeerInfo::SIMULATION_PRIMARY: + case gz::sim::private_msgs::PeerInfo::SIMULATION_PRIMARY: info.role = NetworkRole::SimulationPrimary; break; - case ignition::gazebo::private_msgs::PeerInfo::SIMULATION_SECONDARY: + case gz::sim::private_msgs::PeerInfo::SIMULATION_SECONDARY: info.role = NetworkRole::SimulationSecondary; break; - case ignition::gazebo::private_msgs::PeerInfo::NONE: + case gz::sim::private_msgs::PeerInfo::NONE: default: info.role = NetworkRole::None; break; diff --git a/src/network/PeerInfo.hh b/src/network/PeerInfo.hh index e9d277e4a6..3b03bf8342 100644 --- a/src/network/PeerInfo.hh +++ b/src/network/PeerInfo.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_NETWORK_PEERINFO_HH_ -#define IGNITION_GAZEBO_NETWORK_PEERINFO_HH_ +#ifndef GZ_SIM_NETWORK_PEERINFO_HH_ +#define GZ_SIM_NETWORK_PEERINFO_HH_ #include @@ -25,13 +25,13 @@ #include "NetworkRole.hh" #include "msgs/peer_info.pb.h" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - class IGNITION_GAZEBO_VISIBLE PeerInfo { + inline namespace GZ_SIM_VERSION_NAMESPACE { + class GZ_GAZEBO_VISIBLE PeerInfo { /// \brief Constructor public: explicit PeerInfo(const NetworkRole &_role = NetworkRole::None); @@ -53,16 +53,16 @@ namespace ignition /// \brief Construct a `PeerInfo` object from a message. /// \param[in] _proto Message /// \result Equivalent PeerInfo - IGNITION_GAZEBO_VISIBLE PeerInfo fromProto( + GZ_GAZEBO_VISIBLE PeerInfo fromProto( const private_msgs::PeerInfo &_proto); /// \brief Construct a `PeerInfo` message from an object. /// \param[in] _info Peer info object /// \result Equivalent message - IGNITION_GAZEBO_VISIBLE private_msgs::PeerInfo toProto( + GZ_GAZEBO_VISIBLE private_msgs::PeerInfo toProto( const PeerInfo &_info); - } // namespace gazebo -} // namespace ignition + } // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_NETWORK_PEERINFO_HH_ +#endif // GZ_SIM_NETWORK_PEERINFO_HH_ diff --git a/src/network/PeerTracker.cc b/src/network/PeerTracker.cc index f4271fac98..989f1acf80 100644 --- a/src/network/PeerTracker.cc +++ b/src/network/PeerTracker.cc @@ -19,14 +19,14 @@ #include #include -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; ///////////////////////////////////////////////// PeerTracker::PeerTracker( PeerInfo _info, EventManager *_eventMgr, - const ignition::transport::NodeOptions &_options): + const gz::transport::NodeOptions &_options): info(std::move(_info)), eventMgr(_eventMgr), node(_options) @@ -163,7 +163,7 @@ bool PeerTracker::RemovePeer(const PeerInfo &_info) auto iter = this->peers.find(_info.id); if (iter == this->peers.end()) { - igndbg << "Attempting to remove peer [" << _info.id << "] from [" + gzdbg << "Attempting to remove peer [" << _info.id << "] from [" << this->info.id << "] but it wasn't connected" << std::endl; return false; } diff --git a/src/network/PeerTracker.hh b/src/network/PeerTracker.hh index 985991ab3a..3a373be2bf 100644 --- a/src/network/PeerTracker.hh +++ b/src/network/PeerTracker.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_NETWORK_PEERTRACKER_HH_ -#define IGNITION_GAZEBO_NETWORK_PEERTRACKER_HH_ +#ifndef GZ_SIM_NETWORK_PEERTRACKER_HH_ +#define GZ_SIM_NETWORK_PEERTRACKER_HH_ #include #include @@ -31,12 +31,12 @@ #include "PeerInfo.hh" -namespace ignition +namespace gz { - namespace gazebo + namespace sim { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { + inline namespace GZ_SIM_VERSION_NAMESPACE { // Network Events /// \brief PeerAdded fired when a peer announces itself or detected via /// heartbeat @@ -53,9 +53,9 @@ namespace ignition /// /// It is used to both announce the existence of a peer, as well as track /// announcements and heartbeats from other peers. - class IGNITION_GAZEBO_VISIBLE PeerTracker { + class GZ_GAZEBO_VISIBLE 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 + } // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_NETWORKCONFIG_HH_ +#endif // GZ_SIM_NETWORKCONFIG_HH_ diff --git a/src/network/PeerTracker_TEST.cc b/src/network/PeerTracker_TEST.cc index 6c5499dd96..fdc1d0d5d9 100644 --- a/src/network/PeerTracker_TEST.cc +++ b/src/network/PeerTracker_TEST.cc @@ -25,12 +25,12 @@ #include "PeerTracker.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 4a3a54d6ec..cb01aee34d 100644 --- a/src/rendering/MarkerManager.cc +++ b/src/rendering/MarkerManager.cc @@ -33,59 +33,59 @@ #include "gz/sim/rendering/MarkerManager.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace 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. /// \return True if the marker was processed successfully. - public: bool ProcessMarkerMsg(const ignition::msgs::Marker &_msg); + public: bool ProcessMarkerMsg(const gz::msgs::Marker &_msg); /// \brief Converts an ignition msg render type to ignition rendering /// \param[in] _msg The message data /// \return Converted rendering type, if any. - public: ignition::rendering::MarkerType MsgToType( - const ignition::msgs::Marker &_msg); + public: gz::rendering::MarkerType MsgToType( + const gz::msgs::Marker &_msg); /// \brief Converts an ignition msg material to ignition rendering // material. // \param[in] _msg The message data. // \return Converted rendering material, if any. public: rendering::MaterialPtr MsgToMaterial( - const ignition::msgs::Marker &_msg); + const gz::msgs::Marker &_msg); /// \brief Updates the markers. public: void Update(); /// \brief Callback that receives marker messages. /// \param[in] _req The marker message. - public: void OnMarkerMsg(const ignition::msgs::Marker &_req); + public: void OnMarkerMsg(const gz::msgs::Marker &_req); /// \brief Callback that receives multiple marker messages. /// \param[in] _req The vector of marker messages /// \param[in] _res Response data /// \return True if the request is received - public: bool OnMarkerMsgArray(const ignition::msgs::Marker_V &_req, - ignition::msgs::Boolean &_res); + public: bool OnMarkerMsgArray(const gz::msgs::Marker_V &_req, + gz::msgs::Boolean &_res); /// \brief Services callback that returns a list of markers. /// \param[out] _rep Service reply /// \return True on success. - public: bool OnList(ignition::msgs::Marker_V &_rep); + public: bool OnList(gz::msgs::Marker_V &_rep); /// \brief Sets Marker from marker message. /// \param[in] _msg The message data. /// \param[out] _markerPtr The message pointer to set. - public: void SetMarker(const ignition::msgs::Marker &_msg, + public: void SetMarker(const gz::msgs::Marker &_msg, const rendering::MarkerPtr &_markerPtr); /// \brief Sets Visual from marker message. /// \param[in] _msg The message data. /// \param[out] _visualPtr The visual pointer to set. - public: void SetVisual(const ignition::msgs::Marker &_msg, + public: void SetVisual(const gz::msgs::Marker &_msg, const rendering::VisualPtr &_visualPtr); /// \brief Sets sim time from time. @@ -100,22 +100,22 @@ class ignition::gazebo::MarkerManagerPrivate /// \brief Map of visuals public: std::map> visuals; + std::map> visuals; /// \brief List of marker message to process. - public: std::list markerMsgs; + public: std::list markerMsgs; /// \brief Pointer to the scene public: rendering::ScenePtr scene; /// \brief Ignition node - public: ignition::transport::Node node; + public: gz::transport::Node node; /// \brief Sim time according to UpdateInfo in RenderUtil public: std::chrono::steady_clock::duration simTime; /// \brief The last marker message received - public: ignition::msgs::Marker msg; + public: gz::msgs::Marker msg; /// \brief Topic name for the marker service public: std::string topicName = "/marker"; @@ -149,11 +149,11 @@ void MarkerManager::Update() } ///////////////////////////////////////////////// -bool MarkerManager::Init(const ignition::rendering::ScenePtr &_scene) +bool MarkerManager::Init(const gz::rendering::ScenePtr &_scene) { if (!_scene) { - ignerr << "Scene pointer is invalid\n"; + gzerr << "Scene pointer is invalid\n"; return false; } @@ -161,7 +161,7 @@ bool MarkerManager::Init(const ignition::rendering::ScenePtr &_scene) if (this->dataPtr->topicName.empty()) { - ignerr << "Unable to advertise marker service. Topic name empty.\n"; + gzerr << "Unable to advertise marker service. Topic name empty.\n"; return false; } @@ -169,7 +169,7 @@ bool MarkerManager::Init(const ignition::rendering::ScenePtr &_scene) if (!this->dataPtr->node.Advertise(this->dataPtr->topicName + "/list", &MarkerManagerPrivate::OnList, this->dataPtr.get())) { - ignerr << "Unable to advertise to the " << this->dataPtr->topicName + gzerr << "Unable to advertise to the " << this->dataPtr->topicName << "/list service.\n"; } @@ -177,7 +177,7 @@ bool MarkerManager::Init(const ignition::rendering::ScenePtr &_scene) if (!this->dataPtr->node.Advertise(this->dataPtr->topicName, &MarkerManagerPrivate::OnMarkerMsg, this->dataPtr.get())) { - ignerr << "Unable to advertise to the " << this->dataPtr->topicName + gzerr << "Unable to advertise to the " << this->dataPtr->topicName << " service.\n"; } @@ -185,7 +185,7 @@ bool MarkerManager::Init(const ignition::rendering::ScenePtr &_scene) if (!this->dataPtr->node.Advertise(this->dataPtr->topicName + "_array", &MarkerManagerPrivate::OnMarkerMsgArray, this->dataPtr.get())) { - ignerr << "Unable to advertise to the " << this->dataPtr->topicName + gzerr << "Unable to advertise to the " << this->dataPtr->topicName << "_array service.\n"; } @@ -229,8 +229,8 @@ void MarkerManagerPrivate::Update() if (it->second->GeometryCount() == 0u) continue; - ignition::rendering::MarkerPtr markerPtr = - std::dynamic_pointer_cast + gz::rendering::MarkerPtr markerPtr = + std::dynamic_pointer_cast (it->second->GeometryByIndex(0u)); if (markerPtr != nullptr) { @@ -263,7 +263,7 @@ void MarkerManagerPrivate::SetSimTime( } ///////////////////////////////////////////////// -void MarkerManagerPrivate::SetVisual(const ignition::msgs::Marker &_msg, +void MarkerManagerPrivate::SetVisual(const gz::msgs::Marker &_msg, const rendering::VisualPtr &_visualPtr) { // Set Visual Scale @@ -294,7 +294,7 @@ void MarkerManagerPrivate::SetVisual(const ignition::msgs::Marker &_msg, } else { - ignerr << "No visual with the name[" << _msg.parent() << "]\n"; + gzerr << "No visual with the name[" << _msg.parent() << "]\n"; } } @@ -302,7 +302,7 @@ void MarkerManagerPrivate::SetVisual(const ignition::msgs::Marker &_msg, } ///////////////////////////////////////////////// -void MarkerManagerPrivate::SetMarker(const ignition::msgs::Marker &_msg, +void MarkerManagerPrivate::SetMarker(const gz::msgs::Marker &_msg, const rendering::MarkerPtr &_markerPtr) { _markerPtr->SetLayer(_msg.layer()); @@ -319,7 +319,7 @@ void MarkerManagerPrivate::SetMarker(const ignition::msgs::Marker &_msg, _markerPtr->SetLifetime(std::chrono::seconds(0)); } // Set Marker Render Type - ignition::rendering::MarkerType markerType = MsgToType(_msg); + gz::rendering::MarkerType markerType = MsgToType(_msg); _markerPtr->SetType(markerType); // Set Marker Material @@ -357,49 +357,49 @@ void MarkerManagerPrivate::SetMarker(const ignition::msgs::Marker &_msg, } ///////////////////////////////////////////////// -ignition::rendering::MarkerType MarkerManagerPrivate::MsgToType( - const ignition::msgs::Marker &_msg) +gz::rendering::MarkerType MarkerManagerPrivate::MsgToType( + const gz::msgs::Marker &_msg) { - ignition::msgs::Marker_Type marker = this->msg.type(); - if (marker != _msg.type() && _msg.type() != ignition::msgs::Marker::NONE) + gz::msgs::Marker_Type marker = this->msg.type(); + if (marker != _msg.type() && _msg.type() != gz::msgs::Marker::NONE) { marker = _msg.type(); this->msg.set_type(_msg.type()); } switch (marker) { - case ignition::msgs::Marker::BOX: - return ignition::rendering::MarkerType::MT_BOX; - case ignition::msgs::Marker::CAPSULE: - return ignition::rendering::MarkerType::MT_CAPSULE; - case ignition::msgs::Marker::CYLINDER: - return ignition::rendering::MarkerType::MT_CYLINDER; - case ignition::msgs::Marker::LINE_STRIP: - return ignition::rendering::MarkerType::MT_LINE_STRIP; - case ignition::msgs::Marker::LINE_LIST: - return ignition::rendering::MarkerType::MT_LINE_LIST; - case ignition::msgs::Marker::POINTS: - return ignition::rendering::MarkerType::MT_POINTS; - case ignition::msgs::Marker::SPHERE: - return ignition::rendering::MarkerType::MT_SPHERE; - case ignition::msgs::Marker::TEXT: - return ignition::rendering::MarkerType::MT_TEXT; - case ignition::msgs::Marker::TRIANGLE_FAN: - return ignition::rendering::MarkerType::MT_TRIANGLE_FAN; - case ignition::msgs::Marker::TRIANGLE_LIST: - return ignition::rendering::MarkerType::MT_TRIANGLE_LIST; - case ignition::msgs::Marker::TRIANGLE_STRIP: - return ignition::rendering::MarkerType::MT_TRIANGLE_STRIP; + case gz::msgs::Marker::BOX: + return gz::rendering::MarkerType::MT_BOX; + case gz::msgs::Marker::CAPSULE: + return gz::rendering::MarkerType::MT_CAPSULE; + case gz::msgs::Marker::CYLINDER: + return gz::rendering::MarkerType::MT_CYLINDER; + case gz::msgs::Marker::LINE_STRIP: + return gz::rendering::MarkerType::MT_LINE_STRIP; + case gz::msgs::Marker::LINE_LIST: + return gz::rendering::MarkerType::MT_LINE_LIST; + case gz::msgs::Marker::POINTS: + return gz::rendering::MarkerType::MT_POINTS; + case gz::msgs::Marker::SPHERE: + return gz::rendering::MarkerType::MT_SPHERE; + case gz::msgs::Marker::TEXT: + return gz::rendering::MarkerType::MT_TEXT; + case gz::msgs::Marker::TRIANGLE_FAN: + return gz::rendering::MarkerType::MT_TRIANGLE_FAN; + case gz::msgs::Marker::TRIANGLE_LIST: + return gz::rendering::MarkerType::MT_TRIANGLE_LIST; + case gz::msgs::Marker::TRIANGLE_STRIP: + return gz::rendering::MarkerType::MT_TRIANGLE_STRIP; default: - ignerr << "Unable to create marker of type[" << _msg.type() << "]\n"; + gzerr << "Unable to create marker of type[" << _msg.type() << "]\n"; break; } - return ignition::rendering::MarkerType::MT_NONE; + return gz::rendering::MarkerType::MT_NONE; } ///////////////////////////////////////////////// rendering::MaterialPtr MarkerManagerPrivate::MsgToMaterial( - const ignition::msgs::Marker &_msg) + const gz::msgs::Marker &_msg) { rendering::MaterialPtr material = this->scene->CreateMaterial(); @@ -433,7 +433,7 @@ rendering::MaterialPtr MarkerManagerPrivate::MsgToMaterial( } ////////////////////////////////////////////////// -bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) +bool MarkerManagerPrivate::ProcessMarkerMsg(const gz::msgs::Marker &_msg) { // Get the namespace, if it exists. Otherwise, use the global namespace std::string ns; @@ -453,14 +453,14 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) // Otherwise generate unique id else { - id = ignition::math::Rand::IntUniform(0, ignition::math::MAX_I32); + id = gz::math::Rand::IntUniform(0, gz::math::MAX_I32); // Make sure it's unique if namespace is given if (nsIter != this->visuals.end()) { while (nsIter->second.find(id) != nsIter->second.end()) - id = ignition::math::Rand::IntUniform(ignition::math::MIN_UI32, - ignition::math::MAX_UI32); + id = gz::math::Rand::IntUniform(gz::math::MIN_UI32, + gz::math::MAX_UI32); } } @@ -470,7 +470,7 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) visualIter = nsIter->second.find(id); // Add/modify a marker - if (_msg.action() == ignition::msgs::Marker::ADD_MODIFY) + if (_msg.action() == gz::msgs::Marker::ADD_MODIFY) { // Modify an existing marker, identified by namespace and id if (nsIter != this->visuals.end() && @@ -480,8 +480,8 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) { // TODO(anyone): Update so that multiple markers can // be attached to one visual - ignition::rendering::MarkerPtr markerPtr = - std::dynamic_pointer_cast + gz::rendering::MarkerPtr markerPtr = + std::dynamic_pointer_cast (visualIter->second->GeometryByIndex(0)); visualIter->second->RemoveGeometryByIndex(0); @@ -528,7 +528,7 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) } } // Remove a single marker - else if (_msg.action() == ignition::msgs::Marker::DELETE_MARKER) + else if (_msg.action() == gz::msgs::Marker::DELETE_MARKER) { // Remove the marker if it can be found. if (nsIter != this->visuals.end() && @@ -543,18 +543,18 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) } else { - ignwarn << "Unable to delete marker with id[" << id << "] " + gzwarn << "Unable to delete marker with id[" << id << "] " << "in namespace[" << ns << "]" << std::endl; return false; } } // Remove all markers, or all markers in a namespace - else if (_msg.action() == ignition::msgs::Marker::DELETE_ALL) + else if (_msg.action() == gz::msgs::Marker::DELETE_ALL) { // If given namespace doesn't exist if (!ns.empty() && nsIter == this->visuals.end()) { - ignwarn << "Unable to delete all markers in namespace[" << ns << + gzwarn << "Unable to delete all markers in namespace[" << ns << "], namespace can't be found." << std::endl; return false; } @@ -584,7 +584,7 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) } else { - ignerr << "Unknown marker action[" << _msg.action() << "]\n"; + gzerr << "Unknown marker action[" << _msg.action() << "]\n"; return false; } @@ -593,7 +593,7 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) ///////////////////////////////////////////////// -bool MarkerManagerPrivate::OnList(ignition::msgs::Marker_V &_rep) +bool MarkerManagerPrivate::OnList(gz::msgs::Marker_V &_rep) { std::lock_guard lock(this->mutex); _rep.clear_marker(); @@ -603,7 +603,7 @@ bool MarkerManagerPrivate::OnList(ignition::msgs::Marker_V &_rep) { for (auto iter : mIter.second) { - ignition::msgs::Marker *markerMsg = _rep.add_marker(); + gz::msgs::Marker *markerMsg = _rep.add_marker(); markerMsg->set_ns(mIter.first); markerMsg->set_id(iter.first); } @@ -613,7 +613,7 @@ bool MarkerManagerPrivate::OnList(ignition::msgs::Marker_V &_rep) } ///////////////////////////////////////////////// -void MarkerManagerPrivate::OnMarkerMsg(const ignition::msgs::Marker &_req) +void MarkerManagerPrivate::OnMarkerMsg(const gz::msgs::Marker &_req) { std::lock_guard lock(this->mutex); this->markerMsgs.push_back(_req); @@ -621,7 +621,7 @@ void MarkerManagerPrivate::OnMarkerMsg(const ignition::msgs::Marker &_req) ///////////////////////////////////////////////// bool MarkerManagerPrivate::OnMarkerMsgArray( - const ignition::msgs::Marker_V&_req, ignition::msgs::Boolean &_res) + const gz::msgs::Marker_V&_req, gz::msgs::Boolean &_res) { std::lock_guard lock(this->mutex); std::copy(_req.marker().begin(), _req.marker().end(), diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 3ee71ba7f8..8ff5d5a02c 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -97,11 +97,11 @@ #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; // Private data class. -class ignition::gazebo::RenderUtilPrivate +class gz::sim::RenderUtilPrivate { /// True if the rendering component is initialized public: bool initialized = false; @@ -228,7 +228,7 @@ class ignition::gazebo::RenderUtilPrivate public: MarkerManager markerManager; /// \brief Pointer to rendering engine. - public: ignition::rendering::RenderEngine *engine{nullptr}; + public: gz::rendering::RenderEngine *engine{nullptr}; /// \brief rendering scene to be managed by the scene manager and used to /// generate sensor data @@ -345,7 +345,7 @@ class ignition::gazebo::RenderUtilPrivate public: std::unordered_map entityLabel; /// \brief A map of entity ids and wire boxes - public: std::unordered_map wireBoxes; + public: std::unordered_map wireBoxes; /// \brief A map of entity ids and trajectory pose updates. public: std::unordered_map trajectoryPoses; @@ -371,7 +371,7 @@ class ignition::gazebo::RenderUtilPrivate /// \brief Callback function for creating sensors. /// The function args are: entity id, sensor sdf, and parent name. /// The function returns the id of the rendering sensor created. - public: std::function createSensorCb; /// \brief Light equality comparison function. @@ -407,7 +407,7 @@ class ignition::gazebo::RenderUtilPrivate /// \brief Callback function for removing sensors. /// The function arg is the entity id - public: std::function removeSensorCb; + public: std::function removeSensorCb; /// \brief Currently selected entities, organized by order of selection. public: std::vector selectedEntities; @@ -834,7 +834,7 @@ void RenderUtilPrivate::FindInertialLinks(const EntityComponentManager &_ecm) } else { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] for viewing inertia must be a model or link" << std::endl; continue; @@ -858,7 +858,7 @@ void RenderUtilPrivate::FindInertialLinks(const EntityComponentManager &_ecm) } else { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] for viewing center of mass must be a model or link" << std::endl; continue; @@ -906,7 +906,7 @@ void RenderUtilPrivate::FindJointModels(const EntityComponentManager &_ecm) } else { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] for viewing joints must be a model" << std::endl; continue; @@ -936,7 +936,7 @@ void RenderUtilPrivate::PopulateViewModeVisualLinks( } else { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] for viewing wireframe must be a model or link" << std::endl; continue; @@ -961,7 +961,7 @@ void RenderUtilPrivate::PopulateViewModeVisualLinks( } else { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] for viewing as transparent must be a model or link" << std::endl; continue; @@ -993,7 +993,7 @@ void RenderUtilPrivate::FindCollisionLinks(const EntityComponentManager &_ecm) } else { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] for viewing collision must be a model or link" << std::endl; continue; @@ -1235,7 +1235,7 @@ void RenderUtil::Update() auto parentNode = this->dataPtr->sceneManager.NodeById(parent); if (!parentNode) { - ignerr << "Failed to create sensor with name[" << dataSdf.Name() + gzerr << "Failed to create sensor with name[" << dataSdf.Name() << "] for entity [" << entity << "]. Parent not found with ID[" << parent << "]." << std::endl; @@ -1247,7 +1247,7 @@ void RenderUtil::Update() // Add to the system's scene manager if (!this->dataPtr->sceneManager.AddSensor(entity, sensorName, parent)) { - ignerr << "Failed to create sensor [" << sensorName << "]" + gzerr << "Failed to create sensor [" << sensorName << "]" << std::endl; } } @@ -1299,7 +1299,7 @@ void RenderUtil::Update() auto actorVisual = this->dataPtr->sceneManager.NodeById(tf.first); if (!actorMesh || !actorVisual) { - ignerr << "Actor with Entity ID '" << tf.first << "'. not found. " + gzerr << "Actor with Entity ID '" << tf.first << "'. not found. " << "Skipping skeleton animation update." << std::endl; continue; } @@ -2501,7 +2501,7 @@ void RenderUtil::Init() if (nullptr != this->dataPtr->scene) return; - ignition::common::SystemPaths pluginPath; + gz::common::SystemPaths pluginPath; pluginPath.SetPluginPathEnv(kRenderPluginPathEnv); rendering::setPluginPaths(pluginPath.PluginPaths()); @@ -2514,7 +2514,7 @@ void RenderUtil::Init() this->dataPtr->engine = rendering::engine(this->dataPtr->engineName, params); if (!this->dataPtr->engine) { - ignerr << "Engine [" << this->dataPtr->engineName << "] is not supported. " + gzerr << "Engine [" << this->dataPtr->engineName << "] is not supported. " << "Loading OGRE2 instead." << std::endl; this->dataPtr->engine = rendering::engine("ogre2", params); } @@ -2524,7 +2524,7 @@ void RenderUtil::Init() this->dataPtr->engine->SceneByName(this->dataPtr->sceneName); if (!this->dataPtr->scene) { - igndbg << "Create scene [" << this->dataPtr->sceneName << "]" << std::endl; + gzdbg << "Create scene [" << this->dataPtr->sceneName << "]" << std::endl; this->dataPtr->scene = this->dataPtr->engine->CreateScene(this->dataPtr->sceneName); if (this->dataPtr->scene) @@ -2580,7 +2580,7 @@ void RenderUtil::ShowGrid() rendering::GridPtr gridGeom = this->dataPtr->scene->CreateGrid(); if (!gridGeom) { - ignwarn << "Failed to create grid for scene [" + gzwarn << "Failed to create grid for scene [" << this->dataPtr->scene->Name() << "] on engine [" << this->dataPtr->scene->Engine()->Name() << "]" << std::endl; @@ -2647,7 +2647,7 @@ void RenderUtil::SetWinID(const std::string &_winID) ///////////////////////////////////////////////// void RenderUtil::SetEnableSensors(bool _enable, - std::function _createSensorCb) { this->dataPtr->enableSensors = _enable; @@ -2656,7 +2656,7 @@ void RenderUtil::SetEnableSensors(bool _enable, ///////////////////////////////////////////////// void RenderUtil::SetRemoveSensorCb( - std::function _removeSensorCb) + std::function _removeSensorCb) { this->dataPtr->removeSensorCb = std::move(_removeSensorCb); } @@ -2777,7 +2777,7 @@ void RenderUtilPrivate::HighlightNode(const rendering::NodePtr &_node) wireBox->SetBox(aabb); // Create visual and add wire box - ignition::rendering::VisualPtr wireBoxVis = + gz::rendering::VisualPtr wireBoxVis = this->scene->CreateVisual(); wireBoxVis->SetInheritScale(false); wireBoxVis->AddGeometry(wireBox); @@ -2787,12 +2787,12 @@ void RenderUtilPrivate::HighlightNode(const rendering::NodePtr &_node) // Add wire box to map for setting visibility this->wireBoxes.insert( - std::pair(entityId, wireBox)); + std::pair(entityId, wireBox)); } else { - ignition::rendering::WireBoxPtr wireBox = wireBoxIt->second; - ignition::math::AxisAlignedBox aabb = vis->LocalBoundingBox(); + gz::rendering::WireBoxPtr wireBox = wireBoxIt->second; + gz::math::AxisAlignedBox aabb = vis->LocalBoundingBox(); wireBox->SetBox(aabb); auto visParent = wireBox->Parent(); if (visParent) @@ -2811,7 +2811,7 @@ void RenderUtilPrivate::LowlightNode(const rendering::NodePtr &_node) entityId = std::get(vis->UserData("gazebo-entity")); if (this->wireBoxes.find(entityId) != this->wireBoxes.end()) { - ignition::rendering::WireBoxPtr wireBox = + gz::rendering::WireBoxPtr wireBox = this->wireBoxes[entityId]; auto visParent = wireBox->Parent(); if (visParent) @@ -2863,7 +2863,7 @@ void RenderUtilPrivate::UpdateLights( if (!light.second.is_light_off()) { - if (!ignition::math::equal( + if (!gz::math::equal( l->Intensity(), static_cast(light.second.intensity()))) { @@ -2886,25 +2886,25 @@ void RenderUtilPrivate::UpdateLights( l->SetSpecularColor(msgs::Convert(light.second.specular())); } } - if (!ignition::math::equal( + if (!gz::math::equal( l->AttenuationRange(), static_cast(light.second.range()))) { l->SetAttenuationRange(light.second.range()); } - if (!ignition::math::equal( + if (!gz::math::equal( l->AttenuationLinear(), static_cast(light.second.attenuation_linear()))) { l->SetAttenuationLinear(light.second.attenuation_linear()); } - if (!ignition::math::equal( + if (!gz::math::equal( l->AttenuationConstant(), static_cast(light.second.attenuation_constant()))) { l->SetAttenuationConstant(light.second.attenuation_constant()); } - if (!ignition::math::equal( + if (!gz::math::equal( l->AttenuationQuadratic(), static_cast(light.second.attenuation_quadratic()))) { @@ -2943,7 +2943,7 @@ void RenderUtilPrivate::UpdateLights( lSpotLight->SetInnerAngle(light.second.spot_inner_angle()); if (lSpotLight->OuterAngle() != light.second.spot_outer_angle()) lSpotLight->SetOuterAngle(light.second.spot_outer_angle()); - if (!ignition::math::equal( + if (!gz::math::equal( lSpotLight->Falloff(), static_cast(light.second.spot_falloff()))) { @@ -2974,7 +2974,7 @@ void RenderUtilPrivate::UpdateThermalCamera(const std::unordered_mapLinearResolution() << ". " << std::endl; } @@ -2987,7 +2987,7 @@ void RenderUtilPrivate::UpdateThermalCamera(const std::unordered_mapMinTemperature() << ", " << camera->MaxTemperature() << "]." << std::endl; @@ -3010,7 +3010,7 @@ void RenderUtilPrivate::UpdateAnimation(const std::unordered_mapdataPtr->wireBoxes.find(_entity); if (wireBoxIt != this->dataPtr->wireBoxes.end()) { - ignition::rendering::WireBoxPtr wireBox = wireBoxIt->second; + gz::rendering::WireBoxPtr wireBox = wireBoxIt->second; auto visParent = wireBox->Parent(); if (visParent) visParent->SetVisible(false); @@ -3192,7 +3192,7 @@ void RenderUtil::ViewInertia(const Entity &_entity) this->dataPtr->sceneManager.VisualById(inertiaVisualId); if (inertiaVisual == nullptr) { - ignerr << "Could not find inertia visual for entity [" << inertiaLink + gzerr << "Could not find inertia visual for entity [" << inertiaLink << "]" << std::endl; continue; } @@ -3251,7 +3251,7 @@ void RenderUtil::ViewCOM(const Entity &_entity) this->dataPtr->sceneManager.VisualById(comVisualId); if (comVisual == nullptr) { - ignerr << "Could not find center of mass visual for entity [" + gzerr << "Could not find center of mass visual for entity [" << inertiaLink << "]" << std::endl; continue; @@ -3337,7 +3337,7 @@ void RenderUtil::ViewJoints(const Entity &_entity) this->dataPtr->sceneManager.VisualById(jointEntity); if (jointVisual == nullptr) { - ignerr << "Could not find visual for entity [" << jointEntity + gzerr << "Could not find visual for entity [" << jointEntity << "]" << std::endl; continue; } @@ -3407,7 +3407,7 @@ void RenderUtil::ViewTransparent(const Entity &_entity) this->dataPtr->sceneManager.VisualById(visEntity); if (transparentVisual == nullptr) { - ignerr << "Could not find visual for entity [" << visEntity + gzerr << "Could not find visual for entity [" << visEntity << "]" << std::endl; continue; } @@ -3479,7 +3479,7 @@ void RenderUtil::ViewWireframes(const Entity &_entity) this->dataPtr->sceneManager.VisualById(visEntity); if (wireframeVisual == nullptr) { - ignerr << "Could not find visual for entity [" << visEntity + gzerr << "Could not find visual for entity [" << visEntity << "]" << std::endl; continue; } @@ -3549,7 +3549,7 @@ void RenderUtil::ViewCollisions(const Entity &_entity) this->dataPtr->sceneManager.VisualById(colEntity); if (colVisual == nullptr) { - ignerr << "Could not find collision visual for entity [" << colEntity + gzerr << "Could not find collision visual for entity [" << colEntity << "]" << std::endl; continue; } diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index ab821e7f73..3efcb359c5 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -63,18 +63,18 @@ #include "gz/sim/Util.hh" #include "gz/sim/rendering/SceneManager.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace std::chrono_literals; using TP = std::chrono::steady_clock::time_point; /// \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. - /// Defaults to zero, which is considered invalid by Ignition Gazebo. + /// Defaults to zero, which is considered invalid by Gazebo. public: Entity worldId{0}; //// \brief Pointer to the rendering scene @@ -161,7 +161,7 @@ rendering::VisualPtr SceneManager::CreateModel(Entity _id, if (this->dataPtr->visuals.find(_id) != this->dataPtr->visuals.end()) { - ignerr << "Entity with Id: [" << _id << "] already exists in the scene" + gzerr << "Entity with Id: [" << _id << "] already exists in the scene" << std::endl; return rendering::VisualPtr(); } @@ -175,7 +175,7 @@ rendering::VisualPtr SceneManager::CreateModel(Entity _id, auto it = this->dataPtr->visuals.find(_parentId); if (it == this->dataPtr->visuals.end()) { - ignerr << "Parent entity with Id: [" << _parentId << "] not found. " + gzerr << "Parent entity with Id: [" << _parentId << "] not found. " << "Not adding model visual with ID[" << _id << "] and name [" << name << "] to the rendering scene." << std::endl; @@ -189,7 +189,7 @@ rendering::VisualPtr SceneManager::CreateModel(Entity _id, if (this->dataPtr->scene->HasVisualName(name)) { - ignerr << "Visual: [" << name << "] already exists" << std::endl; + gzerr << "Visual: [" << name << "] already exists" << std::endl; return rendering::VisualPtr(); } @@ -217,7 +217,7 @@ rendering::VisualPtr SceneManager::CreateLink(Entity _id, if (this->dataPtr->visuals.find(_id) != this->dataPtr->visuals.end()) { - ignerr << "Entity with Id: [" << _id << "] already exists in the scene" + gzerr << "Entity with Id: [" << _id << "] already exists in the scene" << std::endl; return rendering::VisualPtr(); } @@ -260,7 +260,7 @@ rendering::VisualPtr SceneManager::CreateVisual(Entity _id, if (this->dataPtr->visuals.find(_id) != this->dataPtr->visuals.end()) { - ignerr << "Entity with Id: [" << _id << "] already exists in the scene" + gzerr << "Entity with Id: [" << _id << "] already exists in the scene" << std::endl; return rendering::VisualPtr(); } @@ -391,7 +391,7 @@ rendering::VisualPtr SceneManager::CreateVisual(Entity _id, } else { - ignerr << "Failed to load geometry for visual: " << _visual.Name() + gzerr << "Failed to load geometry for visual: " << _visual.Name() << std::endl; } @@ -415,7 +415,7 @@ std::vector SceneManager::Filter(const std::string &_node, auto rootNode = this->dataPtr->scene->NodeByName(_node); if (!rootNode) { - ignerr << "Could not find a node with the name [" << _node + gzerr << "Could not find a node with the name [" << _node << "] in the scene." << std::endl; return filteredNodes; } @@ -448,7 +448,7 @@ std::pair> SceneManager::CopyVisual( if (this->dataPtr->visuals.find(_id) != this->dataPtr->visuals.end()) { - ignerr << "Entity with Id: [" << _id << "] already exists in the scene" + gzerr << "Entity with Id: [" << _id << "] already exists in the scene" << std::endl; return result; } @@ -458,7 +458,7 @@ std::pair> SceneManager::CopyVisual( this->dataPtr->scene->NodeByName(_visual)); if (!originalVisual) { - ignerr << "Could not find a node with the name [" << _visual + gzerr << "Could not find a node with the name [" << _visual << "] in the scene." << std::endl; return result; } @@ -471,7 +471,7 @@ std::pair> SceneManager::CopyVisual( auto it = this->dataPtr->visuals.find(_parentId); if (it == this->dataPtr->visuals.end()) { - ignerr << "Parent entity with Id: [" << _parentId << "] not found. " + gzerr << "Parent entity with Id: [" << _parentId << "] not found. " << "Not adding visual with ID [" << _id << "] and name [" << name << "] to the rendering scene." << std::endl; @@ -485,7 +485,7 @@ std::pair> SceneManager::CopyVisual( if (this->dataPtr->scene->HasVisualName(name)) { - ignerr << "Visual: [" << name << "] already exists" << std::endl; + gzerr << "Visual: [" << name << "] already exists" << std::endl; return result; } @@ -531,7 +531,7 @@ std::pair> SceneManager::CopyVisual( auto childId = this->UniqueId(); if (!childId) { - ignerr << "Unable to create an entity ID for the copied visual's " + gzerr << "Unable to create an entity ID for the copied visual's " << "child, so the copied visual will be deleted.\n"; childrenTracked = false; break; @@ -540,7 +540,7 @@ std::pair> SceneManager::CopyVisual( visual->ChildByIndex(i)); if (!childVisual) { - ignerr << "Unable to retrieve a child visual of the copied visual, " + gzerr << "Unable to retrieve a child visual of the copied visual, " << "so the copied visual will be deleted.\n"; childrenTracked = false; break; @@ -580,7 +580,7 @@ rendering::VisualPtr SceneManager::VisualById(Entity _id) { if (this->dataPtr->visuals.find(_id) == this->dataPtr->visuals.end()) { - ignerr << "Could not find visual for entity: " << _id << std::endl; + gzerr << "Could not find visual for entity: " << _id << std::endl; return nullptr; } return this->dataPtr->visuals[_id]; @@ -667,7 +667,7 @@ rendering::GeometryPtr SceneManager::LoadGeometry(const sdf::Geometry &_geom, _geom.MeshShape()->FilePath()); if (fullPath.empty()) { - ignerr << "Mesh geometry missing uri" << std::endl; + gzerr << "Mesh geometry missing uri" << std::endl; return geom; } rendering::MeshDescriptor descriptor; @@ -677,8 +677,8 @@ rendering::GeometryPtr SceneManager::LoadGeometry(const sdf::Geometry &_geom, descriptor.subMeshName = _geom.MeshShape()->Submesh(); descriptor.centerSubMesh = _geom.MeshShape()->CenterSubmesh(); - ignition::common::MeshManager *meshManager = - ignition::common::MeshManager::Instance(); + gz::common::MeshManager *meshManager = + gz::common::MeshManager::Instance(); descriptor.mesh = meshManager->Load(descriptor.meshName); geom = this->dataPtr->scene->CreateMesh(descriptor); scale = _geom.MeshShape()->Scale(); @@ -689,7 +689,7 @@ rendering::GeometryPtr SceneManager::LoadGeometry(const sdf::Geometry &_geom, _geom.HeightmapShape()->FilePath())); if (fullPath.empty()) { - ignerr << "Heightmap geometry missing URI" << std::endl; + gzerr << "Heightmap geometry missing URI" << std::endl; return geom; } @@ -704,7 +704,7 @@ rendering::GeometryPtr SceneManager::LoadGeometry(const sdf::Geometry &_geom, auto img = std::make_shared(); if (img->Load(fullPath) < 0) { - ignerr << "Failed to load heightmap image data from [" + gzerr << "Failed to load heightmap image data from [" << fullPath << "]" << std::endl; return geom; } @@ -716,7 +716,7 @@ rendering::GeometryPtr SceneManager::LoadGeometry(const sdf::Geometry &_geom, auto dem = std::make_shared(); if (dem->Load(fullPath) < 0) { - ignerr << "Failed to load heightmap dem data from [" + gzerr << "Failed to load heightmap dem data from [" << fullPath << "]" << std::endl; return geom; } @@ -753,13 +753,13 @@ rendering::GeometryPtr SceneManager::LoadGeometry(const sdf::Geometry &_geom, geom = this->dataPtr->scene->CreateHeightmap(descriptor); if (nullptr == geom) { - ignerr << "Failed to create heightmap [" << fullPath << "]" << std::endl; + gzerr << "Failed to create heightmap [" << fullPath << "]" << std::endl; } scale = _geom.HeightmapShape()->Size(); } else { - ignerr << "Unsupported geometry type" << std::endl; + gzerr << "Unsupported geometry type" << std::endl; } _scale = scale; _localPose = localPose; @@ -803,7 +803,7 @@ rendering::MaterialPtr SceneManager::LoadMaterial( if (!fullPath.empty()) material->SetRoughnessMap(fullPath); else - ignerr << "Unable to find file [" << roughnessMap << "]\n"; + gzerr << "Unable to find file [" << roughnessMap << "]\n"; } // metalness map @@ -815,7 +815,7 @@ rendering::MaterialPtr SceneManager::LoadMaterial( if (!fullPath.empty()) material->SetMetalnessMap(fullPath); else - ignerr << "Unable to find file [" << metalnessMap << "]\n"; + gzerr << "Unable to find file [" << metalnessMap << "]\n"; } workflow = const_cast(metal); } @@ -824,8 +824,8 @@ rendering::MaterialPtr SceneManager::LoadMaterial( auto specular = pbr->Workflow(sdf::PbrWorkflowType::SPECULAR); if (specular) { - ignerr << "PBR material: currently only metal workflow is supported. " - << "Ignition Gazebo will try to render the material using " + gzerr << "PBR material: currently only metal workflow is supported. " + << "Gazebo will try to render the material using " << "metal workflow but without Roughness / Metalness settings." << std::endl; } @@ -834,7 +834,7 @@ rendering::MaterialPtr SceneManager::LoadMaterial( if (!workflow) { - ignerr << "No valid PBR workflow found. " << std::endl; + gzerr << "No valid PBR workflow found. " << std::endl; return rendering::MaterialPtr(); } @@ -851,7 +851,7 @@ rendering::MaterialPtr SceneManager::LoadMaterial( material->SetAlphaFromTexture(true, 0.5, _material.DoubleSided()); } else - ignerr << "Unable to find file [" << albedoMap << "]\n"; + gzerr << "Unable to find file [" << albedoMap << "]\n"; } // normal map @@ -863,7 +863,7 @@ rendering::MaterialPtr SceneManager::LoadMaterial( if (!fullPath.empty()) material->SetNormalMap(fullPath); else - ignerr << "Unable to find file [" << normalMap << "]\n"; + gzerr << "Unable to find file [" << normalMap << "]\n"; } @@ -876,7 +876,7 @@ rendering::MaterialPtr SceneManager::LoadMaterial( if (!fullPath.empty()) material->SetEnvironmentMap(fullPath); else - ignerr << "Unable to find file [" << environmentMap << "]\n"; + gzerr << "Unable to find file [" << environmentMap << "]\n"; } // emissive map @@ -888,7 +888,7 @@ rendering::MaterialPtr SceneManager::LoadMaterial( if (!fullPath.empty()) material->SetEmissiveMap(fullPath); else - ignerr << "Unable to find file [" << emissiveMap << "]\n"; + gzerr << "Unable to find file [" << emissiveMap << "]\n"; } // light map @@ -904,7 +904,7 @@ rendering::MaterialPtr SceneManager::LoadMaterial( } else { - ignerr << "Unable to find file [" << lightMap << "]\n"; + gzerr << "Unable to find file [" << lightMap << "]\n"; } } } @@ -924,7 +924,7 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, if (this->dataPtr->visuals.find(_id) != this->dataPtr->visuals.end()) { - ignerr << "Entity with Id: [" << _id << "] already exists in the scene" + gzerr << "Entity with Id: [" << _id << "] already exists in the scene" << std::endl; return rendering::VisualPtr(); } @@ -935,7 +935,7 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, auto it = this->dataPtr->visuals.find(_parentId); if (it == this->dataPtr->visuals.end()) { - ignerr << "Parent entity with Id: [" << _parentId << "] not found. " + gzerr << "Parent entity with Id: [" << _parentId << "] not found. " << "Not adding actor with ID [" << _id << "] and name [" << _name << "] to the rendering scene." << std::endl; @@ -954,7 +954,7 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, descriptor.mesh = meshManager->Load(descriptor.meshName); if (nullptr == descriptor.mesh) { - ignerr << "Actor skin mesh [" << descriptor.meshName << "] not found." + gzerr << "Actor skin mesh [" << descriptor.meshName << "] not found." << std::endl; return rendering::VisualPtr(); } @@ -964,7 +964,7 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, common::SkeletonPtr meshSkel = descriptor.mesh->MeshSkeleton(); if (nullptr == meshSkel) { - ignerr << "Mesh skeleton in [" << descriptor.meshName << "] not found." + gzerr << "Mesh skeleton in [" << descriptor.meshName << "] not found." << std::endl; return rendering::VisualPtr(); } @@ -1014,7 +1014,7 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, animMesh = meshManager->Load(animFilename); if (animMesh->MeshSkeleton()->AnimationCount() > 1) { - ignwarn << "File [" << animFilename + gzwarn << "File [" << animFilename << "] has more than one animation, but only the 1st one is used." << std::endl; } @@ -1025,7 +1025,7 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, auto firstAnim = animMesh->MeshSkeleton()->Animation(0); if (nullptr == firstAnim) { - ignerr << "Failed to get animations from [" << animFilename + gzerr << "Failed to get animations from [" << animFilename << "]" << std::endl; return nullptr; } @@ -1086,7 +1086,7 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, const sdf::Trajectory *trajSdf = _actor.TrajectoryByIndex(i); if (nullptr == trajSdf) { - ignerr << "Null trajectory SDF for [" << _actor.Name() << "]" + gzerr << "Null trajectory SDF for [" << _actor.Name() << "]" << std::endl; continue; } @@ -1131,7 +1131,7 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, } else { - ignwarn << "Animation has no x displacement. " + gzwarn << "Animation has no x displacement. " << "Ignoring for the animation in '" << animation->Filename() << "'." << std::endl; } @@ -1192,7 +1192,7 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, descriptor); if (nullptr == actorMesh) { - ignerr << "Actor skin file [" << descriptor.meshName << "] not found." + gzerr << "Actor skin file [" << descriptor.meshName << "] not found." << std::endl; return rendering::VisualPtr(); } @@ -1224,7 +1224,7 @@ rendering::VisualPtr SceneManager::CreateLightVisual(Entity _id, if (this->dataPtr->visuals.find(_id) != this->dataPtr->visuals.end()) { - ignerr << "Entity with Id: [" << _id << "] already exists in the scene" + gzerr << "Entity with Id: [" << _id << "] already exists in the scene" << std::endl; return rendering::VisualPtr(); } @@ -1237,7 +1237,7 @@ rendering::VisualPtr SceneManager::CreateLightVisual(Entity _id, } else { - ignerr << "Parent entity with Id: [" << _parentId << "] not found. " + gzerr << "Parent entity with Id: [" << _parentId << "] not found. " << "Not adding light visual with ID [" << _id << "] and name [" << _name << "] to the rendering scene." << std::endl; @@ -1248,7 +1248,7 @@ rendering::VisualPtr SceneManager::CreateLightVisual(Entity _id, if (this->dataPtr->scene->HasVisualName(name)) { - ignerr << "Visual: [" << name << "] already exists" << std::endl; + gzerr << "Visual: [" << name << "] already exists" << std::endl; return rendering::VisualPtr(); } @@ -1294,7 +1294,7 @@ rendering::LightPtr SceneManager::CreateLight(Entity _id, if (this->dataPtr->lights.find(_id) != this->dataPtr->lights.end()) { - ignerr << "Light with Id: [" << _id << "] already exists in the scene" + gzerr << "Light with Id: [" << _id << "] already exists in the scene" << std::endl; return rendering::LightPtr(); } @@ -1343,7 +1343,7 @@ rendering::LightPtr SceneManager::CreateLight(Entity _id, break; } default: - ignerr << "Light type not supported" << std::endl; + gzerr << "Light type not supported" << std::endl; return light; } @@ -1379,7 +1379,7 @@ rendering::VisualPtr SceneManager::CreateInertiaVisual(Entity _id, if (this->dataPtr->visuals.find(_id) != this->dataPtr->visuals.end()) { - ignerr << "Entity with Id: [" << _id << "] already exists in the scene" + gzerr << "Entity with Id: [" << _id << "] already exists in the scene" << std::endl; return rendering::VisualPtr(); } @@ -1432,7 +1432,7 @@ rendering::VisualPtr SceneManager::CreateJointVisual( if (this->dataPtr->visuals.find(_id) != this->dataPtr->visuals.end()) { - ignerr << "Entity with Id: [" << _id << "] already exists in the scene" + gzerr << "Entity with Id: [" << _id << "] already exists in the scene" << std::endl; return rendering::VisualPtr(); } @@ -1533,7 +1533,7 @@ rendering::VisualPtr SceneManager::CreateJointVisual( // For fixed joint type, scale joint visual to the joint child link double childSize = std::max(0.1, parent->BoundingBox().Size().Length()); - auto scale = ignition::math::Vector3d(childSize * 0.2, + auto scale = gz::math::Vector3d(childSize * 0.2, childSize * 0.2, childSize * 0.2); jointVisual->SetLocalScale(scale); } @@ -1557,7 +1557,7 @@ rendering::VisualPtr SceneManager::CreateCOMVisual(Entity _id, if (this->dataPtr->visuals.find(_id) != this->dataPtr->visuals.end()) { - ignerr << "Entity with Id: [" << _id << "] already exists in the scene" + gzerr << "Entity with Id: [" << _id << "] already exists in the scene" << std::endl; return rendering::VisualPtr(); } @@ -1607,7 +1607,7 @@ rendering::ParticleEmitterPtr SceneManager::CreateParticleEmitter( if (this->dataPtr->particleEmitters.find(_id) != this->dataPtr->particleEmitters.end()) { - ignerr << "Particle emitter with Id: [" << _id << "] already exists in the " + gzerr << "Particle emitter with Id: [" << _id << "] already exists in the " <<" scene" << std::endl; return rendering::ParticleEmitterPtr(); } @@ -1655,7 +1655,7 @@ rendering::ParticleEmitterPtr SceneManager::UpdateParticleEmitter(Entity _id, auto emitterIt = this->dataPtr->particleEmitters.find(_id); if (emitterIt == this->dataPtr->particleEmitters.end()) { - ignerr << "Particle emitter with Id: [" << _id << "] not found in the " + gzerr << "Particle emitter with Id: [" << _id << "] not found in the " << "scene" << std::endl; return rendering::ParticleEmitterPtr(); } @@ -1664,19 +1664,19 @@ rendering::ParticleEmitterPtr SceneManager::UpdateParticleEmitter(Entity _id, // Type. switch (_emitter.type()) { - case ignition::msgs::ParticleEmitter_EmitterType_BOX: + case gz::msgs::ParticleEmitter_EmitterType_BOX: { - emitter->SetType(ignition::rendering::EmitterType::EM_BOX); + emitter->SetType(gz::rendering::EmitterType::EM_BOX); break; } - case ignition::msgs::ParticleEmitter_EmitterType_CYLINDER: + case gz::msgs::ParticleEmitter_EmitterType_CYLINDER: { - emitter->SetType(ignition::rendering::EmitterType::EM_CYLINDER); + emitter->SetType(gz::rendering::EmitterType::EM_CYLINDER); break; } - case ignition::msgs::ParticleEmitter_EmitterType_ELLIPSOID: + case gz::msgs::ParticleEmitter_EmitterType_ELLIPSOID: { - emitter->SetType(ignition::rendering::EmitterType::EM_ELLIPSOID); + emitter->SetType(gz::rendering::EmitterType::EM_ELLIPSOID); break; } default: @@ -1687,7 +1687,7 @@ rendering::ParticleEmitterPtr SceneManager::UpdateParticleEmitter(Entity _id, // Emitter size. if (_emitter.has_size()) - emitter->SetEmitterSize(ignition::msgs::Convert(_emitter.size())); + emitter->SetEmitterSize(gz::msgs::Convert(_emitter.size())); // Rate. if (_emitter.has_rate()) @@ -1706,7 +1706,7 @@ rendering::ParticleEmitterPtr SceneManager::UpdateParticleEmitter(Entity _id, if (_emitter.has_particle_size()) { emitter->SetParticleSize( - ignition::msgs::Convert(_emitter.particle_size())); + gz::msgs::Convert(_emitter.particle_size())); } // Lifetime. @@ -1716,7 +1716,7 @@ rendering::ParticleEmitterPtr SceneManager::UpdateParticleEmitter(Entity _id, // Material. if (_emitter.has_material()) { - ignition::rendering::MaterialPtr material = + gz::rendering::MaterialPtr material = this->LoadMaterial(convert(_emitter.material())); emitter->SetMaterial(material); } @@ -1738,8 +1738,8 @@ rendering::ParticleEmitterPtr SceneManager::UpdateParticleEmitter(Entity _id, else if (_emitter.has_color_start() && _emitter.has_color_end()) { emitter->SetColorRange( - ignition::msgs::Convert(_emitter.color_start()), - ignition::msgs::Convert(_emitter.color_end())); + gz::msgs::Convert(_emitter.color_start()), + gz::msgs::Convert(_emitter.color_end())); } // Scale rate. @@ -1777,7 +1777,7 @@ bool SceneManager::AddSensor(Entity _gazeboId, const std::string &_sensorName, if (this->dataPtr->sensors.find(_gazeboId) != this->dataPtr->sensors.end()) { - ignerr << "Sensor for entity [" << _gazeboId + gzerr << "Sensor for entity [" << _gazeboId << "] already exists in the scene" << std::endl; return false; } @@ -1798,7 +1798,7 @@ bool SceneManager::AddSensor(Entity _gazeboId, const std::string &_sensorName, rendering::SensorPtr sensor = this->dataPtr->scene->SensorByName(_sensorName); if (!sensor) { - ignerr << "Unable to find sensor [" << _sensorName << "]" << std::endl; + gzerr << "Unable to find sensor [" << _sensorName << "]" << std::endl; return false; } diff --git a/src/systems/CMakeLists.txt b/src/systems/CMakeLists.txt index 043ffea86e..3fc7508371 100644 --- a/src/systems/CMakeLists.txt +++ b/src/systems/CMakeLists.txt @@ -5,7 +5,7 @@ # [PRIVATE_LINK_LIBS ] # [PRIVATE_COMPILE_DEFS ]) # -# Add a system component to Ignition Gazebo. +# Add a system component to Gazebo. # # Required. Name of the system. # @@ -73,7 +73,7 @@ function(gz_add_system system_name) endif() # Note that plugins are currently being installed in 2 places. /lib and the plugin dir - install(TARGETS ${system_target} DESTINATION ${IGNITION_GAZEBO_PLUGIN_INSTALL_DIR}) + install(TARGETS ${system_target} DESTINATION ${GZ_SIM_PLUGIN_INSTALL_DIR}) # The library created by `ign_add_component` includes the ign-gazebo version # (i.e. libignition-gazebo1-name-system.so), but for portability of SDF @@ -89,7 +89,7 @@ function(gz_add_system system_name) else() file(MAKE_DIRECTORY "${PROJECT_BINARY_DIR}/lib") EXECUTE_PROCESS(COMMAND ${CMAKE_COMMAND} -E create_symlink ${versioned} ${unversioned} WORKING_DIRECTORY "${PROJECT_BINARY_DIR}/lib") - INSTALL(FILES ${PROJECT_BINARY_DIR}/lib/${unversioned} DESTINATION ${IGNITION_GAZEBO_PLUGIN_INSTALL_DIR}) + INSTALL(FILES ${PROJECT_BINARY_DIR}/lib/${unversioned} DESTINATION ${GZ_SIM_PLUGIN_INSTALL_DIR}) endif() endfunction() diff --git a/src/systems/ackermann_steering/AckermannSteering.cc b/src/systems/ackermann_steering/AckermannSteering.cc index 189846cc05..da90254814 100644 --- a/src/systems/ackermann_steering/AckermannSteering.cc +++ b/src/systems/ackermann_steering/AckermannSteering.cc @@ -38,8 +38,8 @@ #include "gz/sim/Model.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; /// \brief Velocity command. @@ -54,25 +54,25 @@ 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 - public: void OnCmdVel(const ignition::msgs::Twist &_msg); + public: void OnCmdVel(const gz::msgs::Twist &_msg); /// \brief Update odometry and publish an odometry message. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateOdometry(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm); /// \brief Update the linear and angular velocities. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateVelocity(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateVelocity(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm); /// \brief Ignition communication node. public: transport::Node node; @@ -162,10 +162,10 @@ class ignition::gazebo::systems::AckermannSteeringPrivate public: std::chrono::steady_clock::duration lastOdomTime{0}; /// \brief Linear velocity limiter. - public: std::unique_ptr limiterLin; + public: std::unique_ptr limiterLin; /// \brief Angular velocity limiter. - public: std::unique_ptr limiterAng; + public: std::unique_ptr limiterAng; /// \brief Previous control command. public: Commands last0Cmd; @@ -202,7 +202,7 @@ void AckermannSteering::Configure(const Entity &_entity, if (!this->dataPtr->model.Valid(_ecm)) { - ignerr << "AckermannSteering plugin should be attached to a model entity. " + gzerr << "AckermannSteering plugin should be attached to a model entity. " << "Failed to initialize." << std::endl; return; } @@ -257,8 +257,8 @@ void AckermannSteering::Configure(const Entity &_entity, this->dataPtr->wheelRadius).first; // Instantiate the speed limiters. - this->dataPtr->limiterLin = std::make_unique(); - this->dataPtr->limiterAng = std::make_unique(); + this->dataPtr->limiterLin = std::make_unique(); + this->dataPtr->limiterAng = std::make_unique(); // Parse speed limiter parameters. if (_sdf->HasElement("min_velocity")) @@ -317,7 +317,7 @@ void AckermannSteering::Configure(const Entity &_entity, auto topic = validTopic(topics); if (topic.empty()) { - ignerr << "AckermannSteering plugin received invalid model name " + gzerr << "AckermannSteering plugin received invalid model name " << "Failed to initialize." << std::endl; return; } @@ -335,7 +335,7 @@ void AckermannSteering::Configure(const Entity &_entity, auto odomTopic = validTopic(odomTopics); if (topic.empty()) { - ignerr << "AckermannSteering plugin received invalid model name " + gzerr << "AckermannSteering plugin received invalid model name " << "Failed to initialize." << std::endl; return; } @@ -349,20 +349,20 @@ void AckermannSteering::Configure(const Entity &_entity, if (_sdf->HasElement("child_frame_id")) this->dataPtr->sdfChildFrameId = _sdf->Get("child_frame_id"); - ignmsg << "AckermannSteering subscribing to twist messages on [" << + gzmsg << "AckermannSteering subscribing to twist messages on [" << topic << "]" << std::endl; } ////////////////////////////////////////////////// -void AckermannSteering::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void AckermannSteering::PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("AckermannSteering::PreUpdate"); // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -383,7 +383,7 @@ void AckermannSteering::PreUpdate(const ignition::gazebo::UpdateInfo &_info, this->dataPtr->leftJoints.push_back(joint); else if (warnedModels.find(modelName) == warnedModels.end()) { - ignwarn << "Failed to find left joint [" << name << "] for model [" + gzwarn << "Failed to find left joint [" << name << "] for model [" << modelName << "]" << std::endl; warned = true; } @@ -396,7 +396,7 @@ void AckermannSteering::PreUpdate(const ignition::gazebo::UpdateInfo &_info, this->dataPtr->rightJoints.push_back(joint); else if (warnedModels.find(modelName) == warnedModels.end()) { - ignwarn << "Failed to find right joint [" << name << "] for model [" + gzwarn << "Failed to find right joint [" << name << "] for model [" << modelName << "]" << std::endl; warned = true; } @@ -408,7 +408,7 @@ void AckermannSteering::PreUpdate(const ignition::gazebo::UpdateInfo &_info, this->dataPtr->leftSteeringJoints.push_back(joint); else if (warnedModels.find(modelName) == warnedModels.end()) { - ignwarn << "Failed to find left steering joint [" + gzwarn << "Failed to find left steering joint [" << name << "] for model [" << modelName << "]" << std::endl; warned = true; @@ -422,7 +422,7 @@ void AckermannSteering::PreUpdate(const ignition::gazebo::UpdateInfo &_info, this->dataPtr->rightSteeringJoints.push_back(joint); else if (warnedModels.find(modelName) == warnedModels.end()) { - ignwarn << "Failed to find right steering joint [" << + gzwarn << "Failed to find right steering joint [" << name << "] for model [" << modelName << "]" << std::endl; warned = true; } @@ -440,7 +440,7 @@ void AckermannSteering::PreUpdate(const ignition::gazebo::UpdateInfo &_info, if (warnedModels.find(modelName) != warnedModels.end()) { - ignmsg << "Found joints for model [" << modelName + gzmsg << "Found joints for model [" << modelName << "], plugin will start working." << std::endl; warnedModels.erase(modelName); } @@ -566,8 +566,8 @@ void AckermannSteering::PostUpdate(const UpdateInfo &_info, ////////////////////////////////////////////////// void AckermannSteeringPrivate::UpdateOdometry( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("AckermannSteering::UpdateOdometry"); // Initialize, if not already initialized. @@ -673,8 +673,8 @@ void AckermannSteeringPrivate::UpdateOdometry( ////////////////////////////////////////////////// void AckermannSteeringPrivate::UpdateVelocity( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("AckermannSteering::UpdateVelocity"); @@ -759,10 +759,14 @@ void AckermannSteeringPrivate::OnCmdVel(const msgs::Twist &_msg) } IGNITION_ADD_PLUGIN(AckermannSteering, - ignition::gazebo::System, + gz::sim::System, AckermannSteering::ISystemConfigure, 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 3cf34460fc..dc856758df 100644 --- a/src/systems/ackermann_steering/AckermannSteering.hh +++ b/src/systems/ackermann_steering/AckermannSteering.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_ACKERMANNSTEERING_HH_ -#define IGNITION_GAZEBO_SYSTEMS_ACKERMANNSTEERING_HH_ +#ifndef GZ_SIM_SYSTEMS_ACKERMANNSTEERING_HH_ +#define GZ_SIM_SYSTEMS_ACKERMANNSTEERING_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declaration @@ -95,7 +95,7 @@ namespace systems /// right_steering_joint /// /// References: - /// https://github.com/ignitionrobotics/ign-gazebo/tree/main/src/systems/diff_drive + /// https://github.com/gazebosim/gz-sim/tree/main/src/systems/diff_drive /// https://www.auto.tuwien.ac.at/bib/pdf_TR/TR0183.pdf /// https://github.com/froohoo/ackermansteer/blob/master/ackermansteer/ @@ -120,8 +120,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/ackermann_steering/SpeedLimiter.hh b/src/systems/ackermann_steering/SpeedLimiter.hh index add505f5d0..459b3196a6 100644 --- a/src/systems/ackermann_steering/SpeedLimiter.hh +++ b/src/systems/ackermann_steering/SpeedLimiter.hh @@ -37,19 +37,19 @@ * Modified: Carlos Agüero */ -#ifndef IGNITION_GAZEBO_SYSTEMS_SPEEDLIMITER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_SPEEDLIMITER_HH_ +#ifndef GZ_SIM_SYSTEMS_SPEEDLIMITER_HH_ +#define GZ_SIM_SYSTEMS_SPEEDLIMITER_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declaration. diff --git a/src/systems/air_pressure/AirPressure.cc b/src/systems/air_pressure/AirPressure.cc index 90a02461ec..8f03d849e8 100644 --- a/src/systems/air_pressure/AirPressure.cc +++ b/src/systems/air_pressure/AirPressure.cc @@ -43,12 +43,12 @@ #include "gz/sim/EntityComponentManager.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace 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_mapdataPtr->entitySensorMap.find(entity); if (it == this->dataPtr->entitySensorMap.end()) { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] isn't in sensor map, this shouldn't happen." << std::endl; continue; } @@ -131,7 +131,7 @@ void AirPressure::PostUpdate(const UpdateInfo &_info, // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -175,7 +175,7 @@ void AirPressurePrivate::AddAirPressure( sensors::AirPressureSensor>(data); if (nullptr == sensor) { - ignerr << "Failed to create sensor [" << sensorScopedName << "]" + gzerr << "Failed to create sensor [" << sensorScopedName << "]" << std::endl; return; } @@ -244,7 +244,7 @@ void AirPressurePrivate::UpdateAirPressures(const EntityComponentManager &_ecm) } else { - ignerr << "Failed to update air pressure: " << _entity << ". " + gzerr << "Failed to update air pressure: " << _entity << ". " << "Entity not found." << std::endl; } @@ -264,7 +264,7 @@ void AirPressurePrivate::RemoveAirPressureEntities( auto sensorId = this->entitySensorMap.find(_entity); if (sensorId == this->entitySensorMap.end()) { - ignerr << "Internal error, missing air pressure sensor for entity [" + gzerr << "Internal error, missing air pressure sensor for entity [" << _entity << "]" << std::endl; return true; } @@ -280,4 +280,7 @@ IGNITION_ADD_PLUGIN(AirPressure, System, AirPressure::ISystemPostUpdate ) +IGNITION_ADD_PLUGIN_ALIAS(AirPressure, "gz::sim::systems::AirPressure") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(AirPressure, "ignition::gazebo::systems::AirPressure") diff --git a/src/systems/air_pressure/AirPressure.hh b/src/systems/air_pressure/AirPressure.hh index 237244492c..4428d4d56d 100644 --- a/src/systems/air_pressure/AirPressure.hh +++ b/src/systems/air_pressure/AirPressure.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_AIRPRESSURE_HH_ -#define IGNITION_GAZEBO_SYSTEMS_AIRPRESSURE_HH_ +#ifndef GZ_SIM_SYSTEMS_AIRPRESSURE_HH_ +#define GZ_SIM_SYSTEMS_AIRPRESSURE_HH_ #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declarations. diff --git a/src/systems/altimeter/Altimeter.cc b/src/systems/altimeter/Altimeter.cc index 6bb6ee3455..f70bce2deb 100644 --- a/src/systems/altimeter/Altimeter.cc +++ b/src/systems/altimeter/Altimeter.cc @@ -45,12 +45,12 @@ #include "gz/sim/EntityComponentManager.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace 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_mapdataPtr->entitySensorMap.find(entity); if (it == this->dataPtr->entitySensorMap.end()) { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] isn't in sensor map, this shouldn't happen." << std::endl; continue; } @@ -131,7 +131,7 @@ void Altimeter::PostUpdate(const UpdateInfo &_info, // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -176,7 +176,7 @@ void AltimeterPrivate::AddAltimeter( sensors::AltimeterSensor>(data); if (nullptr == sensor) { - ignerr << "Failed to create sensor [" << sensorScopedName << "]" + gzerr << "Failed to create sensor [" << sensorScopedName << "]" << std::endl; return; } @@ -250,7 +250,7 @@ void AltimeterPrivate::UpdateAltimeters(const EntityComponentManager &_ecm) } else { - ignerr << "Failed to update altimeter: " << _entity << ". " + gzerr << "Failed to update altimeter: " << _entity << ". " << "Entity not found." << std::endl; } @@ -270,7 +270,7 @@ void AltimeterPrivate::RemoveAltimeterEntities( auto sensorId = this->entitySensorMap.find(_entity); if (sensorId == this->entitySensorMap.end()) { - ignerr << "Internal error, missing altimeter sensor for entity [" + gzerr << "Internal error, missing altimeter sensor for entity [" << _entity << "]" << std::endl; return true; } @@ -286,4 +286,7 @@ IGNITION_ADD_PLUGIN(Altimeter, System, Altimeter::ISystemPostUpdate ) +IGNITION_ADD_PLUGIN_ALIAS(Altimeter, "gz::sim::systems::Altimeter") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(Altimeter, "ignition::gazebo::systems::Altimeter") diff --git a/src/systems/altimeter/Altimeter.hh b/src/systems/altimeter/Altimeter.hh index cef06a13eb..b4a07ef7a3 100644 --- a/src/systems/altimeter/Altimeter.hh +++ b/src/systems/altimeter/Altimeter.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_ALTIMETER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_ALTIMETER_HH_ +#ifndef GZ_SIM_SYSTEMS_ALTIMETER_HH_ +#define GZ_SIM_SYSTEMS_ALTIMETER_HH_ #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declarations. diff --git a/src/systems/apply_joint_force/ApplyJointForce.cc b/src/systems/apply_joint_force/ApplyJointForce.cc index 80b9a48304..39beee45b6 100644 --- a/src/systems/apply_joint_force/ApplyJointForce.cc +++ b/src/systems/apply_joint_force/ApplyJointForce.cc @@ -27,15 +27,15 @@ #include "gz/sim/Model.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace 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 - public: void OnCmdForce(const ignition::msgs::Double &_msg); + public: void OnCmdForce(const gz::msgs::Double &_msg); /// \brief Ignition communication node. public: transport::Node node; @@ -72,7 +72,7 @@ void ApplyJointForce::Configure(const Entity &_entity, if (!this->dataPtr->model.Valid(_ecm)) { - ignerr << "ApplyJointForce plugin should be attached to a model entity. " + gzerr << "ApplyJointForce plugin should be attached to a model entity. " << "Failed to initialize." << std::endl; return; } @@ -88,7 +88,7 @@ void ApplyJointForce::Configure(const Entity &_entity, if (this->dataPtr->jointName == "") { - ignerr << "ApplyJointForce found an empty jointName parameter. " + gzerr << "ApplyJointForce found an empty jointName parameter. " << "Failed to initialize."; return; } @@ -99,27 +99,27 @@ void ApplyJointForce::Configure(const Entity &_entity, "/cmd_force"); if (topic.empty()) { - ignerr << "Failed to create valid topic for [" << this->dataPtr->jointName + gzerr << "Failed to create valid topic for [" << this->dataPtr->jointName << "]" << std::endl; return; } this->dataPtr->node.Subscribe(topic, &ApplyJointForcePrivate::OnCmdForce, this->dataPtr.get()); - ignmsg << "ApplyJointForce subscribing to Double messages on [" << topic + gzmsg << "ApplyJointForce subscribing to Double messages on [" << topic << "]" << std::endl; } ////////////////////////////////////////////////// -void ApplyJointForce::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void ApplyJointForce::PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("ApplyJointForce::PreUpdate"); // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -164,9 +164,13 @@ void ApplyJointForcePrivate::OnCmdForce(const msgs::Double &_msg) } IGNITION_ADD_PLUGIN(ApplyJointForce, - ignition::gazebo::System, + gz::sim::System, 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 42b69da9bf..0c93a28c20 100644 --- a/src/systems/apply_joint_force/ApplyJointForce.hh +++ b/src/systems/apply_joint_force/ApplyJointForce.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_APPLYJOINTFORCE_HH_ -#define IGNITION_GAZEBO_SYSTEMS_APPLYJOINTFORCE_HH_ +#ifndef GZ_SIM_SYSTEMS_APPLYJOINTFORCE_HH_ +#define GZ_SIM_SYSTEMS_APPLYJOINTFORCE_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declaration @@ -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/battery_plugin/LinearBatteryPlugin.cc b/src/systems/battery_plugin/LinearBatteryPlugin.cc index a451879121..dba602d190 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.cc +++ b/src/systems/battery_plugin/LinearBatteryPlugin.cc @@ -48,11 +48,11 @@ #include "gz/sim/components/World.hh" #include "gz/sim/Model.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; -class ignition::gazebo::systems::LinearBatteryPluginPrivate +class gz::sim::systems::LinearBatteryPluginPrivate { /// \brief Reset the plugin public: void Reset(); @@ -63,11 +63,11 @@ class ignition::gazebo::systems::LinearBatteryPluginPrivate /// \brief Callback executed to start recharging. /// \param[in] _req This value should be true. - public: void OnEnableRecharge(const ignition::msgs::Boolean &_req); + public: void OnEnableRecharge(const gz::msgs::Boolean &_req); /// \brief Callback executed to stop recharging. /// \param[in] _req This value should be true. - public: void OnDisableRecharge(const ignition::msgs::Boolean &_req); + public: void OnDisableRecharge(const gz::msgs::Boolean &_req); /// \brief Callback connected to additional topics that can start battery /// draining. @@ -76,7 +76,7 @@ class ignition::gazebo::systems::LinearBatteryPluginPrivate /// \param[in] _info Information about the message. public: void OnBatteryDrainingMsg( const char *_data, const size_t _size, - const ignition::transport::MessageInfo &_info); + const gz::transport::MessageInfo &_info); /// \brief Name of model, only used for printing warning when battery drains. public: std::string modelName; @@ -129,15 +129,15 @@ class ignition::gazebo::systems::LinearBatteryPluginPrivate /// \brief Hours taken to fully charge battery public: double tCharge{0.0}; - /// \TODO(caguero) Remove this flag in Ignition Dome. + /// \TODO(caguero) Remove this flag in Gazebo Dome. /// \brief Flag to enable some battery fixes. public: bool fixIssue225{false}; - /// \TODO(caguero) Remove in Ignition Dome. + /// \TODO(caguero) Remove in Gazebo Dome. /// \brief Battery current for a historic time window public: std::deque iList; - /// \TODO(caguero) Remove in Ignition Dome. + /// \TODO(caguero) Remove in Gazebo Dome. /// \brief Time interval for a historic time window public: std::deque dtList; @@ -203,7 +203,7 @@ void LinearBatteryPlugin::Configure(const Entity &_entity, auto model = Model(_entity); if (!model.Valid(_ecm)) { - ignerr << "Linear battery plugin should be attached to a model entity. " + gzerr << "Linear battery plugin should be attached to a model entity. " << "Failed to initialize." << std::endl; return; } @@ -221,7 +221,7 @@ void LinearBatteryPlugin::Configure(const Entity &_entity, if (this->dataPtr->c <= 0) { - ignerr << "No or incorrect value specified. Capacity should be " + gzerr << "No or incorrect value specified. Capacity should be " << "greater than 0.\n"; return; } @@ -232,11 +232,11 @@ void LinearBatteryPlugin::Configure(const Entity &_entity, this->dataPtr->q0 = _sdf->Get("initial_charge"); if (this->dataPtr->q0 > this->dataPtr->c || this->dataPtr->q0 < 0) { - ignerr << " value should be between [0, ]." + gzerr << " value should be between [0, ]." << std::endl; this->dataPtr->q0 = std::max(0.0, std::min(this->dataPtr->q0, this->dataPtr->c)); - ignerr << "Setting to [" << this->dataPtr->q0 + gzerr << "Setting to [" << this->dataPtr->q0 << "] instead." << std::endl; } } @@ -251,7 +251,7 @@ void LinearBatteryPlugin::Configure(const Entity &_entity, this->dataPtr->tau = _sdf->Get("smooth_current_tau"); if (this->dataPtr->tau <= 0) { - ignerr << " value should be positive. " + gzerr << " value should be positive. " << "Using [1] instead." << std::endl; this->dataPtr->tau = 1; } @@ -284,7 +284,7 @@ void LinearBatteryPlugin::Configure(const Entity &_entity, } else { - ignerr << "No or specified. Both are required.\n"; + gzerr << "No or specified. Both are required.\n"; return; } @@ -297,7 +297,7 @@ void LinearBatteryPlugin::Configure(const Entity &_entity, this->dataPtr->tCharge = _sdf->Get("charging_time"); else { - ignerr << "No specified. " + gzerr << "No specified. " "Parameter required to enable recharge.\n"; return; } @@ -315,7 +315,7 @@ void LinearBatteryPlugin::Configure(const Entity &_entity, disableRechargeTopic); if (validEnableRechargeTopic.empty() || validDisableRechargeTopic.empty()) { - ignerr << "Failed to create valid topics. Not valid: [" + gzerr << "Failed to create valid topics. Not valid: [" << enableRechargeTopic << "] and [" << disableRechargeTopic << "]" << std::endl; return; @@ -344,11 +344,11 @@ void LinearBatteryPlugin::Configure(const Entity &_entity, bool success = this->dataPtr->battery->SetPowerLoad( this->dataPtr->consumerId, powerLoad); if (!success) - ignerr << "Failed to set consumer power load." << std::endl; + gzerr << "Failed to set consumer power load." << std::endl; } else { - ignwarn << "Required attribute power_load missing " + gzwarn << "Required attribute power_load missing " << "in LinearBatteryPlugin SDF" << std::endl; } @@ -363,15 +363,15 @@ void LinearBatteryPlugin::Configure(const Entity &_entity, std::bind(&LinearBatteryPluginPrivate::OnBatteryDrainingMsg, this->dataPtr.get(), std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); - ignmsg << "LinearBatteryPlugin subscribes to power draining topic [" + gzmsg << "LinearBatteryPlugin subscribes to power draining topic [" << topic << "]." << std::endl; sdfElem = sdfElem->GetNextElement("power_draining_topic"); } } - ignmsg << "LinearBatteryPlugin configured. Battery name: " + gzmsg << "LinearBatteryPlugin configured. Battery name: " << this->dataPtr->battery->Name() << std::endl; - igndbg << "Battery initial voltage: " << this->dataPtr->battery->InitVoltage() + gzdbg << "Battery initial voltage: " << this->dataPtr->battery->InitVoltage() << std::endl; this->dataPtr->soc = this->dataPtr->q / this->dataPtr->c; @@ -383,7 +383,7 @@ void LinearBatteryPlugin::Configure(const Entity &_entity, auto validStateTopic = transport::TopicUtils::AsValidTopic(stateTopic); if (validStateTopic.empty()) { - ignerr << "Failed to create valid state topic [" + gzerr << "Failed to create valid state topic [" << stateTopic << "]" << std::endl; return; } @@ -411,37 +411,37 @@ double LinearBatteryPluginPrivate::StateOfCharge() const ////////////////////////////////////////////////// void LinearBatteryPluginPrivate::OnEnableRecharge( - const ignition::msgs::Boolean &/*_req*/) + const gz::msgs::Boolean &/*_req*/) { - igndbg << "Request for start charging received" << std::endl; + gzdbg << "Request for start charging received" << std::endl; this->startCharging = true; } ////////////////////////////////////////////////// void LinearBatteryPluginPrivate::OnDisableRecharge( - const ignition::msgs::Boolean &/*_req*/) + const gz::msgs::Boolean &/*_req*/) { - igndbg << "Request for stop charging received" << std::endl; + gzdbg << "Request for stop charging received" << std::endl; this->startCharging = false; } ////////////////////////////////////////////////// void LinearBatteryPluginPrivate::OnBatteryDrainingMsg( - const char *, const size_t, const ignition::transport::MessageInfo &) + const char *, const size_t, const gz::transport::MessageInfo &) { this->startDrainingFromTopics = true; } ////////////////////////////////////////////////// void LinearBatteryPlugin::PreUpdate( - const ignition::gazebo::UpdateInfo &/*_info*/, - ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::UpdateInfo &/*_info*/, + gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("LinearBatteryPlugin::PreUpdate"); // \todo(anyone) Add in the ability to stop the battery from draining // after it has been started by a topic. See this comment: - // https://github.com/ignitionrobotics/ign-gazebo/pull/1255#discussion_r770223092 + // https://github.com/gazebosim/gz-sim/pull/1255#discussion_r770223092 this->dataPtr->startDraining = this->dataPtr->startDrainingFromTopics; // Start draining the battery if the robot has started moving if (!this->dataPtr->startDraining) @@ -492,7 +492,7 @@ void LinearBatteryPlugin::Update(const UpdateInfo &_info, // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -514,7 +514,7 @@ void LinearBatteryPlugin::Update(const UpdateInfo &_info, if (drainTime != this->dataPtr->lastPrintTime) { this->dataPtr->lastPrintTime = drainTime; - igndbg << "[Battery Plugin] Battery drain: " << drainTime << + gzdbg << "[Battery Plugin] Battery drain: " << drainTime << " minutes passed.\n"; } @@ -526,7 +526,7 @@ void LinearBatteryPlugin::Update(const UpdateInfo &_info, this->dataPtr->stepSize).count()) * 1e-9; if (this->dataPtr->tau < dt) { - ignerr << " should be in the range [dt, +inf) but is " + gzerr << " should be in the range [dt, +inf) but is " << "configured with [" << this->dataPtr->tau << "]. We'll be using " << "[" << dt << "] instead" << std::endl; this->dataPtr->tau = dt; @@ -650,19 +650,19 @@ double LinearBatteryPlugin::OnUpdateVoltage( auto socInt = static_cast(this->dataPtr->StateOfCharge() * 100); if (socInt % 10 == 0 && socInt != prevSocInt) { - igndbg << "Battery: " << this->dataPtr->battery->Name() << std::endl; - igndbg << "PowerLoads().size(): " << _battery->PowerLoads().size() + gzdbg << "Battery: " << this->dataPtr->battery->Name() << std::endl; + gzdbg << "PowerLoads().size(): " << _battery->PowerLoads().size() << std::endl; - igndbg << "charging status: " << std::boolalpha + gzdbg << "charging status: " << std::boolalpha << this->dataPtr->startCharging << std::endl; - igndbg << "charging current: " << iCharge << std::endl; - igndbg << "voltage: " << voltage << std::endl; - igndbg << "state of charge: " << this->dataPtr->StateOfCharge() + gzdbg << "charging current: " << iCharge << std::endl; + gzdbg << "voltage: " << voltage << std::endl; + gzdbg << "state of charge: " << this->dataPtr->StateOfCharge() << " (q " << this->dataPtr->q << ")" << std::endl << std::endl; } if (this->dataPtr->StateOfCharge() < 0 && !this->dataPtr->drainPrinted) { - ignwarn << "Model " << this->dataPtr->modelName << " out of battery.\n"; + gzwarn << "Model " << this->dataPtr->modelName << " out of battery.\n"; this->dataPtr->drainPrinted = true; } @@ -670,11 +670,15 @@ double LinearBatteryPlugin::OnUpdateVoltage( } IGNITION_ADD_PLUGIN(LinearBatteryPlugin, - ignition::gazebo::System, + gz::sim::System, LinearBatteryPlugin::ISystemConfigure, LinearBatteryPlugin::ISystemPreUpdate, 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 44ecb3f13f..a6a3d2ed5c 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.hh +++ b/src/systems/battery_plugin/LinearBatteryPlugin.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_LINEAR_BATTERY_PLUGIN_HH_ -#define IGNITION_GAZEBO_SYSTEMS_LINEAR_BATTERY_PLUGIN_HH_ +#ifndef GZ_SIM_SYSTEMS_LINEAR_BATTERY_PLUGIN_HH_ +#define GZ_SIM_SYSTEMS_LINEAR_BATTERY_PLUGIN_HH_ #include #include @@ -26,12 +26,12 @@ #include "gz/sim/System.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declaration @@ -57,7 +57,7 @@ namespace systems /// - `` Hours taken to fully charge the battery. /// (Required if `` is set to true) /// - `` True to change the battery behavior to fix some issues - /// described in https://github.com/ignitionrobotics/ign-gazebo/issues/225. + /// described in https://github.com/gazebosim/gz-sim/issues/225. /// - `` A topic that is used to start battery /// discharge. Any message on the specified topic will cause the batter to /// start draining. This element can be specified multiple times if @@ -84,8 +84,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 f5bb3b2c5f..3e34d5e66d 100644 --- a/src/systems/breadcrumbs/Breadcrumbs.cc +++ b/src/systems/breadcrumbs/Breadcrumbs.cc @@ -44,8 +44,8 @@ #include "gz/sim/components/World.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; ////////////////////////////////////////////////// @@ -60,7 +60,7 @@ void Breadcrumbs::Configure(const Entity &_entity, // Exit early if breadcrumbs deployments are set to zero. if (this->maxDeployments == 0) { - ignmsg << "Breadcrumbs max deployment is == 0. Breadcrumbs are disabled." + gzmsg << "Breadcrumbs max deployment is == 0. Breadcrumbs are disabled." << std::endl; return; } @@ -77,14 +77,14 @@ void Breadcrumbs::Configure(const Entity &_entity, this->model = Model(_entity); if (!this->model.Valid(_ecm)) { - ignerr << "The Breadcrumbs system should be attached to a model entity. " + gzerr << "The Breadcrumbs system should be attached to a model entity. " << "Failed to initialize." << std::endl; return; } if (!_sdf->HasElement("breadcrumb")) { - ignerr << " not set" << std::endl; + gzerr << " not set" << std::endl; return; } @@ -92,7 +92,7 @@ void Breadcrumbs::Configure(const Entity &_entity, if (!breadcrumb->HasElement("sdf")) { - ignerr << " not found in " << std::endl; + gzerr << " not found in " << std::endl; return; } @@ -105,13 +105,13 @@ void Breadcrumbs::Configure(const Entity &_entity, { for (const auto &e : errors) { - ignerr << e.Message() << std::endl; + gzerr << e.Message() << std::endl; } return; } if (nullptr == this->modelRoot.Model()) { - ignerr << "Model not found in " << std::endl; + gzerr << "Model not found in " << std::endl; return; } @@ -127,7 +127,7 @@ void Breadcrumbs::Configure(const Entity &_entity, } else { - ignerr << "Geometry specified in is invalid\n"; + gzerr << "Geometry specified in is invalid\n"; return; } } @@ -151,7 +151,7 @@ void Breadcrumbs::Configure(const Entity &_entity, { if (!node.EnableStats(this->topic, true)) { - ignerr << "Unable to enable topic statistics on topic[" + gzerr << "Unable to enable topic statistics on topic[" << this->topic << "]." << std::endl; this->topicStatistics = false; } @@ -161,7 +161,7 @@ void Breadcrumbs::Configure(const Entity &_entity, this->remainingPub = this->node.Advertise( this->topic + "/remaining"); - ignmsg << "Breadcrumbs subscribing to deploy messages on [" + gzmsg << "Breadcrumbs subscribing to deploy messages on [" << this->topic << "]" << std::endl; this->creator = std::make_unique(_ecm, _eventMgr); @@ -172,8 +172,8 @@ void Breadcrumbs::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void Breadcrumbs::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void Breadcrumbs::PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("Breadcrumbs::PreUpdate"); @@ -222,7 +222,7 @@ void Breadcrumbs::PreUpdate(const ignition::gazebo::UpdateInfo &_info, { if (!this->allowRenaming) { - ignwarn << "Entity named [" << desiredName + gzwarn << "Entity named [" << desiredName << "] already exists and " << "[allow_renaming] is false. Entity not spawned." << std::endl; @@ -241,7 +241,7 @@ void Breadcrumbs::PreUpdate(const ignition::gazebo::UpdateInfo &_info, modelToSpawn.SetName(desiredName); modelToSpawn.SetRawPose(poseComp->Data() * modelToSpawn.RawPose()); - ignmsg << "Deploying " << modelToSpawn.Name() << " at " + gzmsg << "Deploying " << modelToSpawn.Name() << " at " << modelToSpawn.RawPose() << std::endl; Entity entity = this->creator->CreateEntities(&modelToSpawn); this->creator->SetParent(entity, this->worldEntity); @@ -277,7 +277,7 @@ void Breadcrumbs::PreUpdate(const ignition::gazebo::UpdateInfo &_info, } else { - ignmsg << "Asked to deploy " << this->modelRoot.Model()->Name() + gzmsg << "Asked to deploy " << this->modelRoot.Model()->Name() << " but the maximum number of deployments has reached the " << "limit of " << this->maxDeployments << std::endl; } @@ -330,12 +330,12 @@ void Breadcrumbs::PreUpdate(const ignition::gazebo::UpdateInfo &_info, auto name = _ecm.Component(it->first)->Data(); if (!this->MakeStatic(it->first, _ecm)) { - ignerr << "Failed to make breadcrumb '" << name + gzerr << "Failed to make breadcrumb '" << name << "' static." << std::endl; } else { - ignmsg << "Breadcrumb '" << name << "' is now static." << std::endl; + gzmsg << "Breadcrumb '" << name << "' is now static." << std::endl; } this->autoStaticEntities.erase(it++); } @@ -412,7 +412,7 @@ void Breadcrumbs::OnDeploy(const msgs::Empty &) // Check topic statistics for dropped messages if (this->topicStatistics) { - ignmsg << "Received breadcrumb deployment for " << + gzmsg << "Received breadcrumb deployment for " << this->modelRoot.Model()->Name() << std::endl; std::optional stats = this->node.TopicStats(this->topic); @@ -420,22 +420,25 @@ void Breadcrumbs::OnDeploy(const msgs::Empty &) { if (stats->DroppedMsgCount() > 0) { - ignwarn << "Dropped message count of " << stats->DroppedMsgCount() + gzwarn << "Dropped message count of " << stats->DroppedMsgCount() << " for breadcrumbs on model " << this->modelRoot.Model()->Name() << std::endl; } } else { - ignerr << "Unable to get topic statistics for topic[" + gzerr << "Unable to get topic statistics for topic[" << this->topic << "]." << std::endl; } } } IGNITION_ADD_PLUGIN(Breadcrumbs, - ignition::gazebo::System, + gz::sim::System, Breadcrumbs::ISystemConfigure, Breadcrumbs::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(Breadcrumbs, "gz::sim::systems::Breadcrumbs") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(Breadcrumbs, "ignition::gazebo::systems::Breadcrumbs") diff --git a/src/systems/breadcrumbs/Breadcrumbs.hh b/src/systems/breadcrumbs/Breadcrumbs.hh index 8311692e13..d7276a0764 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_SIM_SYSTEMS_BREADCRUMBS_HH_ +#define GZ_SIM_SYSTEMS_BREADCRUMBS_HH_ #include #include @@ -35,12 +35,12 @@ #include "gz/sim/SdfEntityCreator.hh" #include "gz/sim/System.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { /// \brief A system for creating Breadcrumbs in the form of models that can @@ -61,7 +61,7 @@ namespace systems /// - ``: Custom topic to be used to deploy breadcrumbs. If topic is /// not set, the default topic with the following pattern would be used /// `/model//breadcrumbs//deploy`. The topic - /// type is ignition.msgs.Empty + /// type is gz.msgs.Empty /// - ``: The maximum number of times this breadcrumb can be /// deployed. Once this many are deployed, publishing on the deploy topic /// will have no effect. If a negative number is set, the maximum deployment @@ -101,8 +101,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 08dcedbb85..b8ba7c290c 100644 --- a/src/systems/buoyancy/Buoyancy.cc +++ b/src/systems/buoyancy/Buoyancy.cc @@ -52,11 +52,11 @@ #include "Buoyancy.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; -class ignition::gazebo::systems::BuoyancyPrivate +class gz::sim::systems::BuoyancyPrivate { public: enum BuoyancyType { @@ -265,7 +265,7 @@ void Buoyancy::Configure(const Entity &_entity, this->dataPtr->world); if (!gravity) { - ignerr << "Unable to get the gravity vector. Make sure this plugin is " + gzerr << "Unable to get the gravity vector. Make sure this plugin is " << "attached to a , not a ." << std::endl; return; } @@ -282,7 +282,7 @@ void Buoyancy::Configure(const Entity &_entity, auto gradedElement = _sdf->GetFirstElement(); if (gradedElement == nullptr) { - ignerr << "Unable to get element description" << std::endl; + gzerr << "Unable to get element description" << std::endl; return; } @@ -292,7 +292,7 @@ void Buoyancy::Configure(const Entity &_entity, if (argument->GetName() == "default_density") { argument->GetValue()->Get(this->dataPtr->fluidDensity); - igndbg << "Default density set to " + gzdbg << "Default density set to " << this->dataPtr->fluidDensity << std::endl; } if (argument->GetName() == "density_change") @@ -301,16 +301,16 @@ void Buoyancy::Configure(const Entity &_entity, auto density = argument->Get("density", 0.0); if (!depth.second) { - ignwarn << "No tag was found as a " + gzwarn << "No tag was found as a " << "child of " << std::endl; } if (!density.second) { - ignwarn << "No tag was found as a " + gzwarn << "No tag was found as a " << "child of " << std::endl; } this->dataPtr->layers[depth.first] = density.first; - igndbg << "Added layer at " << depth.first << ", " + gzdbg << "Added layer at " << depth.first << ", " << density.first << std::endl; } argument = argument->GetNextElement(); @@ -318,7 +318,7 @@ void Buoyancy::Configure(const Entity &_entity, } else { - ignwarn << + gzwarn << "Neither nor specified" << std::endl << "\tDefaulting to 1000" @@ -337,15 +337,15 @@ void Buoyancy::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void Buoyancy::PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("Buoyancy::PreUpdate"); const components::Gravity *gravity = _ecm.Component( this->dataPtr->world); if (!gravity) { - ignerr << "Unable to get the gravity vector. Has gravity been defined?" + gzerr << "Unable to get the gravity vector. Has gravity been defined?" << std::endl; return; } @@ -376,8 +376,8 @@ void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info, _entity, components::Collision()); double volumeSum = 0; - ignition::math::Vector3d weightedPosInLinkSum = - ignition::math::Vector3d::Zero; + gz::math::Vector3d weightedPosInLinkSum = + gz::math::Vector3d::Zero; // Compute the volume of the link by iterating over all the collision // elements and storing each geometry's volume. @@ -389,7 +389,7 @@ void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info, if (!coll) { - ignerr << "Invalid collision pointer. This shouldn't happen\n"; + gzerr << "Invalid collision pointer. This shouldn't happen\n"; continue; } @@ -420,16 +420,16 @@ void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info, if (mesh) volume = mesh->Volume(); else - ignerr << "Unable to load mesh[" << file << "]\n"; + gzerr << "Unable to load mesh[" << file << "]\n"; } else { - ignerr << "Invalid mesh filename[" << file << "]\n"; + gzerr << "Invalid mesh filename[" << file << "]\n"; } break; } default: - ignerr << "Unsupported collision geometry[" + gzerr << "Unsupported collision geometry[" << static_cast(coll->Data().Geom()->Type()) << "]\n"; break; } @@ -507,7 +507,7 @@ void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info, if (!coll) { - ignerr << "Invalid collision pointer. This shouldn't happen\n"; + gzerr << "Invalid collision pointer. This shouldn't happen\n"; continue; } @@ -530,7 +530,7 @@ void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info, static bool warned{false}; if (!warned) { - ignwarn << "Only and collisions are supported " + gzwarn << "Only and collisions are supported " << "by the graded buoyancy option." << std::endl; warned = true; } @@ -581,9 +581,13 @@ bool Buoyancy::IsEnabled(Entity _entity, } IGNITION_ADD_PLUGIN(Buoyancy, - ignition::gazebo::System, + gz::sim::System, 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 aaad03dac3..2f11b87049 100644 --- a/src/systems/buoyancy/Buoyancy.hh +++ b/src/systems/buoyancy/Buoyancy.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_BUOYANCY_HH_ -#define IGNITION_GAZEBO_SYSTEMS_BUOYANCY_HH_ +#ifndef GZ_SIM_SYSTEMS_BUOYANCY_HH_ +#define GZ_SIM_SYSTEMS_BUOYANCY_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declaration @@ -129,8 +129,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 Check if an entity is enabled or not. /// \param[in] _entity Target entity diff --git a/src/systems/buoyancy_engine/BuoyancyEngine.cc b/src/systems/buoyancy_engine/BuoyancyEngine.cc index d200e22cdd..8b58052b4c 100644 --- a/src/systems/buoyancy_engine/BuoyancyEngine.cc +++ b/src/systems/buoyancy_engine/BuoyancyEngine.cc @@ -32,17 +32,17 @@ #include "BuoyancyEngine.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; -class ignition::gazebo::systems::BuoyancyEnginePrivateData +class gz::sim::systems::BuoyancyEnginePrivateData { /// \brief Callback for incoming commands /// \param[in] _volumeSetPoint - ignition message containing the desired /// volume (in m^3) to fill/drain bladder to. public: void OnCmdBuoyancyEngine( - const ignition::msgs::Double &_volumeSetPoint); + const gz::msgs::Double &_volumeSetPoint); /// \brief Current volume of bladder in m^3 public: double bladderVolume = 3e-5; @@ -60,7 +60,7 @@ class ignition::gazebo::systems::BuoyancyEnginePrivateData public: double maxVolume = 0.000990; /// \brief The link which the bladder is attached to - public: ignition::gazebo::Entity linkEntity{kNullEntity}; + public: gz::sim::Entity linkEntity{kNullEntity}; /// \brief The world entity public: Entity world{kNullEntity}; @@ -75,10 +75,10 @@ class ignition::gazebo::systems::BuoyancyEnginePrivateData public: std::optional surface = std::nullopt; /// \brief Trasport node for control - public: ignition::transport::Node node; + public: gz::transport::Node node; /// \brief Publishes bladder status - public: ignition::transport::Node::Publisher statusPub; + public: gz::transport::Node::Publisher statusPub; /// \brief mutex for protecting bladder volume and set point. public: std::mutex mtx; @@ -96,7 +96,7 @@ double BuoyancyEnginePrivateData::CurrentFluidDensity( if (!this->surface.has_value()) return fluidDensity; - auto pose = gazebo::worldPose(this->linkEntity, _ecm); + auto pose = sim::worldPose(this->linkEntity, _ecm); if (pose.Pos().Z() < this->surface.value()) { @@ -107,7 +107,7 @@ double BuoyancyEnginePrivateData::CurrentFluidDensity( ////////////////////////////////////////////////// void BuoyancyEnginePrivateData::OnCmdBuoyancyEngine( - const ignition::msgs::Double &_volumeSetpoint) + const gz::msgs::Double &_volumeSetpoint) { auto volume = std::max(this->minVolume, _volumeSetpoint.data()); volume = std::min(volume, this->maxVolume); @@ -124,15 +124,15 @@ BuoyancyEnginePlugin::BuoyancyEnginePlugin() ////////////////////////////////////////////////// void BuoyancyEnginePlugin::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*/) { - auto model = ignition::gazebo::Model(_entity); + auto model = gz::sim::Model(_entity); if (!_sdf->HasElement("link_name")) { - ignerr << "Buoyancy Engine must be attached to some link." << std::endl; + gzerr << "Buoyancy Engine must be attached to some link." << std::endl; return; } @@ -140,7 +140,7 @@ void BuoyancyEnginePlugin::Configure( model.LinkByName(_ecm, _sdf->Get("link_name")); if (this->dataPtr->linkEntity == kNullEntity) { - ignerr << "Link [" << _sdf->Get("link_name") + gzerr << "Link [" << _sdf->Get("link_name") << "] was not found in model [" << model.Name(_ecm) << "]" << std::endl; return; } @@ -185,7 +185,7 @@ void BuoyancyEnginePlugin::Configure( this->dataPtr->world = _ecm.EntityByComponents(components::World()); if (this->dataPtr->world == kNullEntity) { - ignerr << "World entity not found" <HasElement("namespace")) { - cmdTopic = ignition::transport::TopicUtils::AsValidTopic( + cmdTopic = gz::transport::TopicUtils::AsValidTopic( "/model/" + _sdf->Get("namespace") + "/buoyancy_engine/"); - statusTopic = ignition::transport::TopicUtils::AsValidTopic( + statusTopic = gz::transport::TopicUtils::AsValidTopic( "/model/" + _sdf->Get("namespace") + "/buoyancy_engine/current_volume"); } @@ -203,20 +203,20 @@ void BuoyancyEnginePlugin::Configure( if (!this->dataPtr->node.Subscribe(cmdTopic, &BuoyancyEnginePrivateData::OnCmdBuoyancyEngine, this->dataPtr.get())) { - ignerr << "Failed to subscribe to [" << cmdTopic << "]" << std::endl; + gzerr << "Failed to subscribe to [" << cmdTopic << "]" << std::endl; } this->dataPtr->statusPub = - this->dataPtr->node.Advertise(statusTopic); + this->dataPtr->node.Advertise(statusTopic); - igndbg << "Listening to commands on [" << cmdTopic + gzdbg << "Listening to commands on [" << cmdTopic << "], publishing status on [" << statusTopic << "]" <> DurationInSecs; auto dt = std::chrono::duration_cast(_info.dt).count(); - ignition::msgs::Double msg; + gz::msgs::Double msg; const components::Gravity *gravity = _ecm.Component( this->dataPtr->world); if (!gravity) { - ignerr << "World has no gravity component" << std::endl; + gzerr << "World has no gravity component" << std::endl; return; } - ignition::gazebo::Link link(this->dataPtr->linkEntity); + gz::sim::Link link(this->dataPtr->linkEntity); math::Vector3d zForce; { std::lock_guard lock(this->dataPtr->mtx); @@ -276,9 +276,13 @@ void BuoyancyEnginePlugin::PreUpdate( IGNITION_ADD_PLUGIN( BuoyancyEnginePlugin, - ignition::gazebo::System, + gz::sim::System, BuoyancyEnginePlugin::ISystemConfigure, BuoyancyEnginePlugin::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(BuoyancyEnginePlugin, + "gz::sim::systems::BuoyancyEngine") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(BuoyancyEnginePlugin, "ignition::gazebo::systems::BuoyancyEngine") diff --git a/src/systems/buoyancy_engine/BuoyancyEngine.hh b/src/systems/buoyancy_engine/BuoyancyEngine.hh index faa0536c37..b636531db0 100644 --- a/src/systems/buoyancy_engine/BuoyancyEngine.hh +++ b/src/systems/buoyancy_engine/BuoyancyEngine.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_BUOYANCYENGINE_HH_ -#define IGNITION_GAZEBO_SYSTEMS_BUOYANCYENGINE_HH_ +#ifndef GZ_SIM_SYSTEMS_BUOYANCYENGINE_HH_ +#define GZ_SIM_SYSTEMS_BUOYANCYENGINE_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { class BuoyancyEnginePrivateData; @@ -59,10 +59,10 @@ namespace systems /// If not defined then there is no surface [optional, float] /// /// ## Topics - /// * Subscribes to a ignition::msgs::Double on `buoyancy_engine` or + /// * Subscribes to a gz::msgs::Double on `buoyancy_engine` or /// `/model/{namespace}/buoyancy_engine`. This is the set point for the /// engine. - /// * Publishes a ignition::msgs::Double on `buoyancy_engine` or + /// * Publishes a gz::msgs::Double on `buoyancy_engine` or /// `/model/{namespace}/buoyancy_engine/current_volume` on the current volume /// /// ## Examples @@ -72,12 +72,12 @@ namespace systems /// ``` /// Enter the following in a separate terminal: /// ``` - /// ign topic -t /model/buoyant_box/buoyancy_engine/ -m ignition.msgs.Double + /// ign topic -t /model/buoyant_box/buoyancy_engine/ -m gz.msgs.Double /// -p "data: 0.003" /// ``` /// To see the box float up. /// ``` - /// ign topic -t /model/buoyant_box/buoyancy_engine/ -m ignition.msgs.Double + /// ign topic -t /model/buoyant_box/buoyancy_engine/ -m gz.msgs.Double /// -p "data: 0.001" /// ``` /// To see the box go down. @@ -86,25 +86,25 @@ namespace systems /// ign topic -t /model/buoyant_box/buoyancy_engine/current_volume -e /// ``` class BuoyancyEnginePlugin: - 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 Constructor public: BuoyancyEnginePlugin(); // Documentation inherited public: void 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*/ ); // Documentation inherited public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm); + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm); /// \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 ad40f17a36..32c334dfc8 100644 --- a/src/systems/camera_video_recorder/CameraVideoRecorder.cc +++ b/src/systems/camera_video_recorder/CameraVideoRecorder.cc @@ -46,12 +46,12 @@ #include "CameraVideoRecorder.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace 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, @@ -70,7 +70,7 @@ class ignition::gazebo::systems::CameraVideoRecorderPrivate public: std::mutex updateMutex; /// \brief Connection to the post-render event. - public: ignition::common::ConnectionPtr postRenderConn; + public: gz::common::ConnectionPtr postRenderConn; /// \brief Pointer to the event manager public: EventManager *eventMgr = nullptr; @@ -168,7 +168,7 @@ bool CameraVideoRecorderPrivate::OnRecordVideo(const msgs::VideoRecord &_msg, if (this->recordVideoFormat != "mp4" && this->recordVideoFormat!= "ogv" && this->recordVideoFormat != "avi") { - ignerr << "Video encoding format: '" << this->recordVideoFormat + gzerr << "Video encoding format: '" << this->recordVideoFormat << "' not supported. Available formats are: mp4, ogv, and avi." << std::endl; _res.set_data(false); @@ -220,7 +220,7 @@ void CameraVideoRecorder::Configure( _ecm.Component(_entity); if (!cameraEntComp) { - ignerr << "The camera video recorder system can only be attached to a " + gzerr << "The camera video recorder system can only be attached to a " << "camera sensor." << std::endl; } @@ -233,7 +233,7 @@ void CameraVideoRecorder::Configure( _sdf->Get("service")); if (this->dataPtr->service.empty()) { - ignerr << "Service [" << _sdf->Get("service") + gzerr << "Service [" << _sdf->Get("service") << "] not valid. Ignoring." << std::endl; } } @@ -248,7 +248,7 @@ void CameraVideoRecorder::Configure( topic = transport::TopicUtils::AsValidTopic(scoped + "/image"); if (topic.empty()) { - ignerr << "Failed to generate valid topic for entity [" << scoped + gzerr << "Failed to generate valid topic for entity [" << scoped << "]" << std::endl; } } @@ -268,7 +268,7 @@ void CameraVideoRecorder::Configure( std::string recorderStatsTopic = this->dataPtr->sensorTopic + "/stats"; this->dataPtr->recorderStatsPub = this->dataPtr->node.Advertise(recorderStatsTopic); - ignmsg << "Camera Video recorder stats topic advertised on [" + gzmsg << "Camera Video recorder stats topic advertised on [" << recorderStatsTopic << "]" << std::endl; } @@ -296,14 +296,14 @@ void CameraVideoRecorderPrivate::OnPostRender() auto sensor = this->scene->SensorByName(this->cameraName); if (!sensor) { - ignerr << "Unable to find sensor: " << this->cameraName + gzerr << "Unable to find sensor: " << this->cameraName << std::endl; return; } this->camera = std::dynamic_pointer_cast(sensor); if (!this->camera) { - ignerr << "Sensor: " << this->cameraName << " is not a caemra" + gzerr << "Sensor: " << this->cameraName << " is not a caemra" << std::endl; return; } @@ -356,7 +356,7 @@ void CameraVideoRecorderPrivate::OnPostRender() std::chrono::steady_clock::duration dt; dt = t - this->recordStartTime; int64_t sec, nsec; - std::tie(sec, nsec) = ignition::math::durationToSecNsec(dt); + std::tie(sec, nsec) = gz::math::durationToSecNsec(dt); msgs::Time msg; msg.set_sec(sec); msg.set_nsec(nsec); @@ -381,7 +381,7 @@ void CameraVideoRecorderPrivate::OnPostRender() this->recordStartTime = std::chrono::steady_clock::time_point( std::chrono::duration(std::chrono::seconds(0))); - ignmsg << "Start video recording on [" << this->service << "]. " + gzmsg << "Start video recording on [" << this->service << "]. " << "Encoding to tmp file: [" << this->tmpVideoFilename << "]" << std::endl; } @@ -395,7 +395,7 @@ void CameraVideoRecorderPrivate::OnPostRender() // stop encoding this->videoEncoder.Stop(); - ignmsg << "Stop video recording on [" << this->service << "]." << std::endl; + gzmsg << "Stop video recording on [" << this->service << "]." << std::endl; if (common::exists(this->tmpVideoFilename)) { @@ -405,7 +405,7 @@ void CameraVideoRecorderPrivate::OnPostRender() if (parentPath != this->recordVideoSavePath && !common::exists(parentPath) && !common::createDirectory(parentPath)) { - ignerr << "Unable to create directory[" << parentPath + gzerr << "Unable to create directory[" << parentPath << "]. Video file[" << this->tmpVideoFilename << "] will not be moved." << std::endl; } @@ -416,7 +416,7 @@ void CameraVideoRecorderPrivate::OnPostRender() // Remove old temp file, if it exists. std::remove(this->tmpVideoFilename.c_str()); - ignmsg << "Saving tmp video[" << this->tmpVideoFilename << "] file to [" + gzmsg << "Saving tmp video[" << this->tmpVideoFilename << "] file to [" << this->recordVideoSavePath << "]" << std::endl; } } @@ -448,7 +448,7 @@ void CameraVideoRecorder::PostUpdate(const UpdateInfo &_info, "/record_video"); if (this->dataPtr->service.empty()) { - ignerr << "Failed to create valid service for [" << scoped << "]" + gzerr << "Failed to create valid service for [" << scoped << "]" << std::endl; } return; @@ -456,16 +456,20 @@ void CameraVideoRecorder::PostUpdate(const UpdateInfo &_info, this->dataPtr->node.Advertise(this->dataPtr->service, &CameraVideoRecorderPrivate::OnRecordVideo, this->dataPtr.get()); - ignmsg << "Record video service on [" + gzmsg << "Record video service on [" << this->dataPtr->service << "]" << std::endl; } IGNITION_ADD_PLUGIN(CameraVideoRecorder, - ignition::gazebo::System, + gz::sim::System, CameraVideoRecorder::ISystemConfigure, CameraVideoRecorder::ISystemPostUpdate) // 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 f9a3118176..9b40fff2d5 100644 --- a/src/systems/camera_video_recorder/CameraVideoRecorder.hh +++ b/src/systems/camera_video_recorder/CameraVideoRecorder.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_CAMERAVIDEORECORDER_SYSTEM_HH_ -#define IGNITION_GAZEBO_CAMERAVIDEORECORDER_SYSTEM_HH_ +#ifndef GZ_SIM_CAMERAVIDEORECORDER_SYSTEM_HH_ +#define GZ_SIM_CAMERAVIDEORECORDER_SYSTEM_HH_ #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { class CameraVideoRecorderPrivate; diff --git a/src/systems/collada_world_exporter/ColladaWorldExporter.cc b/src/systems/collada_world_exporter/ColladaWorldExporter.cc index cd3d3d3902..8ab4c3146d 100644 --- a/src/systems/collada_world_exporter/ColladaWorldExporter.cc +++ b/src/systems/collada_world_exporter/ColladaWorldExporter.cc @@ -50,12 +50,12 @@ #include "ColladaWorldExporter.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; -class ignition::gazebo::systems::ColladaWorldExporterPrivate +class gz::sim::systems::ColladaWorldExporterPrivate { // Default constructor public: ColladaWorldExporterPrivate() = default; @@ -85,7 +85,7 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate components::Name, components::Geometry, components::Transparency>( - [&](const ignition::gazebo::Entity &_entity, + [&](const gz::sim::Entity &_entity, const components::Visual *, const components::Name *_name, const components::Geometry *_geom, @@ -94,7 +94,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 = sim::worldPose(_entity, _ecm); common::MaterialPtr mat = std::make_shared(); auto material = _ecm.Component(_entity); @@ -107,12 +107,12 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate } mat->SetTransparency(_transparency->Data()); - const ignition::common::Mesh *mesh; - std::weak_ptr subm; + const gz::common::Mesh *mesh; + std::weak_ptr subm; math::Vector3d scale; math::Matrix4d matrix(worldPose); - ignition::common::MeshManager *meshManager = - ignition::common::MeshManager::Instance(); + gz::common::MeshManager *meshManager = + gz::common::MeshManager::Instance(); auto addSubmeshFunc = [&](int _matIndex) { @@ -210,13 +210,13 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate if (fullPath.empty()) { - ignerr << "Mesh geometry missing uri" << std::endl; + gzerr << "Mesh geometry missing uri" << std::endl; return true; } mesh = meshManager->Load(fullPath); if (!mesh) { - ignerr << "mesh not found!" << std::endl; + gzerr << "mesh not found!" << std::endl; return true; } @@ -246,7 +246,7 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate } else { - ignwarn << "Unsupported geometry type" << std::endl; + gzwarn << "Unsupported geometry type" << std::endl; } return true; @@ -301,7 +301,7 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate common::ColladaExporter exporter; exporter.Export(&worldMesh, "./" + worldMesh.Name(), true, subMeshMatrix, lights); - ignmsg << "The world has been exported into the " + gzmsg << "The world has been exported into the " << "./" + worldMesh.Name() << " directory." << std::endl; this->exported = true; } @@ -327,5 +327,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 0db2e7fae2..6a5891eef3 100644 --- a/src/systems/collada_world_exporter/ColladaWorldExporter.hh +++ b/src/systems/collada_world_exporter/ColladaWorldExporter.hh @@ -15,18 +15,18 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_COLLADAWORLDEXPORTER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_COLLADAWORLDEXPORTER_HH_ +#ifndef GZ_SIM_SYSTEMS_COLLADAWORLDEXPORTER_HH_ +#define GZ_SIM_SYSTEMS_COLLADAWORLDEXPORTER_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declarations. diff --git a/src/systems/comms_endpoint/CommsEndpoint.cc b/src/systems/comms_endpoint/CommsEndpoint.cc index 4202be96e2..170a1a41df 100644 --- a/src/systems/comms_endpoint/CommsEndpoint.cc +++ b/src/systems/comms_endpoint/CommsEndpoint.cc @@ -30,11 +30,11 @@ #include "gz/sim/Util.hh" #include "CommsEndpoint.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; -class ignition::gazebo::systems::CommsEndpoint::Implementation +class gz::sim::systems::CommsEndpoint::Implementation { /// \brief Send the bind request. public: void Bind(); @@ -42,7 +42,7 @@ class ignition::gazebo::systems::CommsEndpoint::Implementation /// \brief Service response callback. /// \brief \param[in] _rep Unused. /// \brief \param[in] _result Bind result. - public: void BindCallback(const ignition::msgs::Boolean &_rep, + public: void BindCallback(const gz::msgs::Boolean &_rep, const bool _result); /// \brief The address. @@ -64,10 +64,10 @@ class ignition::gazebo::systems::CommsEndpoint::Implementation public: std::string unbindSrv = "/broker/unbind"; /// \brief Message to send the bind request. - public: ignition::msgs::StringMsg_V bindReq; + public: gz::msgs::StringMsg_V bindReq; /// \brief Message to send the unbind request. - public: ignition::msgs::StringMsg_V unbindReq; + public: gz::msgs::StringMsg_V unbindReq; /// \brief Time between bind retries (secs). public: std::chrono::steady_clock::duration bindRequestPeriod{1}; @@ -76,17 +76,17 @@ class ignition::gazebo::systems::CommsEndpoint::Implementation public: std::chrono::steady_clock::duration lastBindRequestTime{-2}; /// \brief The ignition transport node. - public: std::unique_ptr node; + public: std::unique_ptr node; }; ////////////////////////////////////////////////// void CommsEndpoint::Implementation::BindCallback( - const ignition::msgs::Boolean &/*_rep*/, const bool _result) + const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (_result) this->bound = true; - igndbg << "Succesfuly bound to [" << this->address << "] on topic [" + gzdbg << "Succesfuly bound to [" << this->address << "] on topic [" << this->topic << "]" << std::endl; } @@ -99,9 +99,9 @@ void CommsEndpoint::Implementation::Bind() ////////////////////////////////////////////////// CommsEndpoint::CommsEndpoint() - : dataPtr(ignition::utils::MakeUniqueImpl()) + : dataPtr(gz::utils::MakeUniqueImpl()) { - this->dataPtr->node = std::make_unique(); + this->dataPtr->node = std::make_unique(); } ////////////////////////////////////////////////// @@ -126,7 +126,7 @@ void CommsEndpoint::Configure(const Entity &_entity, // Parse
. if (!_sdf->HasElement("address")) { - ignerr << "No
specified." << std::endl; + gzerr << "No
specified." << std::endl; return; } this->dataPtr->address = _sdf->Get("address"); @@ -134,7 +134,7 @@ void CommsEndpoint::Configure(const Entity &_entity, // Parse . if (!_sdf->HasElement("topic")) { - ignerr << "No specified." << std::endl; + gzerr << "No specified." << std::endl; return; } this->dataPtr->topic = _sdf->Get("topic"); @@ -164,8 +164,8 @@ void CommsEndpoint::Configure(const Entity &_entity, ////////////////////////////////////////////////// void CommsEndpoint::PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &/*_ecm*/) + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &/*_ecm*/) { IGN_PROFILE("CommsEndpoint::PreUpdate"); @@ -185,9 +185,13 @@ void CommsEndpoint::PreUpdate( } IGNITION_ADD_PLUGIN(CommsEndpoint, - ignition::gazebo::System, + gz::sim::System, CommsEndpoint::ISystemConfigure, CommsEndpoint::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(CommsEndpoint, + "gz::sim::systems::CommsEndpoint") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(CommsEndpoint, "ignition::gazebo::systems::CommsEndpoint") diff --git a/src/systems/comms_endpoint/CommsEndpoint.hh b/src/systems/comms_endpoint/CommsEndpoint.hh index d41841b45c..7b9c3a68ec 100644 --- a/src/systems/comms_endpoint/CommsEndpoint.hh +++ b/src/systems/comms_endpoint/CommsEndpoint.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_COMMSENDPOINT_HH_ -#define IGNITION_GAZEBO_SYSTEMS_COMMSENDPOINT_HH_ +#ifndef GZ_SIM_SYSTEMS_COMMSENDPOINT_HH_ +#define GZ_SIM_SYSTEMS_COMMSENDPOINT_HH_ #include @@ -23,12 +23,12 @@ #include #include "gz/sim/System.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { /// \brief A system that registers in the comms broker an endpoint. @@ -54,7 +54,7 @@ namespace systems /// Here's an example: /// + /// name="gz::sim::systems::CommsEndpoint"> ///
addr1
/// addr1/rx /// @@ -81,8 +81,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. IGN_UTILS_UNIQUE_IMPL_PTR(dataPtr) diff --git a/src/systems/contact/Contact.cc b/src/systems/contact/Contact.cc index 9b575c2889..a1166675a7 100644 --- a/src/systems/contact/Contact.cc +++ b/src/systems/contact/Contact.cc @@ -42,8 +42,8 @@ #include "gz/sim/components/Name.hh" #include "gz/sim/components/ParentEntity.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace 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. @@ -122,8 +122,8 @@ void ContactSensor::Load(const sdf::ElementPtr &_sdf, const std::string &_topic, this->topic = tmpTopic; } - ignmsg << "Contact system publishing on " << this->topic << std::endl; - this->pub = this->node.Advertise(this->topic); + gzmsg << "Contact system publishing on " << this->topic << std::endl; + this->pub = this->node.Advertise(this->topic); } ////////////////////////////////////////////////// @@ -244,7 +244,7 @@ void ContactPrivate::RemoveSensors( auto sensorId = this->entitySensorMap.find(_entity); if (sensorId == this->entitySensorMap.end()) { - ignerr << "Internal error, missing Contact sensor for entity [" + gzerr << "Internal error, missing Contact sensor for entity [" << _entity << "]" << std::endl; return true; } @@ -275,7 +275,7 @@ void Contact::PostUpdate(const UpdateInfo &_info, // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -299,5 +299,8 @@ IGNITION_ADD_PLUGIN(Contact, System, Contact::ISystemPostUpdate ) +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 6e6b76dadf..0494978fb3 100644 --- a/src/systems/contact/Contact.hh +++ b/src/systems/contact/Contact.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_CONTACT_HH_ -#define IGNITION_GAZEBO_SYSTEMS_CONTACT_HH_ +#ifndef GZ_SIM_SYSTEMS_CONTACT_HH_ +#define GZ_SIM_SYSTEMS_CONTACT_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declaration @@ -60,6 +60,6 @@ namespace systems }; } } -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz #endif diff --git a/src/systems/detachable_joint/DetachableJoint.cc b/src/systems/detachable_joint/DetachableJoint.cc index 3cc9ff573d..5f2c6fb52b 100644 --- a/src/systems/detachable_joint/DetachableJoint.cc +++ b/src/systems/detachable_joint/DetachableJoint.cc @@ -35,8 +35,8 @@ #include "DetachableJoint.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; ///////////////////////////////////////////////// @@ -48,7 +48,7 @@ void DetachableJoint::Configure(const Entity &_entity, this->model = Model(_entity); if (!this->model.Valid(_ecm)) { - ignerr << "DetachableJoint should be attached to a model entity. " + gzerr << "DetachableJoint should be attached to a model entity. " << "Failed to initialize." << std::endl; return; } @@ -59,7 +59,7 @@ void DetachableJoint::Configure(const Entity &_entity, this->parentLinkEntity = this->model.LinkByName(_ecm, parentLinkName); if (kNullEntity == this->parentLinkEntity) { - ignerr << "Link with name " << parentLinkName + gzerr << "Link with name " << parentLinkName << " not found in model " << this->model.Name(_ecm) << ". Make sure the parameter 'parent_link' has the " << "correct value. Failed to initialize.\n"; @@ -68,7 +68,7 @@ void DetachableJoint::Configure(const Entity &_entity, } else { - ignerr << "'parent_link' is a required parameter for DetachableJoint. " + gzerr << "'parent_link' is a required parameter for DetachableJoint. " "Failed to initialize.\n"; return; } @@ -79,7 +79,7 @@ void DetachableJoint::Configure(const Entity &_entity, } else { - ignerr << "'child_model' is a required parameter for DetachableJoint." + gzerr << "'child_model' is a required parameter for DetachableJoint." "Failed to initialize.\n"; return; } @@ -90,7 +90,7 @@ void DetachableJoint::Configure(const Entity &_entity, } else { - ignerr << "'child_link' is a required parameter for DetachableJoint." + gzerr << "'child_link' is a required parameter for DetachableJoint." "Failed to initialize.\n"; return; } @@ -114,8 +114,8 @@ void DetachableJoint::Configure(const Entity &_entity, ////////////////////////////////////////////////// void DetachableJoint::PreUpdate( - const ignition::gazebo::UpdateInfo &/*_info*/, - ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::UpdateInfo &/*_info*/, + gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("DetachableJoint::PreUpdate"); if (this->validConfig && !this->initialized) @@ -152,20 +152,20 @@ void DetachableJoint::PreUpdate( this->node.Subscribe( this->topic, &DetachableJoint::OnDetachRequest, this); - ignmsg << "DetachableJoint subscribing to messages on " + gzmsg << "DetachableJoint subscribing to messages on " << "[" << this->topic << "]" << std::endl; this->initialized = true; } else { - ignwarn << "Child Link " << this->childLinkName + gzwarn << "Child Link " << this->childLinkName << " could not be found.\n"; } } else if (!this->suppressChildWarning) { - ignwarn << "Child Model " << this->childModelName + gzwarn << "Child Model " << this->childModelName << " could not be found.\n"; } } @@ -175,7 +175,7 @@ void DetachableJoint::PreUpdate( if (this->detachRequested && (kNullEntity != this->detachableJointEntity)) { // Detach the models - igndbg << "Removing entity: " << this->detachableJointEntity << std::endl; + gzdbg << "Removing entity: " << this->detachableJointEntity << std::endl; _ecm.RequestRemoveEntity(this->detachableJointEntity); this->detachableJointEntity = kNullEntity; this->detachRequested = false; @@ -190,9 +190,13 @@ void DetachableJoint::OnDetachRequest(const msgs::Empty &) } IGNITION_ADD_PLUGIN(DetachableJoint, - ignition::gazebo::System, + gz::sim::System, 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 36d405e215..ae40230656 100644 --- a/src/systems/detachable_joint/DetachableJoint.hh +++ b/src/systems/detachable_joint/DetachableJoint.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_DETACHABLEJOINT_HH_ -#define IGNITION_GAZEBO_SYSTEMS_DETACHABLEJOINT_HH_ +#ifndef GZ_SIM_SYSTEMS_DETACHABLEJOINT_HH_ +#define GZ_SIM_SYSTEMS_DETACHABLEJOINT_HH_ #include @@ -27,12 +27,12 @@ #include "gz/sim/Model.hh" #include "gz/sim/System.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { /// \brief A system that initially attaches two models via a fixed joint and @@ -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 9e1eb89f13..71a97c16a2 100644 --- a/src/systems/diff_drive/DiffDrive.cc +++ b/src/systems/diff_drive/DiffDrive.cc @@ -39,8 +39,8 @@ #include "gz/sim/Model.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; /// \brief Velocity command. @@ -55,29 +55,29 @@ 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 - public: void OnCmdVel(const ignition::msgs::Twist &_msg); + public: void OnCmdVel(const gz::msgs::Twist &_msg); /// \brief Callback for enable/disable subscription /// \param[in] _msg Boolean message - public: void OnEnable(const ignition::msgs::Boolean &_msg); + public: void OnEnable(const gz::msgs::Boolean &_msg); /// \brief Update odometry and publish an odometry message. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateOdometry(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm); /// \brief Update the linear and angular velocities. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateVelocity(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateVelocity(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm); /// \brief Ignition communication node. public: transport::Node node; @@ -128,10 +128,10 @@ class ignition::gazebo::systems::DiffDrivePrivate public: transport::Node::Publisher tfPub; /// \brief Linear velocity limiter. - public: std::unique_ptr limiterLin; + public: std::unique_ptr limiterLin; /// \brief Angular velocity limiter. - public: std::unique_ptr limiterAng; + public: std::unique_ptr limiterAng; /// \brief Previous control command. public: Commands last0Cmd; @@ -177,7 +177,7 @@ void DiffDrive::Configure(const Entity &_entity, if (!this->dataPtr->model.Valid(_ecm)) { - ignerr << "DiffDrive plugin should be attached to a model entity. " + gzerr << "DiffDrive plugin should be attached to a model entity. " << "Failed to initialize." << std::endl; return; } @@ -206,8 +206,8 @@ void DiffDrive::Configure(const Entity &_entity, this->dataPtr->wheelRadius).first; // Instantiate the speed limiters. - this->dataPtr->limiterLin = std::make_unique(); - this->dataPtr->limiterAng = std::make_unique(); + this->dataPtr->limiterLin = std::make_unique(); + this->dataPtr->limiterAng = std::make_unique(); // Parse speed limiter parameters. @@ -381,20 +381,20 @@ void DiffDrive::Configure(const Entity &_entity, if (_sdf->HasElement("child_frame_id")) this->dataPtr->sdfChildFrameId = _sdf->Get("child_frame_id"); - ignmsg << "DiffDrive subscribing to twist messages on [" << topic << "]" + gzmsg << "DiffDrive subscribing to twist messages on [" << topic << "]" << std::endl; } ////////////////////////////////////////////////// -void DiffDrive::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void DiffDrive::PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("DiffDrive::PreUpdate"); // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -413,7 +413,7 @@ void DiffDrive::PreUpdate(const ignition::gazebo::UpdateInfo &_info, this->dataPtr->leftJoints.push_back(joint); else if (warnedModels.find(modelName) == warnedModels.end()) { - ignwarn << "Failed to find left joint [" << name << "] for model [" + gzwarn << "Failed to find left joint [" << name << "] for model [" << modelName << "]" << std::endl; warned = true; } @@ -426,7 +426,7 @@ void DiffDrive::PreUpdate(const ignition::gazebo::UpdateInfo &_info, this->dataPtr->rightJoints.push_back(joint); else if (warnedModels.find(modelName) == warnedModels.end()) { - ignwarn << "Failed to find right joint [" << name << "] for model [" + gzwarn << "Failed to find right joint [" << name << "] for model [" << modelName << "]" << std::endl; warned = true; } @@ -442,7 +442,7 @@ void DiffDrive::PreUpdate(const ignition::gazebo::UpdateInfo &_info, if (warnedModels.find(modelName) != warnedModels.end()) { - ignmsg << "Found joints for model [" << modelName + gzmsg << "Found joints for model [" << modelName << "], plugin will start working." << std::endl; warnedModels.erase(modelName); } @@ -524,8 +524,8 @@ void DiffDrive::PostUpdate(const UpdateInfo &_info, } ////////////////////////////////////////////////// -void DiffDrivePrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) +void DiffDrivePrivate::UpdateOdometry(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("DiffDrive::UpdateOdometry"); // Initialize, if not already initialized. @@ -608,7 +608,7 @@ void DiffDrivePrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, // Construct the Pose_V/tf message and publish it. msgs::Pose_V tfMsg; - ignition::msgs::Pose *tfMsgPose = tfMsg.add_pose(); + gz::msgs::Pose *tfMsgPose = tfMsg.add_pose(); tfMsgPose->mutable_header()->CopyFrom(*msg.mutable_header()); tfMsgPose->mutable_position()->CopyFrom(msg.mutable_pose()->position()); tfMsgPose->mutable_orientation()->CopyFrom(msg.mutable_pose()->orientation()); @@ -619,8 +619,8 @@ void DiffDrivePrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, } ////////////////////////////////////////////////// -void DiffDrivePrivate::UpdateVelocity(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &/*_ecm*/) +void DiffDrivePrivate::UpdateVelocity(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &/*_ecm*/) { IGN_PROFILE("DiffDrive::UpdateVelocity"); @@ -674,9 +674,12 @@ void DiffDrivePrivate::OnEnable(const msgs::Boolean &_msg) } IGNITION_ADD_PLUGIN(DiffDrive, - ignition::gazebo::System, + gz::sim::System, DiffDrive::ISystemConfigure, 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 9ef73091e6..0208695b42 100644 --- a/src/systems/diff_drive/DiffDrive.hh +++ b/src/systems/diff_drive/DiffDrive.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_DIFFDRIVE_HH_ -#define IGNITION_GAZEBO_SYSTEMS_DIFFDRIVE_HH_ +#ifndef GZ_SIM_SYSTEMS_DIFFDRIVE_HH_ +#define GZ_SIM_SYSTEMS_DIFFDRIVE_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declaration @@ -68,14 +68,14 @@ namespace systems /// /// ``: Custom `frame_id` field that this system will use as the /// origin of the odometry transform in both the `` - /// `ignition.msgs.Pose_V` message and the `` - /// `ignition.msgs.Odometry` message. This element if optional, and the + /// `gz.msgs.Pose_V` message and the `` + /// `gz.msgs.Odometry` message. This element if optional, and the /// default value is `{name_of_model}/odom`. /// /// ``: Custom `child_frame_id` that this system will use as /// the target of the odometry trasnform in both the `` - /// `ignition.msgs.Pose_V` message and the `` - /// `ignition.msgs.Odometry` message. This element if optional, + /// `gz.msgs.Pose_V` message and the `` + /// `gz.msgs.Odometry` message. This element if optional, /// and the default value is `{name_of_model}/{name_of_link}`. /// /// ``: Sets both the minimum linear and minimum angular @@ -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/elevator/Elevator.cc b/src/systems/elevator/Elevator.cc index e756ff533c..15009dcced 100644 --- a/src/systems/elevator/Elevator.cc +++ b/src/systems/elevator/Elevator.cc @@ -50,12 +50,12 @@ #include "gz/sim/components/Name.hh" #include "gz/sim/components/Pose.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { @@ -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 @@ -231,7 +231,7 @@ void Elevator::Configure(const Entity &_entity, _sdf->Get("cmd_topic", topicPrefix + "/cmd").first; this->dataPtr->node.Subscribe(cmdTopicName, &ElevatorPrivate::OnCmdMsg, this->dataPtr.get()); - ignmsg << "System " << this->dataPtr->model.Name(_ecm) << " subscribed to " + gzmsg << "System " << this->dataPtr->model.Name(_ecm) << " subscribed to " << cmdTopicName << " for command messages" << std::endl; } @@ -272,7 +272,7 @@ bool ElevatorPrivate::InitCabin(const std::string &_cabinJointName, this->cabinJoint = this->model.JointByName(_ecm, _cabinJointName); if (this->cabinJoint == kNullEntity) { - ignerr << "Failed to find cabin joint " << _cabinJointName << std::endl; + gzerr << "Failed to find cabin joint " << _cabinJointName << std::endl; return false; } if (!_ecm.EntityHasComponentType(this->cabinJoint, @@ -298,7 +298,7 @@ bool ElevatorPrivate::InitCabin(const std::string &_cabinJointName, auto link = this->model.LinkByName(_ecm, name); if (link == kNullEntity) { - ignerr << "Failed to find floor link " << name << std::endl; + gzerr << "Failed to find floor link " << name << std::endl; return false; } auto z = _ecm.Component(link)->Data().Z(); @@ -326,7 +326,7 @@ bool ElevatorPrivate::InitDoors(const std::string &_doorJointPrefix, auto joint = this->model.JointByName(_ecm, name); if (joint == kNullEntity) { - ignerr << "Failed to find door joint " << name << std::endl; + gzerr << "Failed to find door joint " << name << std::endl; return false; } if (!_ecm.EntityHasComponentType(joint, @@ -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 @@ -434,7 +434,7 @@ void ElevatorPrivate::OnCmdMsg(const msgs::Int32 &_msg) auto target = _msg.data(); if (target < 0 || target >= static_cast(this->cabinTargets.size())) { - ignwarn << "Invalid target [" << target << "]; command must be in [0," + gzwarn << "Invalid target [" << target << "]; command must be in [0," << this->cabinTargets.size() << ")" << std::endl; return; } @@ -444,9 +444,12 @@ 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 } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/src/systems/elevator/Elevator.hh b/src/systems/elevator/Elevator.hh index e18cc76d11..39f26a372d 100644 --- a/src/systems/elevator/Elevator.hh +++ b/src/systems/elevator/Elevator.hh @@ -20,19 +20,19 @@ * \date January 2021 */ -#ifndef IGNITION_GAZEBO_SYSTEMS_ELEVATOR_HH_ -#define IGNITION_GAZEBO_SYSTEMS_ELEVATOR_HH_ +#ifndef GZ_SIM_SYSTEMS_ELEVATOR_HH_ +#define GZ_SIM_SYSTEMS_ELEVATOR_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { @@ -102,7 +102,7 @@ class ElevatorPrivate; /// /// ``: Time to wait with a door open before the door /// closes. This element is optional and the default value is 5 sec. -class IGNITION_GAZEBO_VISIBLE Elevator : public System, +class GZ_GAZEBO_VISIBLE Elevator : public System, public ISystemConfigure, public ISystemPostUpdate { @@ -128,7 +128,7 @@ class IGNITION_GAZEBO_VISIBLE Elevator : public System, } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_SYSTEMS_ELEVATOR_HH_ +#endif // GZ_SIM_SYSTEMS_ELEVATOR_HH_ diff --git a/src/systems/elevator/ElevatorCommonPrivate.hh b/src/systems/elevator/ElevatorCommonPrivate.hh index 748024485a..91a8818e15 100644 --- a/src/systems/elevator/ElevatorCommonPrivate.hh +++ b/src/systems/elevator/ElevatorCommonPrivate.hh @@ -20,8 +20,8 @@ * \date January 2021 */ -#ifndef IGNITION_GAZEBO_SYSTEMS_ELEVATOR_COMMON_PRIVATE_HH_ -#define IGNITION_GAZEBO_SYSTEMS_ELEVATOR_COMMON_PRIVATE_HH_ +#ifndef GZ_SIM_SYSTEMS_ELEVATOR_COMMON_PRIVATE_HH_ +#define GZ_SIM_SYSTEMS_ELEVATOR_COMMON_PRIVATE_HH_ #include #include @@ -29,12 +29,12 @@ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { @@ -93,7 +93,7 @@ class ElevatorCommonPrivate } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_SYSTEMS_ELEVATOR_COMMON_PRIVATE_HH_ +#endif // GZ_SIM_SYSTEMS_ELEVATOR_COMMON_PRIVATE_HH_ diff --git a/src/systems/elevator/ElevatorStateMachine.hh b/src/systems/elevator/ElevatorStateMachine.hh index e60b16c8aa..9f28d1b93c 100644 --- a/src/systems/elevator/ElevatorStateMachine.hh +++ b/src/systems/elevator/ElevatorStateMachine.hh @@ -20,8 +20,8 @@ * \date January 2021 */ -#ifndef IGNITION_GAZEBO_SYSTEMS_ELEVATOR_STATE_MACHINE_HH_ -#define IGNITION_GAZEBO_SYSTEMS_ELEVATOR_STATE_MACHINE_HH_ +#ifndef GZ_SIM_SYSTEMS_ELEVATOR_STATE_MACHINE_HH_ +#define GZ_SIM_SYSTEMS_ELEVATOR_STATE_MACHINE_HH_ #include @@ -30,12 +30,12 @@ #include "afsm/fsm.hpp" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { @@ -136,9 +136,9 @@ using ElevatorStateMachine = ::afsm::state_machine; } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz #include "state_machine/ElevatorStateMachineImpl.hh" -#endif // IGNITION_GAZEBO_SYSTEMS_ELEVATOR_STATE_MACHINE_HH_ +#endif // GZ_SIM_SYSTEMS_ELEVATOR_STATE_MACHINE_HH_ diff --git a/src/systems/elevator/state_machine/ActionsImpl.hh b/src/systems/elevator/state_machine/ActionsImpl.hh index e613fc6388..16e5d31af9 100644 --- a/src/systems/elevator/state_machine/ActionsImpl.hh +++ b/src/systems/elevator/state_machine/ActionsImpl.hh @@ -22,12 +22,12 @@ #include "../ElevatorStateMachine.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { @@ -97,5 +97,5 @@ struct CabinAtTarget } // namespace actions } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/src/systems/elevator/state_machine/ElevatorStateMachineImpl.hh b/src/systems/elevator/state_machine/ElevatorStateMachineImpl.hh index 9518317af8..3a9a5e5fa4 100644 --- a/src/systems/elevator/state_machine/ElevatorStateMachineImpl.hh +++ b/src/systems/elevator/state_machine/ElevatorStateMachineImpl.hh @@ -31,12 +31,12 @@ #include "../ElevatorCommonPrivate.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { @@ -102,7 +102,7 @@ void ElevatorStateMachinePrivate::EnqueueNewTarget(double _target) std::ostringstream ss; ss << "The elevator enqueued target " << _target << " [ "; for (const auto &target : this->targets) ss << target << " "; - ignmsg << ss.str() << "]" << std::endl; + gzmsg << ss.str() << "]" << std::endl; } ////////////////////////////////////////////////// @@ -126,8 +126,8 @@ ElevatorStateMachineDef::~ElevatorStateMachineDef() = default; } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz #include "EventsImpl.hh" diff --git a/src/systems/elevator/state_machine/EventsImpl.hh b/src/systems/elevator/state_machine/EventsImpl.hh index 1aa4d9a781..ce50894970 100644 --- a/src/systems/elevator/state_machine/EventsImpl.hh +++ b/src/systems/elevator/state_machine/EventsImpl.hh @@ -20,12 +20,12 @@ * \date January 2021 */ -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { @@ -75,5 +75,5 @@ struct CabinAtTarget } // namespace events } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/src/systems/elevator/state_machine/GuardsImpl.hh b/src/systems/elevator/state_machine/GuardsImpl.hh index ec5ac4c706..0a6c8349e8 100644 --- a/src/systems/elevator/state_machine/GuardsImpl.hh +++ b/src/systems/elevator/state_machine/GuardsImpl.hh @@ -22,12 +22,12 @@ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { @@ -78,5 +78,5 @@ struct NoQueuedTarget } // namespace guards } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/src/systems/elevator/state_machine/StatesImpl.hh b/src/systems/elevator/state_machine/StatesImpl.hh index 2c5d1abc0c..bc636aed2d 100644 --- a/src/systems/elevator/state_machine/StatesImpl.hh +++ b/src/systems/elevator/state_machine/StatesImpl.hh @@ -27,12 +27,12 @@ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { @@ -43,7 +43,7 @@ struct ElevatorStateMachineDef::IdleState : state public: template void on_enter(const Event &, FSM &) { - ignmsg << "The elevator is idling" << std::endl; + gzmsg << "The elevator is idling" << std::endl; } }; @@ -74,7 +74,7 @@ struct ElevatorStateMachineDef::DoorState : state> { const auto &data = _fsm.dataPtr; int32_t floorTarget = data->system->state; - ignmsg << "The elevator is " << this->Report(data) << std::endl; + gzmsg << "The elevator is " << this->Report(data) << std::endl; double jointTarget = this->JointTarget(data, floorTarget); data->SendCmd(data->system->doorJointCmdPubs[floorTarget], jointTarget); @@ -173,7 +173,7 @@ struct ElevatorStateMachineDef::WaitState : state void on_enter(const Event &, FSM &_fsm) { const auto &data = _fsm.dataPtr; - ignmsg << "The elevator is waiting to close door " << data->system->state + gzmsg << "The elevator is waiting to close door " << data->system->state << std::endl; this->triggerEvent = [&_fsm] { _fsm.process_event(events::Timeout()); }; @@ -215,7 +215,7 @@ struct ElevatorStateMachineDef::MoveCabinState : state { const auto &data = _fsm.dataPtr; int32_t floorTarget = data->targets.front(); - ignmsg << "The elevator is moving the cabin [ " << data->system->state + gzmsg << "The elevator is moving the cabin [ " << data->system->state << " -> " << floorTarget << " ]" << std::endl; double jointTarget = data->system->cabinTargets[floorTarget]; @@ -246,5 +246,5 @@ struct ElevatorStateMachineDef::MoveCabinState : state } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/src/systems/elevator/utils/DoorTimer.cc b/src/systems/elevator/utils/DoorTimer.cc index 960712f78a..2ac9cb4046 100644 --- a/src/systems/elevator/utils/DoorTimer.cc +++ b/src/systems/elevator/utils/DoorTimer.cc @@ -24,12 +24,12 @@ #include "DoorTimer.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { @@ -101,5 +101,5 @@ void DoorTimer::Update(const UpdateInfo &_info, bool _isDoorwayBlocked) } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/src/systems/elevator/utils/DoorTimer.hh b/src/systems/elevator/utils/DoorTimer.hh index 352889760d..31716802b9 100644 --- a/src/systems/elevator/utils/DoorTimer.hh +++ b/src/systems/elevator/utils/DoorTimer.hh @@ -20,8 +20,8 @@ * \date January 2021 */ -#ifndef IGNITION_GAZEBO_SYSTEMS_DOOR_TIMER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_DOOR_TIMER_HH_ +#ifndef GZ_SIM_SYSTEMS_DOOR_TIMER_HH_ +#define GZ_SIM_SYSTEMS_DOOR_TIMER_HH_ #include #include @@ -29,12 +29,12 @@ #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { @@ -74,7 +74,7 @@ class DoorTimer } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_SYSTEMS_DOOR_TIMER_HH_ +#endif // GZ_SIM_SYSTEMS_DOOR_TIMER_HH_ diff --git a/src/systems/elevator/utils/JointMonitor.cc b/src/systems/elevator/utils/JointMonitor.cc index d55c270664..d600cbb867 100644 --- a/src/systems/elevator/utils/JointMonitor.cc +++ b/src/systems/elevator/utils/JointMonitor.cc @@ -27,12 +27,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { @@ -98,5 +98,5 @@ void JointMonitor::Update(const EntityComponentManager &_ecm) } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/src/systems/elevator/utils/JointMonitor.hh b/src/systems/elevator/utils/JointMonitor.hh index 3f4b602a69..eea1284dc6 100644 --- a/src/systems/elevator/utils/JointMonitor.hh +++ b/src/systems/elevator/utils/JointMonitor.hh @@ -20,20 +20,20 @@ * \date January 2021 */ -#ifndef IGNITION_GAZEBO_SYSTEMS_JOINT_MONITOR_HH_ -#define IGNITION_GAZEBO_SYSTEMS_JOINT_MONITOR_HH_ +#ifndef GZ_SIM_SYSTEMS_JOINT_MONITOR_HH_ +#define GZ_SIM_SYSTEMS_JOINT_MONITOR_HH_ #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { @@ -73,7 +73,7 @@ class JointMonitor } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz -#endif // IGNITION_GAZEBO_SYSTEMS_JOINT_MONITOR_HH_ +#endif // GZ_SIM_SYSTEMS_JOINT_MONITOR_HH_ diff --git a/src/systems/follow_actor/FollowActor.cc b/src/systems/follow_actor/FollowActor.cc index aad9a9e58e..54a4d442ce 100644 --- a/src/systems/follow_actor/FollowActor.cc +++ b/src/systems/follow_actor/FollowActor.cc @@ -29,12 +29,12 @@ #include "FollowActor.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; /// \brief Private FollowActor data class. -class ignition::gazebo::systems::FollowActorPrivate +class gz::sim::systems::FollowActorPrivate { /// \brief Entity for the actor. public: Entity actorEntity{kNullEntity}; @@ -84,13 +84,13 @@ void FollowActor::Configure(const Entity &_entity, auto actorComp = _ecm.Component(_entity); if (!actorComp) { - ignerr << "Entity [" << _entity << "] is not an actor." << std::endl; + gzerr << "Entity [" << _entity << "] is not an actor." << std::endl; return; } if (!_sdf->HasElement("target")) { - ignerr << "Missing , can't follow." << std::endl; + gzerr << "Missing , can't follow." << std::endl; return; } @@ -99,7 +99,7 @@ void FollowActor::Configure(const Entity &_entity, targetName)); if (kNullEntity == this->dataPtr->targetEntity) { - ignerr << "Failed to find target entity [" << targetName << "]" + gzerr << "Failed to find target entity [" << targetName << "]" << std::endl; return; } @@ -123,7 +123,7 @@ void FollowActor::Configure(const Entity &_entity, { if (actorComp->Data().AnimationCount() < 1) { - ignerr << "Actor SDF doesn't have any animations." << std::endl; + gzerr << "Actor SDF doesn't have any animations." << std::endl; return; } @@ -136,7 +136,7 @@ void FollowActor::Configure(const Entity &_entity, if (animationName.empty()) { - ignerr << "Can't find actor's animation name." << std::endl; + gzerr << "Can't find actor's animation name." << std::endl; return; } @@ -237,7 +237,7 @@ void FollowActor::PreUpdate(const UpdateInfo &_info, { if (this->dataPtr->following) { - ignmsg << "Target [" << this->dataPtr->targetEntity + gzmsg << "Target [" << this->dataPtr->targetEntity << "] too far, actor [" << this->dataPtr->actorEntity <<"] stopped following" << std::endl; this->dataPtr->following = false; @@ -246,7 +246,7 @@ void FollowActor::PreUpdate(const UpdateInfo &_info, } if (!this->dataPtr->following) { - ignmsg << "Target [" << this->dataPtr->targetEntity + gzmsg << "Target [" << this->dataPtr->targetEntity << "] within range, actor [" << this->dataPtr->actorEntity <<"] started following" << std::endl; this->dataPtr->following = true; @@ -291,4 +291,7 @@ IGNITION_ADD_PLUGIN(FollowActor, System, FollowActor::ISystemPreUpdate ) +IGNITION_ADD_PLUGIN_ALIAS(FollowActor, "gz::sim::systems::FollowActor") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(FollowActor, "ignition::gazebo::systems::FollowActor") diff --git a/src/systems/follow_actor/FollowActor.hh b/src/systems/follow_actor/FollowActor.hh index 1443d12fb3..7a01a920cc 100644 --- a/src/systems/follow_actor/FollowActor.hh +++ b/src/systems/follow_actor/FollowActor.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_FOLLOWACTOR_HH_ -#define IGNITION_GAZEBO_SYSTEMS_FOLLOWACTOR_HH_ +#ifndef GZ_SIM_SYSTEMS_FOLLOWACTOR_HH_ +#define GZ_SIM_SYSTEMS_FOLLOWACTOR_HH_ #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declarations. diff --git a/src/systems/force_torque/ForceTorque.cc b/src/systems/force_torque/ForceTorque.cc index 3a2f3f77ff..c4f606237c 100644 --- a/src/systems/force_torque/ForceTorque.cc +++ b/src/systems/force_torque/ForceTorque.cc @@ -46,16 +46,16 @@ #include "gz/sim/EntityComponentManager.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; /// \brief Private ForceTorque data class. -class ignition::gazebo::systems::ForceTorquePrivate +class gz::sim::systems::ForceTorquePrivate { /// \brief A map of FT entity to its FT sensor. public: std::unordered_map> entitySensorMap; + std::unique_ptr> entitySensorMap; /// \brief A struct to hold the joint and link entities associated with a /// sensor @@ -124,7 +124,7 @@ void ForceTorque::PostUpdate(const UpdateInfo &_info, // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -183,7 +183,7 @@ void ForceTorquePrivate::CreateForceTorqueEntities(EntityComponentManager &_ecm) sensors::ForceTorqueSensor>(data); if (nullptr == sensor) { - ignerr << "Failed to create sensor [" << sensorScopedName << "]" + gzerr << "Failed to create sensor [" << sensorScopedName << "]" << std::endl; return true; } @@ -199,7 +199,7 @@ void ForceTorquePrivate::CreateForceTorqueEntities(EntityComponentManager &_ecm) if (!_ecm.EntityHasComponentType(jointEntity, components::Joint::typeId)) { - ignerr << "Parent entity of sensor [" << sensorScopedName + gzerr << "Parent entity of sensor [" << sensorScopedName << "] must be a joint. Failed to create sensor." << std::endl; return true; } @@ -215,7 +215,7 @@ void ForceTorquePrivate::CreateForceTorqueEntities(EntityComponentManager &_ecm) this->GetLinkFromScopedName(_ecm, jointParentName, modelEntity); if (kNullEntity == jointParentLinkEntity ) { - ignerr << "Parent link with name [" << jointParentName + gzerr << "Parent link with name [" << jointParentName << "] of joint with name [" << jointName << "] not found. Failed to create sensor [" << sensorScopedName << "]" << std::endl; @@ -228,7 +228,7 @@ void ForceTorquePrivate::CreateForceTorqueEntities(EntityComponentManager &_ecm) this->GetLinkFromScopedName(_ecm, jointChildName, modelEntity); if (kNullEntity == jointChildLinkEntity) { - ignerr << "Child link with name [" << jointChildName + gzerr << "Child link with name [" << jointChildName << "] of joint with name [" << jointName << "] not found. Failed to create sensor [" << sensorScopedName << "]" << std::endl; @@ -268,7 +268,7 @@ void ForceTorquePrivate::Update(const EntityComponentManager &_ecm) auto jointLinkIt = this->sensorJointLinkMap.find(_entity); if (jointLinkIt == this->sensorJointLinkMap.end()) { - ignerr << "Failed to update Force/Torque Sensor: " << _entity + gzerr << "Failed to update Force/Torque Sensor: " << _entity << ". Associated entities not found." << std::endl; return true; } @@ -313,7 +313,7 @@ void ForceTorquePrivate::Update(const EntityComponentManager &_ecm) } else { - ignerr << "Failed to update Force/Torque Sensor: " << _entity << ". " + gzerr << "Failed to update Force/Torque Sensor: " << _entity << ". " << "Entity not found." << std::endl; } @@ -333,7 +333,7 @@ void ForceTorquePrivate::RemoveForceTorqueEntities( auto sensorId = this->entitySensorMap.find(_entity); if (sensorId == this->entitySensorMap.end()) { - ignerr << "Internal error, missing FT sensor for entity [" + gzerr << "Internal error, missing FT sensor for entity [" << _entity << "]" << std::endl; return true; } @@ -349,4 +349,7 @@ IGNITION_ADD_PLUGIN(ForceTorque, System, ForceTorque::ISystemPostUpdate ) +IGNITION_ADD_PLUGIN_ALIAS(ForceTorque, "gz::sim::systems::ForceTorque") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(ForceTorque, "ignition::gazebo::systems::ForceTorque") diff --git a/src/systems/force_torque/ForceTorque.hh b/src/systems/force_torque/ForceTorque.hh index 25b13aebfe..09b5b7ed70 100644 --- a/src/systems/force_torque/ForceTorque.hh +++ b/src/systems/force_torque/ForceTorque.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_FORCE_TORQUE_HH_ -#define IGNITION_GAZEBO_SYSTEMS_FORCE_TORQUE_HH_ +#ifndef GZ_SIM_SYSTEMS_FORCE_TORQUE_HH_ +#define GZ_SIM_SYSTEMS_FORCE_TORQUE_HH_ #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declarations. @@ -34,7 +34,7 @@ namespace systems /// \class ForceTorque ForceTorque.hh gz/sim/systems/ForceTorque.hh /// \brief This system manages all Force-Torque sensors in simulation. - /// Each FT sensor reports readings over Ignition Transport. + /// Each FT sensor reports readings over Gazebo Transport. /// \note Regardless of the setting of //sensor/force_torque/frame the point /// of application of the force is at the sensor's origin. /// //sensor/force_torque/frame only changes the coordinate frame in which the diff --git a/src/systems/hydrodynamics/Hydrodynamics.cc b/src/systems/hydrodynamics/Hydrodynamics.cc index ed3a6a5b61..3c8e115388 100644 --- a/src/systems/hydrodynamics/Hydrodynamics.cc +++ b/src/systems/hydrodynamics/Hydrodynamics.cc @@ -35,12 +35,12 @@ #include "Hydrodynamics.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; /// \brief Private Hydrodynamics data class. -class ignition::gazebo::systems::HydrodynamicsPrivateData +class gz::sim::systems::HydrodynamicsPrivateData { /// \brief Values to set via Plugin Parameters. /// Plugin Parameter: Added mass in surge, X_\dot{u}. @@ -127,50 +127,50 @@ class ignition::gazebo::systems::HydrodynamicsPrivateData void HydrodynamicsPrivateData::UpdateCurrent(const msgs::Vector3d &_msg) { std::lock_guard lock(this->mtx); - this->currentVector = ignition::msgs::Convert(_msg); + this->currentVector = gz::msgs::Convert(_msg); } ///////////////////////////////////////////////// void AddAngularVelocityComponent( - const ignition::gazebo::Entity &_entity, - ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::Entity &_entity, + gz::sim::EntityComponentManager &_ecm) { - if (!_ecm.Component(_entity)) + if (!_ecm.Component(_entity)) { _ecm.CreateComponent(_entity, - ignition::gazebo::components::AngularVelocity()); + gz::sim::components::AngularVelocity()); } // Create an angular velocity component if one is not present. - if (!_ecm.Component( + if (!_ecm.Component( _entity)) { _ecm.CreateComponent(_entity, - ignition::gazebo::components::WorldAngularVelocity()); + gz::sim::components::WorldAngularVelocity()); } } ///////////////////////////////////////////////// void AddWorldPose( - const ignition::gazebo::Entity &_entity, - ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::Entity &_entity, + gz::sim::EntityComponentManager &_ecm) { - if (!_ecm.Component(_entity)) + if (!_ecm.Component(_entity)) { - _ecm.CreateComponent(_entity, ignition::gazebo::components::WorldPose()); + _ecm.CreateComponent(_entity, gz::sim::components::WorldPose()); } } ///////////////////////////////////////////////// void AddWorldLinearVelocity( - const ignition::gazebo::Entity &_entity, - ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::Entity &_entity, + gz::sim::EntityComponentManager &_ecm) { - if (!_ecm.Component( + if (!_ecm.Component( _entity)) { _ecm.CreateComponent(_entity, - ignition::gazebo::components::WorldLinearVelocity()); + gz::sim::components::WorldLinearVelocity()); } } @@ -197,16 +197,16 @@ Hydrodynamics::~Hydrodynamics() ///////////////////////////////////////////////// void Hydrodynamics::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*/ ) { if (_sdf->HasElement("waterDensity")) { - ignwarn << - " parameter is deprecated and will be removed Ignition G.\n" + gzwarn << + " parameter is deprecated and will be removed Gazebo G.\n" << "\tPlease update your SDF to use instead."; } @@ -233,14 +233,14 @@ void Hydrodynamics::Configure( this->dataPtr->paramNrr = SdfParamDouble(_sdf, "nRR" , 0); // Create model object, to access convenient functions - auto model = ignition::gazebo::Model(_entity); + auto model = gz::sim::Model(_entity); std::string ns {""}; std::string currentTopic {"/ocean_current"}; if (_sdf->HasElement("namespace")) { ns = _sdf->Get("namespace"); - currentTopic = ignition::transport::TopicUtils::AsValidTopic( + currentTopic = gz::transport::TopicUtils::AsValidTopic( "/model/" + ns + "/ocean_current"); } @@ -251,7 +251,7 @@ void Hydrodynamics::Configure( if (!_sdf->HasElement("link_name")) { - ignerr << "You musk specify a for the hydrodynamic" + gzerr << "You musk specify a for the hydrodynamic" << " plugin to act upon"; return; } @@ -259,7 +259,7 @@ void Hydrodynamics::Configure( this->dataPtr->linkEntity = model.LinkByName(_ecm, linkName); if (!_ecm.HasEntity(this->dataPtr->linkEntity)) { - ignerr << "Link name" << linkName << "does not exist"; + gzerr << "Link name" << linkName << "does not exist"; return; } @@ -288,8 +288,8 @@ void Hydrodynamics::Configure( ///////////////////////////////////////////////// void Hydrodynamics::PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { if (_info.paused) return; @@ -307,14 +307,14 @@ void Hydrodynamics::PreUpdate( Eigen::MatrixXd Dmat = Eigen::MatrixXd::Zero(6, 6); // Get vehicle state - ignition::gazebo::Link baseLink(this->dataPtr->linkEntity); + gz::sim::Link baseLink(this->dataPtr->linkEntity); auto linearVelocity = _ecm.Component(this->dataPtr->linkEntity); auto rotationalVelocity = baseLink.WorldAngularVelocity(_ecm); if (!linearVelocity) { - ignerr << "no linear vel" <<"\n"; + gzerr << "no linear vel" <<"\n"; return; } @@ -389,9 +389,9 @@ void Hydrodynamics::PreUpdate( const Eigen::VectorXd kTotalWrench = kAmassVec + kDvec + kCmatVec; - ignition::math::Vector3d + gz::math::Vector3d totalForce(-kTotalWrench(0), -kTotalWrench(1), -kTotalWrench(2)); - ignition::math::Vector3d + gz::math::Vector3d totalTorque(-kTotalWrench(3), -kTotalWrench(4), -kTotalWrench(5)); baseLink.AddWorldWrench( @@ -406,6 +406,11 @@ IGNITION_ADD_PLUGIN( Hydrodynamics::ISystemPreUpdate ) +IGNITION_ADD_PLUGIN_ALIAS( + Hydrodynamics, + "gz::sim::systems::Hydrodynamics") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS( Hydrodynamics, "ignition::gazebo::systems::Hydrodynamics") diff --git a/src/systems/hydrodynamics/Hydrodynamics.hh b/src/systems/hydrodynamics/Hydrodynamics.hh index efac603151..71429e922e 100644 --- a/src/systems/hydrodynamics/Hydrodynamics.hh +++ b/src/systems/hydrodynamics/Hydrodynamics.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_HYDRODYNAMICS_HH_ -#define IGNITION_GAZEBO_SYSTEMS_HYDRODYNAMICS_HH_ +#ifndef GZ_SIM_SYSTEMS_HYDRODYNAMICS_HH_ +#define GZ_SIM_SYSTEMS_HYDRODYNAMICS_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { class HydrodynamicsPrivateData; @@ -89,12 +89,12 @@ namespace systems /// To control the rudder of the craft run the following /// ``` /// ign topic -t /model/tethys/joint/vertical_fins_joint/0/cmd_pos - /// -m ignition.msgs.Double -p 'data: -0.17' + /// -m gz.msgs.Double -p 'data: -0.17' /// ``` /// To apply a thrust you may run the following command /// ``` /// ign topic -t /model/tethys/joint/propeller_joint/cmd_pos - /// -m ignition.msgs.Double -p 'data: -31' + /// -m gz.msgs.Double -p 'data: -31' /// ``` /// The vehicle should move in a circle. /// @@ -103,7 +103,7 @@ namespace systems /// hydrodynamics plugin allows simulation of such currents. We can add /// a current simply by publishing the following: /// ``` - /// ign topic -t /ocean_current -m ignition.msgs.Vector3d -p 'x: 1, y:0, z:0' + /// ign topic -t /ocean_current -m gz.msgs.Vector3d -p 'x: 1, y:0, z:0' /// ``` /// You should observe your vehicle slowly drift to the side. /// @@ -111,9 +111,9 @@ namespace systems /// [1] Fossen, Thor I. _Guidance and Control of Ocean Vehicles_. /// United Kingdom: Wiley, 1994. class Hydrodynamics: - 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 Constructor public: Hydrodynamics(); @@ -123,15 +123,15 @@ namespace systems /// Documentation inherited public: void Configure( - const ignition::gazebo::Entity &_entity, + 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; /// 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/imu/Imu.cc b/src/systems/imu/Imu.cc index 2327c1c468..00a658e349 100644 --- a/src/systems/imu/Imu.cc +++ b/src/systems/imu/Imu.cc @@ -44,16 +44,16 @@ #include "gz/sim/EntityComponentManager.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace 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> entitySensorMap; + std::unique_ptr> entitySensorMap; /// \brief Ign-sensors sensor factory for creating sensors public: sensors::SensorFactory sensorFactory; @@ -65,7 +65,7 @@ class ignition::gazebo::systems::ImuPrivate /// \brief Keep track of world ID, which is equivalent to the scene's /// root visual. - /// Defaults to zero, which is considered invalid by Ignition Gazebo. + /// Defaults to zero, which is considered invalid by Gazebo. public: Entity worldEntity = kNullEntity; /// True if the rendering component is initialized @@ -116,7 +116,7 @@ void Imu::PreUpdate(const UpdateInfo &/*_info*/, auto it = this->dataPtr->entitySensorMap.find(entity); if (it == this->dataPtr->entitySensorMap.end()) { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] isn't in sensor map, this shouldn't happen." << std::endl; continue; } @@ -135,7 +135,7 @@ void Imu::PostUpdate(const UpdateInfo &_info, // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -168,7 +168,7 @@ void ImuPrivate::AddSensor( auto gravity = _ecm.Component(worldEntity); if (nullptr == gravity) { - ignerr << "World missing gravity." << std::endl; + gzerr << "World missing gravity." << std::endl; return; } @@ -188,7 +188,7 @@ void ImuPrivate::AddSensor( sensors::ImuSensor>(data); if (nullptr == sensor) { - ignerr << "Failed to create sensor [" << sensorScopedName << "]" + gzerr << "Failed to create sensor [" << sensorScopedName << "]" << std::endl; return; } @@ -217,7 +217,7 @@ void ImuPrivate::AddSensor( if (imuElementPtr->HasElement("orientation_reference_frame")) { double heading = 0.0; - ignition::gazebo::World world(worldEntity); + gz::sim::World world(worldEntity); if (world.SphericalCoordinates(_ecm)) { auto sphericalCoordinates = world.SphericalCoordinates(_ecm).value(); @@ -225,7 +225,7 @@ void ImuPrivate::AddSensor( } sensor->SetWorldFrameOrientation(math::Quaterniond(0, 0, heading), - ignition::sensors::WorldFrameEnumType::ENU); + gz::sensors::WorldFrameEnumType::ENU); } } @@ -250,7 +250,7 @@ void ImuPrivate::CreateSensors(const EntityComponentManager &_ecm) this->worldEntity = _ecm.EntityByComponents(components::World()); if (kNullEntity == this->worldEntity) { - ignerr << "Missing world entity." << std::endl; + gzerr << "Missing world entity." << std::endl; return; } @@ -309,7 +309,7 @@ void ImuPrivate::Update(const EntityComponentManager &_ecm) } else { - ignerr << "Failed to update IMU: " << _entity << ". " + gzerr << "Failed to update IMU: " << _entity << ". " << "Entity not found." << std::endl; } @@ -329,7 +329,7 @@ void ImuPrivate::RemoveImuEntities( auto sensorId = this->entitySensorMap.find(_entity); if (sensorId == this->entitySensorMap.end()) { - ignerr << "Internal error, missing IMU sensor for entity [" + gzerr << "Internal error, missing IMU sensor for entity [" << _entity << "]" << std::endl; return true; } @@ -345,4 +345,7 @@ IGNITION_ADD_PLUGIN(Imu, System, Imu::ISystemPostUpdate ) +IGNITION_ADD_PLUGIN_ALIAS(Imu, "gz::sim::systems::Imu") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(Imu, "ignition::gazebo::systems::Imu") diff --git a/src/systems/imu/Imu.hh b/src/systems/imu/Imu.hh index 0dc1c50555..828aa31e74 100644 --- a/src/systems/imu/Imu.hh +++ b/src/systems/imu/Imu.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_IMU_HH_ -#define IGNITION_GAZEBO_SYSTEMS_IMU_HH_ +#ifndef GZ_SIM_SYSTEMS_IMU_HH_ +#define GZ_SIM_SYSTEMS_IMU_HH_ #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declarations. @@ -35,7 +35,7 @@ namespace systems /// \class Imu Imu.hh gz/sim/systems/Imu.hh /// \brief This system manages all IMU sensors in simulation. /// Each IMU sensor eports vertical position, angular velocity - /// and lienar acceleration readings over Ignition Transport. + /// and lienar acceleration readings over Gazebo Transport. class Imu: public System, public ISystemPreUpdate, diff --git a/src/systems/joint_controller/JointController.cc b/src/systems/joint_controller/JointController.cc index 752568c43d..cb4dd947a5 100644 --- a/src/systems/joint_controller/JointController.cc +++ b/src/systems/joint_controller/JointController.cc @@ -31,15 +31,15 @@ #include "gz/sim/components/JointVelocityCmd.hh" #include "gz/sim/Model.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; -class ignition::gazebo::systems::JointControllerPrivate +class gz::sim::systems::JointControllerPrivate { /// \brief Callback for velocity subscription /// \param[in] _msg Velocity message - public: void OnCmdVel(const ignition::msgs::Double &_msg); + public: void OnCmdVel(const gz::msgs::Double &_msg); /// \brief Ignition communication node. public: transport::Node node; @@ -61,7 +61,7 @@ class ignition::gazebo::systems::JointControllerPrivate public: bool useForceCommands{false}; /// \brief Velocity PID controller. - public: ignition::math::PID velPid; + public: gz::math::PID velPid; }; ////////////////////////////////////////////////// @@ -80,7 +80,7 @@ void JointController::Configure(const Entity &_entity, if (!this->dataPtr->model.Valid(_ecm)) { - ignerr << "JointController plugin should be attached to a model entity. " + gzerr << "JointController plugin should be attached to a model entity. " << "Failed to initialize." << std::endl; return; } @@ -89,7 +89,7 @@ void JointController::Configure(const Entity &_entity, auto jointName = _sdf->Get("joint_name"); if (jointName.empty()) { - ignerr << "JointController found an empty jointName parameter. " + gzerr << "JointController found an empty jointName parameter. " << "Failed to initialize."; return; } @@ -98,7 +98,7 @@ void JointController::Configure(const Entity &_entity, jointName); if (this->dataPtr->jointEntity == kNullEntity) { - ignerr << "Joint with name[" << jointName << "] not found. " + gzerr << "Joint with name[" << jointName << "] not found. " << "The JointController may not control this joint.\n"; return; } @@ -106,7 +106,7 @@ void JointController::Configure(const Entity &_entity, if (_sdf->HasElement("initial_velocity")) { this->dataPtr->jointVelCmd = _sdf->Get("initial_velocity"); - ignmsg << "Joint velocity initialized to [" + gzmsg << "Joint velocity initialized to [" << this->dataPtr->jointVelCmd << "]" << std::endl; } @@ -127,19 +127,19 @@ void JointController::Configure(const Entity &_entity, this->dataPtr->velPid.Init(p, i, d, iMax, iMin, cmdMax, cmdMin, cmdOffset); - igndbg << "[JointController] Force mode with parameters:" << std::endl; - igndbg << "p_gain: [" << p << "]" << std::endl; - igndbg << "i_gain: [" << i << "]" << std::endl; - igndbg << "d_gain: [" << d << "]" << std::endl; - igndbg << "i_max: [" << iMax << "]" << std::endl; - igndbg << "i_min: [" << iMin << "]" << std::endl; - igndbg << "cmd_max: [" << cmdMax << "]" << std::endl; - igndbg << "cmd_min: [" << cmdMin << "]" << std::endl; - igndbg << "cmd_offset: [" << cmdOffset << "]" << std::endl; + gzdbg << "[JointController] Force mode with parameters:" << std::endl; + gzdbg << "p_gain: [" << p << "]" << std::endl; + gzdbg << "i_gain: [" << i << "]" << std::endl; + gzdbg << "d_gain: [" << d << "]" << std::endl; + gzdbg << "i_max: [" << iMax << "]" << std::endl; + gzdbg << "i_min: [" << iMin << "]" << std::endl; + gzdbg << "cmd_max: [" << cmdMax << "]" << std::endl; + gzdbg << "cmd_min: [" << cmdMin << "]" << std::endl; + gzdbg << "cmd_offset: [" << cmdOffset << "]" << std::endl; } else { - igndbg << "[JointController] Velocity mode" << std::endl; + gzdbg << "[JointController] Velocity mode" << std::endl; } // Subscribe to commands @@ -148,7 +148,7 @@ void JointController::Configure(const Entity &_entity, "/cmd_vel"); if (topic.empty()) { - ignerr << "Failed to create topic for joint [" << jointName + gzerr << "Failed to create topic for joint [" << jointName << "]" << std::endl; return; } @@ -159,7 +159,7 @@ void JointController::Configure(const Entity &_entity, if (topic.empty()) { - ignerr << "Failed to create topic [" << _sdf->Get("topic") + gzerr << "Failed to create topic [" << _sdf->Get("topic") << "]" << " for joint [" << jointName << "]" << std::endl; return; @@ -168,13 +168,13 @@ void JointController::Configure(const Entity &_entity, this->dataPtr->node.Subscribe(topic, &JointControllerPrivate::OnCmdVel, this->dataPtr.get()); - ignmsg << "JointController subscribing to Double messages on [" << topic + gzmsg << "JointController subscribing to Double messages on [" << topic << "]" << std::endl; } ////////////////////////////////////////////////// -void JointController::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void JointController::PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("JointController::PreUpdate"); @@ -185,7 +185,7 @@ void JointController::PreUpdate(const ignition::gazebo::UpdateInfo &_info, // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -260,9 +260,13 @@ void JointControllerPrivate::OnCmdVel(const msgs::Double &_msg) } IGNITION_ADD_PLUGIN(JointController, - ignition::gazebo::System, + gz::sim::System, 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 f2fbf9e968..23f10a81a3 100644 --- a/src/systems/joint_controller/JointController.hh +++ b/src/systems/joint_controller/JointController.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_JOINTCONTROLLER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_JOINTCONTROLLER_HH_ +#ifndef GZ_SIM_SYSTEMS_JOINTCONTROLLER_HH_ +#define GZ_SIM_SYSTEMS_JOINTCONTROLLER_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declaration @@ -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 7b6b7af711..bf6f36f766 100644 --- a/src/systems/joint_position_controller/JointPositionController.cc +++ b/src/systems/joint_position_controller/JointPositionController.cc @@ -32,15 +32,15 @@ #include "gz/sim/components/JointPosition.hh" #include "gz/sim/Model.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; -class ignition::gazebo::systems::JointPositionControllerPrivate +class gz::sim::systems::JointPositionControllerPrivate { /// \brief Callback for position subscription /// \param[in] _msg Position message - public: void OnCmdPos(const ignition::msgs::Double &_msg); + public: void OnCmdPos(const gz::msgs::Double &_msg); /// \brief Ignition communication node. public: transport::Node node; @@ -61,7 +61,7 @@ class ignition::gazebo::systems::JointPositionControllerPrivate public: Model model{kNullEntity}; /// \brief Position PID controller. - public: ignition::math::PID posPid; + public: gz::math::PID posPid; /// \brief Joint index to be used. public: unsigned int jointIndex = 0u; @@ -96,7 +96,7 @@ void JointPositionController::Configure(const Entity &_entity, if (!this->dataPtr->model.Valid(_ecm)) { - ignerr << "JointPositionController plugin should be attached to a model " + gzerr << "JointPositionController plugin should be attached to a model " << "entity. Failed to initialize." << std::endl; return; } @@ -106,7 +106,7 @@ void JointPositionController::Configure(const Entity &_entity, if (this->dataPtr->jointName == "") { - ignerr << "JointPositionController found an empty jointName parameter. " + gzerr << "JointPositionController found an empty jointName parameter. " << "Failed to initialize."; return; } @@ -182,7 +182,7 @@ void JointPositionController::Configure(const Entity &_entity, "/" + std::to_string(this->dataPtr->jointIndex) + "/cmd_pos"); if (topic.empty()) { - ignerr << "Failed to create topic for joint [" << this->dataPtr->jointName + gzerr << "Failed to create topic for joint [" << this->dataPtr->jointName << "]" << std::endl; return; } @@ -193,7 +193,7 @@ void JointPositionController::Configure(const Entity &_entity, if (topic.empty()) { - ignerr << "Failed to create topic [" << _sdf->Get("topic") + gzerr << "Failed to create topic [" << _sdf->Get("topic") << "]" << " for joint [" << this->dataPtr->jointName << "]" << std::endl; return; @@ -202,31 +202,31 @@ void JointPositionController::Configure(const Entity &_entity, this->dataPtr->node.Subscribe( topic, &JointPositionControllerPrivate::OnCmdPos, this->dataPtr.get()); - igndbg << "[JointPositionController] system parameters:" << std::endl; - igndbg << "p_gain: [" << p << "]" << std::endl; - igndbg << "i_gain: [" << i << "]" << std::endl; - igndbg << "d_gain: [" << d << "]" << std::endl; - igndbg << "i_max: [" << iMax << "]" << std::endl; - igndbg << "i_min: [" << iMin << "]" << std::endl; - igndbg << "cmd_max: [" << cmdMax << "]" << std::endl; - igndbg << "cmd_min: [" << cmdMin << "]" << std::endl; - igndbg << "cmd_offset: [" << cmdOffset << "]" << std::endl; - igndbg << "Topic: [" << topic << "]" << std::endl; - igndbg << "initial_position: [" << this->dataPtr->jointPosCmd << "]" + gzdbg << "[JointPositionController] system parameters:" << std::endl; + gzdbg << "p_gain: [" << p << "]" << std::endl; + gzdbg << "i_gain: [" << i << "]" << std::endl; + gzdbg << "d_gain: [" << d << "]" << std::endl; + gzdbg << "i_max: [" << iMax << "]" << std::endl; + gzdbg << "i_min: [" << iMin << "]" << std::endl; + gzdbg << "cmd_max: [" << cmdMax << "]" << std::endl; + gzdbg << "cmd_min: [" << cmdMin << "]" << std::endl; + gzdbg << "cmd_offset: [" << cmdOffset << "]" << std::endl; + gzdbg << "Topic: [" << topic << "]" << std::endl; + gzdbg << "initial_position: [" << this->dataPtr->jointPosCmd << "]" << std::endl; } ////////////////////////////////////////////////// void JointPositionController::PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("JointPositionController::PreUpdate"); // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -244,7 +244,7 @@ void JointPositionController::PreUpdate( { static bool warned = false; if(!warned) - ignerr << "Could not find joint with name [" + gzerr << "Could not find joint with name [" << this->dataPtr->jointName <<"]\n"; warned = true; return; @@ -273,7 +273,7 @@ void JointPositionController::PreUpdate( static std::unordered_set reported; if (reported.find(this->dataPtr->jointEntity) == reported.end()) { - ignerr << "[JointPositionController]: Detected an invalid " + gzerr << "[JointPositionController]: Detected an invalid " << "parameter. The index specified is [" << this->dataPtr->jointIndex << "] but joint [" << this->dataPtr->jointName << "] only has [" @@ -357,9 +357,13 @@ void JointPositionControllerPrivate::OnCmdPos(const msgs::Double &_msg) } IGNITION_ADD_PLUGIN(JointPositionController, - ignition::gazebo::System, + gz::sim::System, 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 eb508c4f84..6f80d15c14 100644 --- a/src/systems/joint_position_controller/JointPositionController.hh +++ b/src/systems/joint_position_controller/JointPositionController.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_JOINTPOSITIONCONTROLLER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_JOINTPOSITIONCONTROLLER_HH_ +#ifndef GZ_SIM_SYSTEMS_JOINTPOSITIONCONTROLLER_HH_ +#define GZ_SIM_SYSTEMS_JOINTPOSITIONCONTROLLER_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declaration @@ -34,11 +34,11 @@ namespace systems /// \brief Joint position controller which can be attached to a model with a /// reference to a single joint. /// - /// A new Ignition Transport topic is created to send target joint positions. + /// A new Gazebo Transport topic is created to send target joint positions. /// 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. If you wish to change the topic on which this plugin listens /// you may use the `` parameter to specify which topic the plugin /// should listen on. @@ -103,8 +103,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 2462b4fd28..9a4e9ae21d 100644 --- a/src/systems/joint_state_publisher/JointStatePublisher.cc +++ b/src/systems/joint_state_publisher/JointStatePublisher.cc @@ -36,8 +36,8 @@ #include "gz/sim/components/Pose.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; ////////////////////////////////////////////////// @@ -55,7 +55,7 @@ void JointStatePublisher::Configure( this->model = Model(_entity); if (!this->model.Valid(_ecm)) { - ignerr << "The JointStatePublisher system should be attached to a model " + gzerr << "The JointStatePublisher system should be attached to a model " << "entity. Failed to initialize." << std::endl; return; } @@ -69,14 +69,14 @@ void JointStatePublisher::Configure( while (elem) { std::string jointName = elem->Get(); - gazebo::Entity jointEntity = this->model.JointByName(_ecm, jointName); + sim::Entity jointEntity = this->model.JointByName(_ecm, jointName); if (jointEntity != kNullEntity) { this->CreateComponents(_ecm, jointEntity); } else { - ignerr << "Joint with name[" << jointName << "] not found. " + gzerr << "Joint with name[" << jointName << "] not found. " << "The JointStatePublisher will not publish this joint.\n"; } @@ -105,11 +105,11 @@ void JointStatePublisher::Configure( ////////////////////////////////////////////////// void JointStatePublisher::CreateComponents(EntityComponentManager &_ecm, - gazebo::Entity _joint) + sim::Entity _joint) { if (this->joints.find(_joint) != this->joints.end()) { - ignwarn << "Ignoring duplicate joint in a JointSatePublisher plugin.\n"; + gzwarn << "Ignoring duplicate joint in a JointSatePublisher plugin.\n"; return; } @@ -169,7 +169,7 @@ void JointStatePublisher::PostUpdate(const UpdateInfo &_info, this->topic = validTopic(topics); if (this->topic.empty()) { - ignerr << "No valid topics for JointStatePublisher could be found." + gzerr << "No valid topics for JointStatePublisher could be found." << "Make sure World/Model name does'nt contain invalid characters.\n"; return; } @@ -255,7 +255,7 @@ void JointStatePublisher::PostUpdate(const UpdateInfo &_info, } else if (!hasWarned) { - ignwarn << "Joint state publisher only supports two joint axis\n"; + gzwarn << "Joint state publisher only supports two joint axis\n"; hasWarned = true; } } @@ -278,7 +278,7 @@ void JointStatePublisher::PostUpdate(const UpdateInfo &_info, } else if (!hasWarned) { - ignwarn << "Joint state publisher only supports two joint axis\n"; + gzwarn << "Joint state publisher only supports two joint axis\n"; hasWarned = true; } } @@ -301,7 +301,7 @@ void JointStatePublisher::PostUpdate(const UpdateInfo &_info, } else if (!hasWarned) { - ignwarn << "Joint state publisher only supports two joint axis\n"; + gzwarn << "Joint state publisher only supports two joint axis\n"; hasWarned = true; } } @@ -313,9 +313,13 @@ void JointStatePublisher::PostUpdate(const UpdateInfo &_info, } IGNITION_ADD_PLUGIN(JointStatePublisher, - ignition::gazebo::System, + gz::sim::System, 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 d3d411300a..a6358da4b3 100644 --- a/src/systems/joint_state_publisher/JointStatePublisher.hh +++ b/src/systems/joint_state_publisher/JointStatePublisher.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_STATE_PUBLISHER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_STATE_PUBLISHER_HH_ +#ifndef GZ_SIM_SYSTEMS_STATE_PUBLISHER_HH_ +#define GZ_SIM_SYSTEMS_STATE_PUBLISHER_HH_ #include #include @@ -25,16 +25,16 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_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 @@ -70,7 +70,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); + sim::Entity _joint); /// \brief The model private: Model model; diff --git a/src/systems/joint_traj_control/JointTrajectoryController.cc b/src/systems/joint_traj_control/JointTrajectoryController.cc index c72ef9e457..a2bb01c549 100644 --- a/src/systems/joint_traj_control/JointTrajectoryController.cc +++ b/src/systems/joint_traj_control/JointTrajectoryController.cc @@ -41,8 +41,8 @@ #include "JointTrajectoryController.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; /// \brief Helper class that contains all parameters required to create and @@ -52,14 +52,14 @@ class JointParameters /// \brief Parse all parameters required for creation of ActuatedJoint and /// return them in a map /// \param[in] _sdf SDF reference used to obtain the parameters - /// \param[in] _ecm Ignition Entity Component Manager + /// \param[in] _ecm Gazebo Entity Component Manager /// \param[in] _enabledJoints List of joint entities that are enabled and /// need to be created /// \return Map of parameters for each joint, the first entry of pair /// indicates the joint name public: static std::map ParseAll( const std::shared_ptr &_sdf, - ignition::gazebo::EntityComponentManager &_ecm, + gz::sim::EntityComponentManager &_ecm, std::vector _enabledJoints); /// \brief Parse all values of a single parameter that is specified multiple @@ -149,22 +149,22 @@ class ActuatedJoint const JointParameters &_params); /// \brief Setup components required for control of this joint - /// \param[in,out] _ecm Ignition Entity Component Manager + /// \param[in,out] _ecm Gazebo Entity Component Manager public: void SetupComponents( - ignition::gazebo::EntityComponentManager &_ecm) const; + gz::sim::EntityComponentManager &_ecm) const; /// \brief Set target of the joint that the controller will attempt to reach /// \param[in] _targetPoint Targets of all controlled joint /// \param[in] _jointIndex Index of the joint, used to determine what index /// of `_targetPoint` to use public: void SetTarget( - const ignition::msgs::JointTrajectoryPoint &_targetPoint, + const gz::msgs::JointTrajectoryPoint &_targetPoint, const size_t &_jointIndex); /// \brief Update command force that is applied on the joint - /// \param[in,out] _ecm Ignition Entity Component Manager + /// \param[in,out] _ecm Gazebo Entity Component Manager /// \param[in] _dt Time difference to update for - public: void Update(ignition::gazebo::EntityComponentManager &_ecm, + public: void Update(gz::sim::EntityComponentManager &_ecm, const std::chrono::steady_clock::duration &_dt); /// \brief Reset the target of the joint @@ -197,9 +197,9 @@ class ActuatedJoint public: struct PIDs { /// \brief Position PID controller - ignition::math::PID position; + gz::math::PID position; /// \brief Velocity PID controller - ignition::math::PID velocity; + gz::math::PID velocity; } pids; }; @@ -250,11 +250,11 @@ class Trajectory /// \brief Trajectory defined in terms of temporal points, whose members are /// ordered according to `jointNames` - public: std::vector points; + public: std::vector points; }; /// \brief Private data of the JointTrajectoryController plugin -class ignition::gazebo::systems::JointTrajectoryControllerPrivate +class gz::sim::systems::JointTrajectoryControllerPrivate { /// \brief Get a list of enabled, unique, 1-axis joints of the model. If no /// joint names are specified in the plugin configuration, all valid 1-axis @@ -262,7 +262,7 @@ class ignition::gazebo::systems::JointTrajectoryControllerPrivate /// \param[in] _entity Entity of the model that the plugin is being /// configured for /// \param[in] _sdf SDF reference used to determine enabled joints - /// \param[in] _ecm Ignition Entity Component Manager + /// \param[in] _ecm Gazebo Entity Component Manager /// \return List of entities containinig all enabled joints public: std::vector GetEnabledJoints( const Entity &_entity, @@ -273,7 +273,7 @@ class ignition::gazebo::systems::JointTrajectoryControllerPrivate /// \param[in] _msg A new message describing a joint trajectory that needs /// to be followed public: void JointTrajectoryCallback( - const ignition::msgs::JointTrajectory &_msg); + const gz::msgs::JointTrajectory &_msg); /// \brief Reset internals of the plugin, without affecting already created /// components @@ -326,13 +326,13 @@ void JointTrajectoryController::Configure( const auto model = Model(_entity); if (!model.Valid(_ecm)) { - ignerr << "[JointTrajectoryController] Failed to initialize because [" + gzerr << "[JointTrajectoryController] Failed to initialize because [" << model.Name(_ecm) << "(Entity=" << _entity << ")] is not a model. Please make sure that" " JointTrajectoryController is attached to a valid model.\n"; return; } - ignmsg << "[JointTrajectoryController] Setting up controller for [" + gzmsg << "[JointTrajectoryController] Setting up controller for [" << model.Name(_ecm) << "(Entity=" << _entity << ")].\n"; // Get list of enabled joints @@ -350,14 +350,14 @@ void JointTrajectoryController::Configure( _ecm.Component(jointEntity)->Data(); this->dataPtr->actuatedJoints[jointName] = ActuatedJoint(jointEntity, jointParameters[jointName]); - ignmsg << "[JointTrajectoryController] Configured joint [" + gzmsg << "[JointTrajectoryController] Configured joint [" << jointName << "(Entity=" << jointEntity << ")].\n"; } // Make sure at least one joint is configured if (this->dataPtr->actuatedJoints.empty()) { - ignerr << "[JointTrajectoryController] Failed to initialize because [" + gzerr << "[JointTrajectoryController] Failed to initialize because [" << model.Name(_ecm) << "(Entity=" << _entity << ")] has no supported joints.\n"; return; @@ -386,12 +386,12 @@ void JointTrajectoryController::Configure( trajectoryTopic); if (validTrajectoryTopic.empty()) { - ignerr << "[JointTrajectoryController] Cannot subscribe to invalid topic [" + gzerr << "[JointTrajectoryController] Cannot subscribe to invalid topic [" << trajectoryTopic << "].\n"; return; } // Subscribe - ignmsg << "[JointTrajectoryController] Subscribing to joint trajectory" + gzmsg << "[JointTrajectoryController] Subscribing to joint trajectory" " commands on topic [" << validTrajectoryTopic << "].\n"; this->dataPtr->node.Subscribe( validTrajectoryTopic, @@ -400,16 +400,16 @@ void JointTrajectoryController::Configure( // Advertise progress const auto progressTopic = validTrajectoryTopic + "_progress"; - ignmsg << "[JointTrajectoryController] Advertising joint trajectory progress" + gzmsg << "[JointTrajectoryController] Advertising joint trajectory progress" " on topic [" << progressTopic << "].\n"; this->dataPtr->progressPub = - this->dataPtr->node.Advertise(progressTopic); + this->dataPtr->node.Advertise(progressTopic); } ////////////////////////////////////////////////// void JointTrajectoryController::PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("JointTrajectoryController::PreUpdate"); @@ -427,7 +427,7 @@ void JointTrajectoryController::PreUpdate( // Reset plugin if jump back in time is detected if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignmsg << "[JointTrajectoryController] Resetting plugin because jump back" + gzmsg << "[JointTrajectoryController] Resetting plugin because jump back" " in time [" << std::chrono::duration_cast(_info.dt).count() << " s] was detected.\n"; @@ -506,7 +506,7 @@ void JointTrajectoryController::PreUpdate( } // Publish current progress of the trajectory - ignition::msgs::Float progressMsg; + gz::msgs::Float progressMsg; progressMsg.set_data(this->dataPtr->trajectory.ComputeProgress()); this->dataPtr->progressPub.Publish(progressMsg); } @@ -548,13 +548,13 @@ std::vector JointTrajectoryControllerPrivate::GetEnabledJoints( // Check that model has exactly one joint that matches the name if (enabledJointEntity.empty()) { - ignerr << "[JointTrajectoryController] Model does not contain joint [" + gzerr << "[JointTrajectoryController] Model does not contain joint [" << enabledJointName << "], which was explicitly enabled.\n"; continue; } else if (enabledJointEntity.size() > 1) { - ignwarn << "[JointTrajectoryController] Model has " + gzwarn << "[JointTrajectoryController] Model has " << enabledJointEntity.size() << " duplicate joints named [" << enabledJointName << "]. Only the first (Entity=" << enabledJointEntity[0] << ") will be configured.\n"; @@ -579,7 +579,7 @@ std::vector JointTrajectoryControllerPrivate::GetEnabledJoints( { if (actuatedJoint.second.entity == jointEntity) { - ignwarn << "[JointTrajectoryController] Ignoring duplicate joint [" + gzwarn << "[JointTrajectoryController] Ignoring duplicate joint [" << jointName << "(Entity=" << jointEntity << ")].\n"; continue; } @@ -600,7 +600,7 @@ std::vector JointTrajectoryControllerPrivate::GetEnabledJoints( } case sdf::JointType::FIXED: { - igndbg << "[JointTrajectoryController] Fixed joint [" << jointName + gzdbg << "[JointTrajectoryController] Fixed joint [" << jointName << "(Entity=" << jointEntity << ")] is skipped.\n"; continue; } @@ -609,7 +609,7 @@ std::vector JointTrajectoryControllerPrivate::GetEnabledJoints( case sdf::JointType::BALL: case sdf::JointType::UNIVERSAL: { - ignwarn << "[JointTrajectoryController] Joint [" << jointName + gzwarn << "[JointTrajectoryController] Joint [" << jointName << "(Entity=" << jointEntity << ")] is of unsupported type. Only joints with a single axis" " are supported.\n"; @@ -617,7 +617,7 @@ std::vector JointTrajectoryControllerPrivate::GetEnabledJoints( } default: { - ignwarn << "[JointTrajectoryController] Joint [" << jointName + gzwarn << "[JointTrajectoryController] Joint [" << jointName << "(Entity=" << jointEntity << ")] is of unknown type.\n"; continue; } @@ -630,12 +630,12 @@ std::vector JointTrajectoryControllerPrivate::GetEnabledJoints( ////////////////////////////////////////////////// void JointTrajectoryControllerPrivate::JointTrajectoryCallback( - const ignition::msgs::JointTrajectory &_msg) + const gz::msgs::JointTrajectory &_msg) { // Make sure the message is valid if (_msg.joint_names_size() == 0) { - ignwarn << "[JointTrajectoryController] JointTrajectory message does not" + gzwarn << "[JointTrajectoryController] JointTrajectory message does not" " contain any joint names.\n"; return; } @@ -644,7 +644,7 @@ void JointTrajectoryControllerPrivate::JointTrajectoryCallback( // contains them if (_msg.points(0).accelerations_size() > 0) { - ignwarn << "[JointTrajectoryController] JointTrajectory message contains" + gzwarn << "[JointTrajectoryController] JointTrajectory message contains" " acceleration commands, which are currently ignored.\n"; } @@ -653,7 +653,7 @@ void JointTrajectoryControllerPrivate::JointTrajectoryCallback( if (this->trajectory.status != Trajectory::Reached) { - ignwarn << "[JointTrajectoryController] A new JointTrajectory message was" + gzwarn << "[JointTrajectoryController] A new JointTrajectory message was" " received while executing a previous trajectory.\n"; } @@ -711,7 +711,7 @@ void JointTrajectoryControllerPrivate::Reset() ////////////////////////////////////////////////// std::map JointParameters::ParseAll( const std::shared_ptr &_sdf, - ignition::gazebo::EntityComponentManager &_ecm, + gz::sim::EntityComponentManager &_ecm, std::vector _enabledJoints) { std::map output; @@ -855,7 +855,7 @@ ActuatedJoint::ActuatedJoint(const Entity &_entity, this->target.acceleration = 0.0; this->target.effort = 0.0; - this->pids.position = ignition::math::PID(_params.positionPID.pGain, + this->pids.position = gz::math::PID(_params.positionPID.pGain, _params.positionPID.iGain, _params.positionPID.dGain, _params.positionPID.iMax, @@ -864,7 +864,7 @@ ActuatedJoint::ActuatedJoint(const Entity &_entity, _params.positionPID.cmdMin, _params.positionPID.cmdOffset); - this->pids.velocity = ignition::math::PID(_params.velocityPID.pGain, + this->pids.velocity = gz::math::PID(_params.velocityPID.pGain, _params.velocityPID.iGain, _params.velocityPID.dGain, _params.velocityPID.iMax, @@ -873,7 +873,7 @@ ActuatedJoint::ActuatedJoint(const Entity &_entity, _params.velocityPID.cmdMin, _params.velocityPID.cmdOffset); - igndbg << "[JointTrajectoryController] Parameters for joint (Entity=" + gzdbg << "[JointTrajectoryController] Parameters for joint (Entity=" << _entity << "):\n" << "initial_position: [" << _params.initialPosition << "]\n" << "position_p_gain: [" << _params.positionPID.pGain << "]\n" @@ -896,7 +896,7 @@ ActuatedJoint::ActuatedJoint(const Entity &_entity, ////////////////////////////////////////////////// void ActuatedJoint::SetupComponents( - ignition::gazebo::EntityComponentManager &_ecm) const + gz::sim::EntityComponentManager &_ecm) const { // Create JointPosition component if one does not exist if (nullptr == _ecm.Component(this->entity)) @@ -919,7 +919,7 @@ void ActuatedJoint::SetupComponents( ////////////////////////////////////////////////// void ActuatedJoint::SetTarget( - const ignition::msgs::JointTrajectoryPoint &_targetPoint, + const gz::msgs::JointTrajectoryPoint &_targetPoint, const size_t &_jointIndex) { if ((signed)_jointIndex < _targetPoint.positions_size()) @@ -941,7 +941,7 @@ void ActuatedJoint::SetTarget( } ////////////////////////////////////////////////// -void ActuatedJoint::Update(ignition::gazebo::EntityComponentManager &_ecm, +void ActuatedJoint::Update(gz::sim::EntityComponentManager &_ecm, const std::chrono::steady_clock::duration &_dt) { // Get JointPosition and JointVelocity components @@ -1059,9 +1059,14 @@ void Trajectory::Reset() // Register plugin IGNITION_ADD_PLUGIN(JointTrajectoryController, - ignition::gazebo::System, + gz::sim::System, JointTrajectoryController::ISystemConfigure, JointTrajectoryController::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS( + JointTrajectoryController, + "gz::sim::systems::JointTrajectoryController") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS( JointTrajectoryController, "ignition::gazebo::systems::JointTrajectoryController") diff --git a/src/systems/joint_traj_control/JointTrajectoryController.hh b/src/systems/joint_traj_control/JointTrajectoryController.hh index 0caa15181a..68b51ce8fc 100644 --- a/src/systems/joint_traj_control/JointTrajectoryController.hh +++ b/src/systems/joint_traj_control/JointTrajectoryController.hh @@ -15,18 +15,18 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_JOINT_TRAJECTORY_CONTROLLER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_JOINT_TRAJECTORY_CONTROLLER_HH_ +#ifndef GZ_SIM_SYSTEMS_JOINT_TRAJECTORY_CONTROLLER_HH_ +#define GZ_SIM_SYSTEMS_JOINT_TRAJECTORY_CONTROLLER_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declaration @@ -35,11 +35,11 @@ namespace systems /// \brief Joint trajectory controller, which can be attached to a model with /// reference to one or more 1-axis joints in order to follow a trajectory. /// - /// Joint trajectories can be sent to this plugin via Ignition Transport. + /// Joint trajectories can be sent to this plugin via Gazebo Transport. /// The default topic name is "/model/${MODEL_NAME}/joint_trajectory" that /// can be configured with the `` system parameter. /// - /// This topic accepts ignition::msgs::JointTrajectory messages that represent + /// This topic accepts gz::msgs::JointTrajectory messages that represent /// a full trajectory, defined as temporal `points` with their fields ordered /// according to `joint_names` field. The fields under `points` are /// `positions` - Controlled by position PID controller for each joint @@ -54,7 +54,7 @@ namespace systems /// /// Input trajectory can be produced by a motion planning framework such as /// MoveIt2. For smooth execution of the trajectory, its points should to be - /// interpolated before sending them via Ignition Transport (interpolation + /// interpolated before sending them via Gazebo Transport (interpolation /// might already be implemented in the motion planning framework of your /// choice). /// @@ -150,15 +150,15 @@ 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; }; } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz #endif diff --git a/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.cc b/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.cc index f5f6ceeddf..21af42f5e0 100644 --- a/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.cc +++ b/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.cc @@ -39,12 +39,12 @@ #include "KineticEnergyMonitor.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace 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; @@ -84,7 +84,7 @@ void KineticEnergyMonitor::Configure(const Entity &_entity, if (!this->dataPtr->model.Valid(_ecm)) { - ignerr << "KineticEnergyMonitor should be attached to a model " + gzerr << "KineticEnergyMonitor should be attached to a model " << "entity. Failed to initialize." << std::endl; return; } @@ -100,7 +100,7 @@ void KineticEnergyMonitor::Configure(const Entity &_entity, if (linkName.empty()) { - ignerr << "found an empty parameter. Failed to initialize." + gzerr << "found an empty parameter. Failed to initialize." << std::endl; return; } @@ -110,7 +110,7 @@ void KineticEnergyMonitor::Configure(const Entity &_entity, if (this->dataPtr->linkEntity == kNullEntity) { - ignerr << "Link " << linkName + gzerr << "Link " << linkName << " could not be found. Failed to initialize.\n"; return; } @@ -122,7 +122,7 @@ void KineticEnergyMonitor::Configure(const Entity &_entity, "/kinetic_energy"}; std::string topic = sdfClone->Get("topic", defaultTopic).first; - ignmsg << "KineticEnergyMonitor publishing messages on " + gzmsg << "KineticEnergyMonitor publishing messages on " << "[" << topic << "]" << std::endl; transport::Node node; @@ -157,7 +157,7 @@ void KineticEnergyMonitor::PostUpdate(const UpdateInfo &_info, if (deltaKE > this->dataPtr->keThreshold) { - ignmsg << this->dataPtr->modelName + gzmsg << this->dataPtr->modelName << " Change in kinetic energy above threshold - deltaKE: " << deltaKE << std::endl; msgs::Double msg; @@ -169,9 +169,13 @@ void KineticEnergyMonitor::PostUpdate(const UpdateInfo &_info, } IGNITION_ADD_PLUGIN(KineticEnergyMonitor, - ignition::gazebo::System, + gz::sim::System, KineticEnergyMonitor::ISystemConfigure, 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 fa68062a00..595e31596d 100644 --- a/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.hh +++ b/src/systems/kinetic_energy_monitor/KineticEnergyMonitor.hh @@ -15,20 +15,20 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_KINETIC_ENERGY_MONITOR_HH_ -#define IGNITION_GAZEBO_SYSTEMS_KINETIC_ENERGY_MONITOR_HH_ +#ifndef GZ_SIM_SYSTEMS_KINETIC_ENERGY_MONITOR_HH_ +#define GZ_SIM_SYSTEMS_KINETIC_ENERGY_MONITOR_HH_ #include #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declarations. @@ -91,7 +91,7 @@ namespace systems + name="gz::sim::systems::KineticEnergyMonitor"> sphere_link 100 diff --git a/src/systems/label/Label.cc b/src/systems/label/Label.cc index 1f76d0bd0a..deff664d0f 100644 --- a/src/systems/label/Label.cc +++ b/src/systems/label/Label.cc @@ -28,8 +28,8 @@ #include "gz/sim/components/SemanticLabel.hh" #include "gz/sim/components/Visual.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; ////////////////////////////////////////////////// @@ -43,14 +43,14 @@ Label::~Label() = default; ////////////////////////////////////////////////// void Label::Configure(const Entity &_entity, const std::shared_ptr &_sdf, - gazebo::EntityComponentManager &_ecm, - gazebo::EventManager & /*_eventMgr*/) + sim::EntityComponentManager &_ecm, + sim::EventManager & /*_eventMgr*/) { const std::string labelTag = "label"; if (!_sdf->HasElement(labelTag)) { - ignerr << "Failed to load Label system; label tag not found.\n"; + gzerr << "Failed to load Label system; label tag not found.\n"; return; } @@ -58,7 +58,7 @@ void Label::Configure(const Entity &_entity, if (label < 0 || label > 255) { - ignerr << "Failed to configure Label system; value " << label + gzerr << "Failed to configure Label system; value " << label << " is not in [0-255] range.\n"; return; } @@ -74,7 +74,7 @@ void Label::Configure(const Entity &_entity, { // TODO(anyone) add support for nested models. We will need to check for // child models and their respective links/visuals - // https://github.com/ignitionrobotics/ign-gazebo/issues/1041 + // https://github.com/gazebosim/gz-sim/issues/1041 // Get link childern of parent model auto links = _ecm.ChildrenByComponents( @@ -96,11 +96,14 @@ void Label::Configure(const Entity &_entity, } else { - ignerr << "Entity [" << _entity << "] is not a visual, actor, or model. " + gzerr << "Entity [" << _entity << "] is not a visual, actor, or model. " << "Label will be ignored. \n"; return; } } IGNITION_ADD_PLUGIN(Label, System, Label::ISystemConfigure) +IGNITION_ADD_PLUGIN_ALIAS(Label, "gz::sim::systems::Label") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(Label, "ignition::gazebo::systems::Label") diff --git a/src/systems/label/Label.hh b/src/systems/label/Label.hh index 4f09d886de..1d29a06021 100644 --- a/src/systems/label/Label.hh +++ b/src/systems/label/Label.hh @@ -14,20 +14,20 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_LABEL_HH_ -#define IGNITION_GAZEBO_SYSTEMS_LABEL_HH_ +#ifndef GZ_SIM_SYSTEMS_LABEL_HH_ +#define GZ_SIM_SYSTEMS_LABEL_HH_ #include #include "gz/sim/config.hh" #include "gz/sim/System.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { /// \brief A label plugin that annotates models by setting the label @@ -50,7 +50,7 @@ namespace systems public: void Configure(const Entity &_entity, const std::shared_ptr &_sdf, EntityComponentManager &_ecm, - gazebo::EventManager &_eventMgr) final; + sim::EventManager &_eventMgr) final; }; } } diff --git a/src/systems/lift_drag/LiftDrag.cc b/src/systems/lift_drag/LiftDrag.cc index 6d5ca6d260..98a0f6e243 100644 --- a/src/systems/lift_drag/LiftDrag.cc +++ b/src/systems/lift_drag/LiftDrag.cc @@ -41,11 +41,11 @@ #include "gz/sim/components/ExternalWorldWrenchCmd.hh" #include "gz/sim/components/Pose.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; -class ignition::gazebo::systems::LiftDragPrivate +class gz::sim::systems::LiftDragPrivate { // Initialize the system public: void Load(const EntityComponentManager &_ecm, @@ -106,16 +106,16 @@ class ignition::gazebo::systems::LiftDragPrivate /// \brief center of pressure in link local coordinates with respect to the /// link's center of mass - public: ignition::math::Vector3d cp = math::Vector3d::Zero; + public: gz::math::Vector3d cp = math::Vector3d::Zero; /// \brief Normally, this is taken as a direction parallel to the chord /// of the airfoil in zero angle of attack forward flight. - public: ignition::math::Vector3d forward = math::Vector3d::UnitX; + public: gz::math::Vector3d forward = math::Vector3d::UnitX; /// \brief A vector in the lift/drag plane, perpendicular to the forward /// vector. Inflow velocity orthogonal to forward and upward vectors /// is considered flow in the wing sweep direction. - public: ignition::math::Vector3d upward = math::Vector3d::UnitZ; + public: gz::math::Vector3d upward = math::Vector3d::UnitZ; /// \brief how much to change CL per radian of control surface joint /// value. @@ -154,15 +154,15 @@ void LiftDragPrivate::Load(const EntityComponentManager &_ecm, this->radialSymmetry).first; this->area = _sdf->Get("area", this->area).first; this->alpha0 = _sdf->Get("a0", this->alpha0).first; - this->cp = _sdf->Get("cp", this->cp).first; + this->cp = _sdf->Get("cp", this->cp).first; // blade forward (-drag) direction in link frame this->forward = - _sdf->Get("forward", this->forward).first; + _sdf->Get("forward", this->forward).first; this->forward.Normalize(); // blade upward (+lift) direction in link frame - this->upward = _sdf->Get( + this->upward = _sdf->Get( "upward", this->upward) .first; this->upward.Normalize(); @@ -178,14 +178,14 @@ void LiftDragPrivate::Load(const EntityComponentManager &_ecm, if (entities.empty()) { - ignerr << "Link with name[" << linkName << "] not found. " + gzerr << "Link with name[" << linkName << "] not found. " << "The LiftDrag will not generate forces\n"; this->validConfig = false; return; } else if (entities.size() > 1) { - ignwarn << "Multiple link entities with name[" << linkName << "] found. " + gzwarn << "Multiple link entities with name[" << linkName << "] found. " << "Using the first one.\n"; } @@ -194,14 +194,14 @@ void LiftDragPrivate::Load(const EntityComponentManager &_ecm, components::Link::typeId)) { this->linkEntity = kNullEntity; - ignerr << "Entity with name[" << linkName << "] is not a link\n"; + gzerr << "Entity with name[" << linkName << "] is not a link\n"; this->validConfig = false; return; } } else { - ignerr << "The LiftDrag system requires the 'link_name' parameter\n"; + gzerr << "The LiftDrag system requires the 'link_name' parameter\n"; this->validConfig = false; return; } @@ -215,14 +215,14 @@ void LiftDragPrivate::Load(const EntityComponentManager &_ecm, if (entities.empty()) { - ignerr << "Joint with name[" << controlJointName << "] not found. " + gzerr << "Joint with name[" << controlJointName << "] not found. " << "The LiftDrag will not generate forces\n"; this->validConfig = false; return; } else if (entities.size() > 1) { - ignwarn << "Multiple joint entities with name[" << controlJointName + gzwarn << "Multiple joint entities with name[" << controlJointName << "] found. Using the first one.\n"; } @@ -231,7 +231,7 @@ void LiftDragPrivate::Load(const EntityComponentManager &_ecm, components::Joint::typeId)) { this->controlJointEntity = kNullEntity; - ignerr << "Entity with name[" << controlJointName << "] is not a joint\n"; + gzerr << "Entity with name[" << controlJointName << "] is not a joint\n"; this->validConfig = false; return; } @@ -281,12 +281,12 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) // rotate forward and upward vectors into world frame const auto forwardI = pose.Rot().RotateVector(this->forward); - ignition::math::Vector3d upwardI; + gz::math::Vector3d upwardI; if (this->radialSymmetry) { // use inflow velocity to determine upward direction // which is the component of inflow perpendicular to forward direction. - ignition::math::Vector3d tmp = forwardI.Cross(velI); + gz::math::Vector3d tmp = forwardI.Cross(velI); upwardI = forwardI.Cross(tmp).Normalize(); } else @@ -300,7 +300,7 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) const double minRatio = -1.0; const double maxRatio = 1.0; // check sweep (angle between velI and lift-drag-plane) - double sinSweepAngle = ignition::math::clamp( + double sinSweepAngle = gz::math::clamp( spanwiseI.Dot(velI), minRatio, maxRatio); // get cos from trig identity @@ -340,7 +340,7 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) // given upwardI and liftI are both unit vectors, we can drop the denominator // cos(theta) = a.Dot(b) const double cosAlpha = - ignition::math::clamp(liftI.Dot(upwardI), minRatio, maxRatio); + gz::math::clamp(liftI.Dot(upwardI), minRatio, maxRatio); // Is alpha positive or negative? Test: // forwardI points toward zero alpha @@ -389,7 +389,7 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) } // compute lift force at cp - ignition::math::Vector3d lift = cl * q * this->area * liftI; + gz::math::Vector3d lift = cl * q * this->area * liftI; // compute cd at cp, check for stall, correct for sweep double cd; @@ -412,7 +412,7 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) cd = std::fabs(cd); // drag at cp - ignition::math::Vector3d drag = cd * q * this->area * dragDirection; + gz::math::Vector3d drag = cd * q * this->area * dragDirection; // compute cm at cp, check for stall, correct for sweep double cm; @@ -441,12 +441,12 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) // compute moment (torque) at cp // spanwiseI used to be momentDirection - ignition::math::Vector3d moment = cm * q * this->area * spanwiseI; + gz::math::Vector3d moment = cm * q * this->area * spanwiseI; // force and torque about cg in world frame - ignition::math::Vector3d force = lift + drag; - ignition::math::Vector3d torque = moment; + gz::math::Vector3d force = lift + drag; + gz::math::Vector3d torque = moment; // Correct for nan or inf force.Correct(); this->cp.Correct(); @@ -472,27 +472,27 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) // Debug // auto linkName = _ecm.Component(this->linkEntity)->Data(); - // igndbg << "=============================\n"; - // igndbg << "Link: [" << linkName << "] pose: [" << pose + // gzdbg << "=============================\n"; + // gzdbg << "Link: [" << linkName << "] pose: [" << pose // << "] dynamic pressure: [" << q << "]\n"; - // igndbg << "spd: [" << vel.Length() << "] vel: [" << vel << "]\n"; - // igndbg << "LD plane spd: [" << velInLDPlane.Length() << "] vel : [" + // gzdbg << "spd: [" << vel.Length() << "] vel: [" << vel << "]\n"; + // gzdbg << "LD plane spd: [" << velInLDPlane.Length() << "] vel : [" // << velInLDPlane << "]\n"; - // igndbg << "forward (inertial): " << forwardI << "\n"; - // igndbg << "upward (inertial): " << upwardI << "\n"; - // igndbg << "q: " << q << "\n"; - // igndbg << "cl: " << cl << "\n"; - // igndbg << "lift dir (inertial): " << liftI << "\n"; - // igndbg << "Span direction (normal to LD plane): " << spanwiseI << "\n"; - // igndbg << "sweep: " << sweep << "\n"; - // igndbg << "alpha: " << alpha << "\n"; - // igndbg << "lift: " << lift << "\n"; - // igndbg << "drag: " << drag << " cd: " << cd << " cda: " + // gzdbg << "forward (inertial): " << forwardI << "\n"; + // gzdbg << "upward (inertial): " << upwardI << "\n"; + // gzdbg << "q: " << q << "\n"; + // gzdbg << "cl: " << cl << "\n"; + // gzdbg << "lift dir (inertial): " << liftI << "\n"; + // gzdbg << "Span direction (normal to LD plane): " << spanwiseI << "\n"; + // gzdbg << "sweep: " << sweep << "\n"; + // gzdbg << "alpha: " << alpha << "\n"; + // gzdbg << "lift: " << lift << "\n"; + // gzdbg << "drag: " << drag << " cd: " << cd << " cda: " // << this->cda << "\n"; - // igndbg << "moment: " << moment << "\n"; - // igndbg << "force: " << force << "\n"; - // igndbg << "torque: " << torque << "\n"; - // igndbg << "totalTorque: " << totalTorque << "\n"; + // gzdbg << "moment: " << moment << "\n"; + // gzdbg << "force: " << force << "\n"; + // gzdbg << "torque: " << torque << "\n"; + // gzdbg << "totalTorque: " << totalTorque << "\n"; } ////////////////////////////////////////////////// @@ -503,7 +503,7 @@ void LiftDrag::Configure(const Entity &_entity, this->dataPtr->model = Model(_entity); if (!this->dataPtr->model.Valid(_ecm)) { - ignerr << "The LiftDrag system should be attached to a model entity. " + gzerr << "The LiftDrag system should be attached to a model entity. " << "Failed to initialize." << std::endl; return; } @@ -518,7 +518,7 @@ void LiftDrag::PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ecm) // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -558,8 +558,11 @@ void LiftDrag::PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ecm) } IGNITION_ADD_PLUGIN(LiftDrag, - ignition::gazebo::System, + gz::sim::System, 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 943da2d398..efbed40502 100644 --- a/src/systems/lift_drag/LiftDrag.hh +++ b/src/systems/lift_drag/LiftDrag.hh @@ -15,18 +15,18 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_LIFT_DRAG_HH_ -#define IGNITION_GAZEBO_SYSTEMS_LIFT_DRAG_HH_ +#ifndef GZ_SIM_SYSTEMS_LIFT_DRAG_HH_ +#define GZ_SIM_SYSTEMS_LIFT_DRAG_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declaration diff --git a/src/systems/log/LogPlayback.cc b/src/systems/log/LogPlayback.cc index 13e5bcc67c..38da93369e 100644 --- a/src/systems/log/LogPlayback.cc +++ b/src/systems/log/LogPlayback.cc @@ -47,12 +47,12 @@ #include "gz/sim/components/Pose.hh" #include "gz/sim/components/World.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace 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. @@ -175,12 +175,12 @@ void LogPlayback::Configure(const Entity &, this->dataPtr->logPath.find_last_of(".") + 1)); if (extension != "zip") { - ignerr << "Please specify a zip file.\n"; + gzerr << "Please specify a zip file.\n"; return; } if (!this->dataPtr->ExtractStateAndResources()) { - ignerr << "Cannot play back files.\n"; + gzerr << "Cannot play back files.\n"; return; } } @@ -192,7 +192,7 @@ void LogPlayback::Configure(const Entity &, } else { - ignwarn << "A LogPlayback instance has already been started. " + gzwarn << "A LogPlayback instance has already been started. " << "Will not start another.\n"; } } @@ -202,23 +202,23 @@ bool LogPlaybackPrivate::Start(EntityComponentManager &_ecm) { if (LogPlaybackPrivate::started) { - ignwarn << "A LogPlayback instance has already been started. " + gzwarn << "A LogPlayback instance has already been started. " << "Will not start another.\n"; return true; } if (this->logPath.empty()) { - ignerr << "Unspecified log path to playback. Nothing to play.\n"; + gzerr << "Unspecified log path to playback. Nothing to play.\n"; return false; } // Append file name std::string dbPath = common::joinPaths(this->logPath, "state.tlog"); - ignmsg << "Loading log file [" + dbPath + "]\n"; + gzmsg << "Loading log file [" + dbPath + "]\n"; if (!common::exists(dbPath)) { - ignerr << "Log path invalid. File [" << dbPath << "] " + gzerr << "Log path invalid. File [" << dbPath << "] " << "does not exist. Nothing to play.\n"; return false; } @@ -227,7 +227,7 @@ bool LogPlaybackPrivate::Start(EntityComponentManager &_ecm) this->log = std::make_unique(); if (!this->log->Open(dbPath)) { - ignerr << "Failed to open log file [" << dbPath << "]" << std::endl; + gzerr << "Failed to open log file [" << dbPath << "]" << std::endl; } // Access all messages in .tlog file @@ -236,7 +236,7 @@ bool LogPlaybackPrivate::Start(EntityComponentManager &_ecm) if (iter == this->batch.end()) { - ignerr << "No messages found in log file [" << dbPath << "]" << std::endl; + gzerr << "No messages found in log file [" << dbPath << "]" << std::endl; } // Look for the first SerializedState message and use it to set the initial @@ -244,14 +244,14 @@ bool LogPlaybackPrivate::Start(EntityComponentManager &_ecm) for (; iter != this->batch.end(); ++iter) { auto msgType = iter->Type(); - if (msgType == "ignition.msgs.SerializedState") + if (msgType == "gz.msgs.SerializedState") { msgs::SerializedState msg; msg.ParseFromString(iter->Data()); this->Parse(_ecm, msg); break; } - else if (msgType == "ignition.msgs.SerializedStateMap") + else if (msgType == "gz.msgs.SerializedStateMap") { msgs::SerializedStateMap msg; msg.ParseFromString(iter->Data()); @@ -272,7 +272,7 @@ bool LogPlaybackPrivate::Start(EntityComponentManager &_ecm) auto worldEntity = _ecm.EntityByComponents(components::World()); if (kNullEntity == worldEntity) { - ignerr << "Missing world entity." << std::endl; + gzerr << "Missing world entity." << std::endl; return false; } @@ -436,7 +436,7 @@ bool LogPlaybackPrivate::ExtractStateAndResources() if (fuel_tools::Zip::Extract(this->logPath, this->extDest)) { - ignmsg << "Extracted recording to [" << this->extDest << "]" << std::endl; + gzmsg << "Extracted recording to [" << this->extDest << "]" << std::endl; // Replace value in variable with the directory of extracted files // Assume directory has same name as compressed file, without extension @@ -447,7 +447,7 @@ bool LogPlaybackPrivate::ExtractStateAndResources() } else { - ignerr << "Failed to extract recording to [" << this->extDest << "]" + gzerr << "Failed to extract recording to [" << this->extDest << "]" << std::endl; return false; } @@ -500,7 +500,14 @@ void LogPlayback::Update(const UpdateInfo &_info, EntityComponentManager &_ecm) { auto msgType = iter->Type(); - if (msgType == "ignition.msgs.SerializedState") + // Support ignition.msgs for backwards compatibility, don't remove on tock + // so users can use logs across versions + if (msgType.find("ignition.msgs") == 0) + { + msgType.replace(0, 8, "gz"); + } + + if (msgType == "gz.msgs.SerializedState") { msgs::SerializedState msg; msg.ParseFromString(iter->Data()); @@ -526,7 +533,7 @@ void LogPlayback::Update(const UpdateInfo &_info, EntityComponentManager &_ecm) this->dataPtr->Parse(_ecm, msg); } - else if (msgType == "ignition.msgs.SerializedStateMap") + else if (msgType == "gz.msgs.SerializedStateMap") { msgs::SerializedStateMap msg; msg.ParseFromString(iter->Data()); @@ -553,13 +560,13 @@ void LogPlayback::Update(const UpdateInfo &_info, EntityComponentManager &_ecm) this->dataPtr->Parse(_ecm, msg); } - else if (msgType == "ignition.msgs.StringMsg") + else if (msgType == "gz.msgs.StringMsg") { // Do nothing, we assume this is the SDF string } else { - ignwarn << "Trying to playback unsupported message type [" + gzwarn << "Trying to playback unsupported message type [" << msgType << "]" << std::endl; } this->dataPtr->ReplaceResourceURIs(_ecm); @@ -601,7 +608,7 @@ void LogPlayback::Update(const UpdateInfo &_info, EntityComponentManager &_ecm) // pause playback if end of log is reached if (_info.simTime >= this->dataPtr->log->EndTime()) { - ignmsg << "End of log file reached. Time: " << + gzmsg << "End of log file reached. Time: " << std::chrono::duration_cast( this->dataPtr->log->EndTime()).count() << " seconds" << std::endl; @@ -609,10 +616,14 @@ void LogPlayback::Update(const UpdateInfo &_info, EntityComponentManager &_ecm) } } -IGNITION_ADD_PLUGIN(ignition::gazebo::systems::LogPlayback, - ignition::gazebo::System, +IGNITION_ADD_PLUGIN(gz::sim::systems::LogPlayback, + gz::sim::System, LogPlayback::ISystemConfigure, LogPlayback::ISystemUpdate) -IGNITION_ADD_PLUGIN_ALIAS(ignition::gazebo::systems::LogPlayback, +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 737884c3a7..3d49f6195c 100644 --- a/src/systems/log/LogPlayback.hh +++ b/src/systems/log/LogPlayback.hh @@ -14,20 +14,20 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_LOGPLAYBACK_HH_ -#define IGNITION_GAZEBO_SYSTEMS_LOGPLAYBACK_HH_ +#ifndef GZ_SIM_SYSTEMS_LOGPLAYBACK_HH_ +#define GZ_SIM_SYSTEMS_LOGPLAYBACK_HH_ #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declarations. diff --git a/src/systems/log/LogRecord.cc b/src/systems/log/LogRecord.cc index 35bbf5b3f0..a0961f83e4 100644 --- a/src/systems/log/LogRecord.cc +++ b/src/systems/log/LogRecord.cc @@ -60,12 +60,12 @@ #include "gz/sim/Util.hh" -using namespace ignition; -using namespace ignition::gazebo; -using namespace ignition::gazebo::systems; +using namespace gz; +using namespace gz::sim; +using namespace gz::sim::systems; // Private data class. -class ignition::gazebo::systems::LogRecordPrivate +class gz::sim::systems::LogRecordPrivate { /// \brief Start recording /// \param[in] _logPath Path to record to. @@ -193,7 +193,7 @@ LogRecord::~LogRecord() this->dataPtr->savedModels.clear(); LogRecordPrivate::started = false; - ignmsg << "Stopping recording" << std::endl; + gzmsg << "Stopping recording" << std::endl; } } @@ -222,14 +222,14 @@ void LogRecord::Configure(const Entity &_entity, // SDF, initialize to default here. if (logPath.empty()) { - logPath = ignLogDirectory(); + logPath = gzLogDirectory(); } this->dataPtr->Start(logPath, this->dataPtr->cmpPath); } else { - ignwarn << "A LogRecord instance has already been started. " + gzwarn << "A LogRecord instance has already been started. " << "Will not start another.\n"; } } @@ -241,7 +241,7 @@ bool LogRecordPrivate::Start(const std::string &_logPath, // Only start one recorder instance if (LogRecordPrivate::started) { - ignwarn << "A LogRecord instance has already been started. " + gzwarn << "A LogRecord instance has already been started. " << "Will not start another.\n"; return true; } @@ -263,7 +263,7 @@ bool LogRecordPrivate::Start(const std::string &_logPath, if (this->logPath.empty() || (common::exists(this->logPath) && !common::isDirectory(this->logPath))) { - ignerr << "Unspecified or invalid log path[" << this->logPath << "]. " + gzerr << "Unspecified or invalid log path[" << this->logPath << "]. " << "Recording will not take place." << std::endl; return false; } @@ -272,7 +272,7 @@ bool LogRecordPrivate::Start(const std::string &_logPath, if (this->recordResources) { - ignmsg << "Resources will be recorded\n"; + gzmsg << "Resources will be recorded\n"; } // Create log directory @@ -291,7 +291,7 @@ bool LogRecordPrivate::Start(const std::string &_logPath, } else { - ignerr << "Failed to generate valid topic to publish SDF. Tried [" + gzerr << "Failed to generate valid topic to publish SDF. Tried [" << sdfTopic << "]." << std::endl; } @@ -305,7 +305,7 @@ bool LogRecordPrivate::Start(const std::string &_logPath, } else { - ignerr << "Failed to generate valid topic to publish state. Tried [" + gzerr << "Failed to generate valid topic to publish state. Tried [" << stateTopic << "]." << std::endl; } @@ -313,14 +313,14 @@ bool LogRecordPrivate::Start(const std::string &_logPath, std::string dbPath = common::joinPaths(this->logPath, "state.tlog"); if (common::exists(dbPath)) { - ignmsg << "Overwriting existing file [" << dbPath << "]\n"; + gzmsg << "Overwriting existing file [" << dbPath << "]\n"; common::removeFile(dbPath); } - ignmsg << "Recording to log file [" << dbPath << "]" << std::endl; + gzmsg << "Recording to log file [" << dbPath << "]" << std::endl; // Add default topics if no topics were specified. - igndbg << "Recording default topic[" << sdfTopic << "].\n"; - igndbg << "Recording default topic[" << stateTopic << "].\n"; + gzdbg << "Recording default topic[" << sdfTopic << "].\n"; + gzdbg << "Recording default topic[" << stateTopic << "].\n"; this->recorder.AddTopic(sdfTopic); this->recorder.AddTopic(stateTopic); @@ -338,12 +338,12 @@ bool LogRecordPrivate::Start(const std::string &_logPath, if (std::regex_match(topic, regexMatch)) { this->recorder.AddTopic(std::regex(topic)); - igndbg << "Recording topic[" << topic << "] as regular expression.\n"; + gzdbg << "Recording topic[" << topic << "] as regular expression.\n"; } else { this->recorder.AddTopic(topic); - igndbg << "Recording topic[" << topic << "] as plain topic.\n"; + gzdbg << "Recording topic[" << topic << "] as plain topic.\n"; } recordTopicElem = recordTopicElem->GetNextElement("record_topic"); } @@ -359,7 +359,7 @@ bool LogRecordPrivate::Start(const std::string &_logPath, // This calls Log::Open() and loads sql schema if (this->recorder.Start(dbPath) == - ignition::transport::log::RecorderError::SUCCESS) + gz::transport::log::RecorderError::SUCCESS) { this->instStarted = true; return true; @@ -428,7 +428,7 @@ void LogRecordPrivate::LogModelResources(const EntityComponentManager &_ecm) if (!this->SaveModels(modelSdfPaths)) { - ignwarn << "Failed to save model resources during logging\n"; + gzwarn << "Failed to save model resources during logging\n"; } } @@ -487,7 +487,7 @@ bool LogRecordPrivate::SaveModels(const std::set &_models) } else { - ignerr << "Saving resource files at URI pointing to outside the model " + gzerr << "Saving resource files at URI pointing to outside the model " << "directory is currently not supported [" << rt << "]" << std::endl; saveError = true; @@ -586,7 +586,7 @@ bool LogRecordPrivate::SaveModels(const std::set &_models) if (!common::createDirectories(destPath) || !common::copyDirectory(srcPath, destPath)) { - ignerr << "Failed to copy model directory from [" << srcPath + gzerr << "Failed to copy model directory from [" << srcPath << "] to [" << destPath << "]" << std::endl; saveError = true; } @@ -600,7 +600,7 @@ bool LogRecordPrivate::SaveModels(const std::set &_models) } else { - ignerr << "File: " << file << " not found!" << std::endl; + gzerr << "File: " << file << " not found!" << std::endl; saveError = true; } } @@ -613,14 +613,14 @@ void LogRecordPrivate::CompressStateAndResources() { if (common::exists(this->cmpPath)) { - ignmsg << "Removing existing file [" << this->cmpPath << "].\n"; + gzmsg << "Removing existing file [" << this->cmpPath << "].\n"; common::removeFile(this->cmpPath); } // Compress directory if (fuel_tools::Zip::Compress(this->logPath, this->cmpPath)) { - ignmsg << "Compressed log file and resources to [" << this->cmpPath + gzmsg << "Compressed log file and resources to [" << this->cmpPath << "].\nRemoving recorded directory [" << this->logPath << "]." << std::endl; // Remove directory after compressing successfully @@ -628,7 +628,7 @@ void LogRecordPrivate::CompressStateAndResources() } else { - ignerr << "Failed to compress log file and resources to [" + gzerr << "Failed to compress log file and resources to [" << this->cmpPath << "]. Keeping recorded directory [" << this->logPath << "]." << std::endl; } @@ -658,7 +658,7 @@ void LogRecord::PostUpdate(const UpdateInfo &_info, // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -670,14 +670,14 @@ void LogRecord::PostUpdate(const UpdateInfo &_info, auto worldEntity = _ecm.EntityByComponents(components::World()); if (worldEntity == kNullEntity) { - ignerr << "Could not find the world entity\n"; + gzerr << "Could not find the world entity\n"; } else { auto worldSdfComp = _ecm.Component(worldEntity); if (worldSdfComp == nullptr || worldSdfComp->Data().Element() == nullptr) { - ignerr << "Could not load world SDF data\n"; + gzerr << "Could not load world SDF data\n"; } else { @@ -706,11 +706,15 @@ void LogRecord::PostUpdate(const UpdateInfo &_info, this->dataPtr->LogModelResources(_ecm); } -IGNITION_ADD_PLUGIN(ignition::gazebo::systems::LogRecord, - ignition::gazebo::System, +IGNITION_ADD_PLUGIN(gz::sim::systems::LogRecord, + gz::sim::System, LogRecord::ISystemConfigure, LogRecord::ISystemPreUpdate, LogRecord::ISystemPostUpdate) -IGNITION_ADD_PLUGIN_ALIAS(ignition::gazebo::systems::LogRecord, +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 ed40cee293..680e015720 100644 --- a/src/systems/log/LogRecord.hh +++ b/src/systems/log/LogRecord.hh @@ -14,20 +14,20 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_LOGRECORD_HH_ -#define IGNITION_GAZEBO_SYSTEMS_LOGRECORD_HH_ +#ifndef GZ_SIM_SYSTEMS_LOGRECORD_HH_ +#define GZ_SIM_SYSTEMS_LOGRECORD_HH_ #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declarations. diff --git a/src/systems/log_video_recorder/LogVideoRecorder.cc b/src/systems/log_video_recorder/LogVideoRecorder.cc index 1f8ea7495f..ceef758be2 100644 --- a/src/systems/log_video_recorder/LogVideoRecorder.cc +++ b/src/systems/log_video_recorder/LogVideoRecorder.cc @@ -40,12 +40,12 @@ using namespace std::chrono_literals; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; // Private data class. -class ignition::gazebo::systems::LogVideoRecorderPrivate +class gz::sim::systems::LogVideoRecorderPrivate { /// \brief Rewind the log public: void Rewind(); @@ -209,7 +209,7 @@ void LogVideoRecorder::Configure( std::chrono::milliseconds ms(static_cast(t * 1000.0)); if (this->dataPtr->startTime > ms) { - ignerr << " cannot be larger than " << std::endl; + gzerr << " cannot be larger than " << std::endl; } else { @@ -282,7 +282,7 @@ void LogVideoRecorder::PostUpdate(const UpdateInfo &_info, { if (_info.paused) { - igndbg << "Warning: Playback is either manually paused or " + gzdbg << "Warning: Playback is either manually paused or " << "is smaller than total log playback time!" << std::endl; } @@ -339,7 +339,7 @@ void LogVideoRecorder::PostUpdate(const UpdateInfo &_info, { // No more models to record. if (this->dataPtr->statusMsg.data().empty()) - igndbg << "Finish Recording" << std::endl; + gzdbg << "Finish Recording" << std::endl; this->dataPtr->statusMsg.set_data("end"); this->dataPtr->statusPub.Publish(this->dataPtr->statusMsg); @@ -365,18 +365,18 @@ void LogVideoRecorder::PostUpdate(const UpdateInfo &_info, // rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - igndbg << "Detected Rewind." << std::endl; + gzdbg << "Detected Rewind." << std::endl; } } ////////////////////////////////////////////////// void LogVideoRecorderPrivate::Rewind() { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error sending rewind request" << std::endl; + gzerr << "Error sending rewind request" << std::endl; }; @@ -384,7 +384,7 @@ void LogVideoRecorderPrivate::Rewind() req.set_rewind(true); if (this->node.Request(this->playbackControlService, req, cb)) { - igndbg << "Rewind Playback " << std::endl; + gzdbg << "Rewind Playback " << std::endl; this->rewindRequested = true; } } @@ -393,38 +393,38 @@ void LogVideoRecorderPrivate::Rewind() void LogVideoRecorderPrivate::Play() { this->eventManager->Emit(false); - igndbg << "Play log " << std::endl; + gzdbg << "Play log " << std::endl; } ////////////////////////////////////////////////// void LogVideoRecorderPrivate::Follow(const std::string &_entity) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error sending follow request" << std::endl; + gzerr << "Error sending follow request" << std::endl; }; - ignition::msgs::StringMsg req; + gz::msgs::StringMsg req; req.set_data(_entity); if (this->node.Request(this->followService, req, cb)) { - igndbg << "Following entity: " << _entity << std::endl; + gzdbg << "Following entity: " << _entity << std::endl; } } ////////////////////////////////////////////////// void LogVideoRecorderPrivate::Record(bool _record) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const gz::msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) - ignerr << "Error sending record request" << std::endl; + gzerr << "Error sending record request" << std::endl; }; - ignition::msgs::VideoRecord req; + gz::msgs::VideoRecord req; if (_record) { @@ -432,11 +432,11 @@ void LogVideoRecorderPrivate::Record(bool _record) req.set_start(true); req.set_format(this->videoFormat); req.set_save_filename(filename); - igndbg << "Recording video " << filename << std::endl; + gzdbg << "Recording video " << filename << std::endl; } else { - igndbg << "Stopping video recorder" << std::endl; + gzdbg << "Stopping video recorder" << std::endl; req.set_stop(true); this->recordStopRequested = true; this->recordStopTime = std::chrono::system_clock::now(); @@ -445,11 +445,15 @@ void LogVideoRecorderPrivate::Record(bool _record) } IGNITION_ADD_PLUGIN(LogVideoRecorder, - ignition::gazebo::System, + gz::sim::System, LogVideoRecorder::ISystemConfigure, LogVideoRecorder::ISystemPostUpdate) // 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 7168d81a95..b55d28f76c 100644 --- a/src/systems/log_video_recorder/LogVideoRecorder.hh +++ b/src/systems/log_video_recorder/LogVideoRecorder.hh @@ -14,20 +14,20 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_LOGVIDEORECORDER_SYSTEM_HH_ -#define IGNITION_GAZEBO_LOGVIDEORECORDER_SYSTEM_HH_ +#ifndef GZ_SIM_LOGVIDEORECORDER_SYSTEM_HH_ +#define GZ_SIM_LOGVIDEORECORDER_SYSTEM_HH_ #include #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { class LogVideoRecorderPrivate; diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudio.cc b/src/systems/logical_audio_sensor_plugin/LogicalAudio.cc index 3568bd3c4a..2e44d5c9d4 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudio.cc +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudio.cc @@ -22,12 +22,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace logical_audio { /// \brief A map to help convert user-input strings to the proper @@ -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; @@ -152,5 +152,5 @@ namespace logical_audio } } // namespace logical_audio } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudio.hh b/src/systems/logical_audio_sensor_plugin/LogicalAudio.hh index 2e535d9e0c..248bff62d9 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudio.hh +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudio.hh @@ -14,8 +14,8 @@ * 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_SIM_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_LOGICALAUDIO_HH_ +#define GZ_SIM_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_LOGICALAUDIO_HH_ #include @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace logical_audio { /// \brief Determines if an audio device can detect volume at a certain level. @@ -42,7 +42,7 @@ namespace logical_audio /// device with a higher detection threshold. /// \return true if the listening device can detect volume at _volumeLevel, /// false otherwise. - IGNITION_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE + GZ_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE bool detect(double _volumeLevel, double _volumeDetectionThreshold); /// \brief Computes the volume level of an audio source at a certain location. @@ -63,15 +63,15 @@ namespace logical_audio /// \return The volume level at this location. /// If the attenuation function or shape is undefined, -1.0 is returned. /// If the source is not playing, 0.0 is returned. - IGNITION_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE + GZ_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE double computeVolume(bool _playing, AttenuationFunction _attenuationFunc, AttenuationShape _attenuationShape, 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 @@ -86,7 +86,7 @@ namespace logical_audio /// the calculated attenuation function. /// \param[in] _str A string that should map to a value in /// AttenuationFunction. - IGNITION_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE + GZ_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE void setAttenuationFunction(AttenuationFunction &_attenuationFunc, std::string _str); @@ -102,7 +102,7 @@ namespace logical_audio /// calculated attenuation shape. /// \param[in] _str A string that should map to a value in /// AttenuationShape. - IGNITION_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE + GZ_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE void setAttenuationShape(AttenuationShape &_attenuationShape, std::string _str); @@ -115,7 +115,7 @@ namespace logical_audio /// source. This value must be greater than _innerRadius. /// If _falloffDistance < _innerRadius, _falloffDistance will be set to /// _innerRadius + 1 (assuming that _innerRadius is valid). - IGNITION_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE + GZ_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE void validateInnerRadiusAndFalloffDistance(double &_innerRadius, double &_falloffDistance); @@ -123,7 +123,7 @@ namespace logical_audio /// \param[in,out] _volumeLevel The volume the source should play at. /// This parameter is checked (and possibly clipped) to ensure that it falls /// between 0.0 (0% volume) and 1.0 (100% volume). - IGNITION_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE + GZ_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE void validateVolumeLevel(double &_volumeLevel); } } diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc index 3e3eae42ec..3974438a43 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc @@ -39,11 +39,11 @@ #include #include "LogicalAudio.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace 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. @@ -78,7 +78,7 @@ class ignition::gazebo::systems::LogicalAudioSensorPluginPrivate const logical_audio::SourcePlayInfo &_sourcePlayInfo); /// \brief Node used to create publishers and services - public: ignition::transport::Node node; + public: gz::transport::Node node; /// \brief A flag used to initialize a source's playing information /// before starting simulation. @@ -97,7 +97,7 @@ class ignition::gazebo::systems::LogicalAudioSensorPluginPrivate /// (an entity can have multiple microphones attached to it). /// The value is the microphone's detection publisher. public: std::unordered_map micEntities; + gz::transport::Node::Publisher> micEntities; /// \brief A mutex used to ensure that the play source service call does /// not interfere with the source's state in the PreUpdate step. @@ -240,7 +240,7 @@ void LogicalAudioSensorPlugin::PostUpdate(const UpdateInfo &_info, // publish the source that the microphone heard, along with the // volume level the microphone detected. The detected source's // ID is embedded in the message's header - ignition::msgs::Double msg; + gz::msgs::Double msg; auto header = msg.mutable_header(); auto timeStamp = header->mutable_stamp(); timeStamp->set_sec(simSeconds.count()); @@ -270,7 +270,7 @@ void LogicalAudioSensorPluginPrivate::CreateAudioSource( if (!_elem->HasElement("id")) { - ignerr << "Audio source is missing an id. " << kSourceSkipMsg; + gzerr << "Audio source is missing an id. " << kSourceSkipMsg; return; } const auto id = _elem->Get("id"); @@ -278,62 +278,62 @@ void LogicalAudioSensorPluginPrivate::CreateAudioSource( // make sure no other sources exist with the same ID in the parent if (_ids.find(id) != _ids.end()) { - ignerr << "The specified source ID of " << id << " already exists for " + gzerr << "The specified source ID of " << id << " already exists for " << "another source in entity " << _parent << ". " << kSourceSkipMsg; return; } _ids.insert(id); - ignition::math::Pose3d pose; + gz::math::Pose3d pose; if (!_elem->HasElement("pose")) { - ignwarn << "Audio source is missing a pose. " + gzwarn << "Audio source is missing a pose. " << "{0.0, 0.0, 0.0, 0.0, 0.0, 0.0} will be used.\n"; pose = {0.0, 0.0, 0.0, 0.0, 0.0, 0.0}; } else { - pose = _elem->Get("pose"); + pose = _elem->Get("pose"); } if (!_elem->HasElement("attenuation_function")) { - ignerr << "Audio source has no attenuation function. " << kSourceSkipMsg; + gzerr << "Audio source has no attenuation function. " << kSourceSkipMsg; return; } const auto attenuationFunc = _elem->Get("attenuation_function"); if (!_elem->HasElement("attenuation_shape")) { - ignerr << "Audio source has no attenuation shape. " << kSourceSkipMsg; + gzerr << "Audio source has no attenuation shape. " << kSourceSkipMsg; return; } const auto attenuationShape = _elem->Get("attenuation_shape"); if (!_elem->HasElement("inner_radius")) { - ignerr << "Audio source has no inner radius. " << kSourceSkipMsg; + gzerr << "Audio source has no inner radius. " << kSourceSkipMsg; return; } const auto innerRadius = _elem->Get("inner_radius"); if (!_elem->HasElement("falloff_distance")) { - ignerr << "Audio source is missing a falloff distance. " << kSourceSkipMsg; + gzerr << "Audio source is missing a falloff distance. " << kSourceSkipMsg; return; } const auto falloffDistance = _elem->Get("falloff_distance"); if (!_elem->HasElement("volume_level")) { - ignerr << "Audio source is missing a volume level. " << kSourceSkipMsg; + gzerr << "Audio source is missing a volume level. " << kSourceSkipMsg; return; } const auto volumeLevel = _elem->Get("volume_level"); if (!_elem->HasElement("playing")) { - ignerr << "Audio source is missing the playing attribute. " + gzerr << "Audio source is missing the playing attribute. " << kSourceSkipMsg; return; } @@ -341,7 +341,7 @@ void LogicalAudioSensorPluginPrivate::CreateAudioSource( if (!_elem->HasElement("play_duration")) { - ignerr << "Audio source is missing the play duration. " << kSourceSkipMsg; + gzerr << "Audio source is missing the play duration. " << kSourceSkipMsg; return; } const auto playDuration = _elem->Get("play_duration"); @@ -350,7 +350,7 @@ void LogicalAudioSensorPluginPrivate::CreateAudioSource( auto entity = _ecm.CreateEntity(); if (entity == kNullEntity) { - ignerr << "Failed to create a logical audio source entity. " + gzerr << "Failed to create a logical audio source entity. " << kSourceSkipMsg; return; } @@ -385,16 +385,16 @@ void LogicalAudioSensorPluginPrivate::CreateAudioSource( components::LogicalAudioSourcePlayInfo(playInfo)); // create service callbacks that allow this source to be played/stopped - std::function playSrvCb = - [this, entity](ignition::msgs::Boolean &_resp) + std::function playSrvCb = + [this, entity](gz::msgs::Boolean &_resp) { std::lock_guard lock(this->playSourceMutex); this->sourceEntities[entity].first = true; _resp.set_data(true); return true; }; - std::function stopSrvCb = - [this, entity](ignition::msgs::Boolean &_resp) + std::function stopSrvCb = + [this, entity](gz::msgs::Boolean &_resp) { std::lock_guard lock(this->stopSourceMutex); this->sourceEntities[entity].second = true; @@ -407,19 +407,19 @@ void LogicalAudioSensorPluginPrivate::CreateAudioSource( auto validName = transport::TopicUtils::AsValidTopic(fullName); if (validName.empty()) { - ignerr << "Failed to create valid topics with entity scoped name [" + gzerr << "Failed to create valid topics with entity scoped name [" << fullName << "]" << std::endl; return; } if (!this->node.Advertise(validName + "/play", playSrvCb)) { - ignerr << "Error advertising the play source service for source " + gzerr << "Error advertising the play source service for source " << id << " in entity " << _parent << ". " << kSourceSkipMsg; return; } if (!this->node.Advertise(validName + "/stop", stopSrvCb)) { - ignerr << "Error advertising the stop source service for source " + gzerr << "Error advertising the stop source service for source " << id << " in entity " << _parent << ". " << kSourceSkipMsg; return; } @@ -440,7 +440,7 @@ void LogicalAudioSensorPluginPrivate::CreateMicrophone( if (!_elem->HasElement("id")) { - ignerr << "Microphone is missing an id. " << kMicSkipMsg; + gzerr << "Microphone is missing an id. " << kMicSkipMsg; return; } const auto id = _elem->Get("id"); @@ -448,28 +448,28 @@ void LogicalAudioSensorPluginPrivate::CreateMicrophone( // make sure no other microphones exist with the same ID in the parent if (_ids.find(id) != _ids.end()) { - ignerr << "The specified microphone ID of " << id << " already exists for " + gzerr << "The specified microphone ID of " << id << " already exists for " << "another microphone in entity " << _parent << ". " << kMicSkipMsg; return; } _ids.insert(id); - ignition::math::Pose3d pose; + gz::math::Pose3d pose; if (!_elem->HasElement("pose")) { - ignwarn << "Microphone is missing a pose. " + gzwarn << "Microphone is missing a pose. " << "{0.0, 0.0, 0.0, 0.0, 0.0, 0.0} will be used.\n"; pose = {0.0, 0.0, 0.0, 0.0, 0.0, 0.0}; } else { - pose = _elem->Get("pose"); + pose = _elem->Get("pose"); } double volumeDetectionThreshold; if (!_elem->HasElement("volume_threshold")) { - ignwarn << "Microphone is missing a volume threshold. 0.0 will be used.\n"; + gzwarn << "Microphone is missing a volume threshold. 0.0 will be used.\n"; volumeDetectionThreshold = 0.0; } else @@ -481,7 +481,7 @@ void LogicalAudioSensorPluginPrivate::CreateMicrophone( auto entity = _ecm.CreateEntity(); if (entity == kNullEntity) { - ignerr << "Failed to create a logical audio microphone entity. " + gzerr << "Failed to create a logical audio microphone entity. " << kMicSkipMsg; return; } @@ -501,11 +501,11 @@ void LogicalAudioSensorPluginPrivate::CreateMicrophone( components::Pose(pose)); // create the detection publisher for this microphone - auto pub = this->node.Advertise( + auto pub = this->node.Advertise( scopedName(entity, _ecm) + "/detection"); if (!pub) { - ignerr << "Error creating a detection publisher for microphone " + gzerr << "Error creating a detection publisher for microphone " << id << " in entity " << _parent << ". " << kMicSkipMsg; return; } @@ -526,10 +526,14 @@ bool LogicalAudioSensorPluginPrivate::DurationExceeded( } IGNITION_ADD_PLUGIN(LogicalAudioSensorPlugin, - ignition::gazebo::System, + gz::sim::System, LogicalAudioSensorPlugin::ISystemConfigure, 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 ee0bfe7275..968a1ca879 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_HH_ -#define IGNITION_GAZEBO_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_HH_ +#ifndef GZ_SIM_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_HH_ +#define GZ_SIM_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward Declaration @@ -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 c18bb4913f..57b813ae05 100644 --- a/src/systems/logical_camera/LogicalCamera.cc +++ b/src/systems/logical_camera/LogicalCamera.cc @@ -46,12 +46,12 @@ #include "gz/sim/EntityComponentManager.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace 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_mapdataPtr->entitySensorMap.find(entity); if (it == this->dataPtr->entitySensorMap.end()) { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] isn't in sensor map, this shouldn't happen." << std::endl; continue; } @@ -133,7 +133,7 @@ void LogicalCamera::PostUpdate(const UpdateInfo &_info, // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -178,7 +178,7 @@ void LogicalCameraPrivate::AddLogicalCamera( sensors::LogicalCameraSensor>(data); if (nullptr == sensor) { - ignerr << "Failed to create sensor [" << sensorScopedName << "]" + gzerr << "Failed to create sensor [" << sensorScopedName << "]" << std::endl; return; } @@ -265,7 +265,7 @@ void LogicalCameraPrivate::UpdateLogicalCameras( } else { - ignerr << "Failed to update logicalCamera: " << _entity << ". " + gzerr << "Failed to update logicalCamera: " << _entity << ". " << "Entity not found." << std::endl; } @@ -285,7 +285,7 @@ void LogicalCameraPrivate::RemoveLogicalCameraEntities( auto sensorIt = this->entitySensorMap.find(_entity); if (sensorIt == this->entitySensorMap.end()) { - ignerr << "Internal error, missing logicalCamera sensor for entity [" + gzerr << "Internal error, missing logicalCamera sensor for entity [" << _entity << "]" << std::endl; return true; } @@ -301,6 +301,9 @@ IGNITION_ADD_PLUGIN(LogicalCamera, System, LogicalCamera::ISystemPostUpdate ) +IGNITION_ADD_PLUGIN_ALIAS(LogicalCamera, + "gz::sim::systems::LogicalCamera") +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(LogicalCamera, "ignition::gazebo::systems::LogicalCamera") diff --git a/src/systems/logical_camera/LogicalCamera.hh b/src/systems/logical_camera/LogicalCamera.hh index 8670bb800e..3c4f569b13 100644 --- a/src/systems/logical_camera/LogicalCamera.hh +++ b/src/systems/logical_camera/LogicalCamera.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_LOGICALCAMERA_HH_ -#define IGNITION_GAZEBO_SYSTEMS_LOGICALCAMERA_HH_ +#ifndef GZ_SIM_SYSTEMS_LOGICALCAMERA_HH_ +#define GZ_SIM_SYSTEMS_LOGICALCAMERA_HH_ #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declarations. diff --git a/src/systems/magnetometer/Magnetometer.cc b/src/systems/magnetometer/Magnetometer.cc index cf4c0db30d..9d54231155 100644 --- a/src/systems/magnetometer/Magnetometer.cc +++ b/src/systems/magnetometer/Magnetometer.cc @@ -43,16 +43,16 @@ #include "gz/sim/EntityComponentManager.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace 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> entitySensorMap; + std::unique_ptr> entitySensorMap; /// \brief Ign-sensors sensor factory for creating sensors public: sensors::SensorFactory sensorFactory; @@ -113,7 +113,7 @@ void Magnetometer::PreUpdate(const UpdateInfo &/*_info*/, auto it = this->dataPtr->entitySensorMap.find(entity); if (it == this->dataPtr->entitySensorMap.end()) { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] isn't in sensor map, this shouldn't happen." << std::endl; continue; } @@ -132,7 +132,7 @@ void Magnetometer::PostUpdate(const UpdateInfo &_info, // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -178,7 +178,7 @@ void MagnetometerPrivate::AddMagnetometer( sensors::MagnetometerSensor>(data); if (nullptr == sensor) { - ignerr << "Failed to create sensor [" << sensorScopedName << "]" + gzerr << "Failed to create sensor [" << sensorScopedName << "]" << std::endl; return; } @@ -210,7 +210,7 @@ void MagnetometerPrivate::CreateSensors(const EntityComponentManager &_ecm) auto worldEntity = _ecm.EntityByComponents(components::World()); if (kNullEntity == worldEntity) { - ignerr << "Missing world entity." << std::endl; + gzerr << "Missing world entity." << std::endl; return; } @@ -218,7 +218,7 @@ void MagnetometerPrivate::CreateSensors(const EntityComponentManager &_ecm) auto worldField = _ecm.Component(worldEntity); if (nullptr == worldField) { - ignerr << "World missing magnetic field." << std::endl; + gzerr << "World missing magnetic field." << std::endl; return; } @@ -271,7 +271,7 @@ void MagnetometerPrivate::Update( } else { - ignerr << "Failed to update magnetometer: " << _entity << ". " + gzerr << "Failed to update magnetometer: " << _entity << ". " << "Entity not found." << std::endl; } @@ -291,7 +291,7 @@ void MagnetometerPrivate::RemoveMagnetometerEntities( auto sensorId = this->entitySensorMap.find(_entity); if (sensorId == this->entitySensorMap.end()) { - ignerr << "Internal error, missing magnetometer sensor for entity [" + gzerr << "Internal error, missing magnetometer sensor for entity [" << _entity << "]" << std::endl; return true; } @@ -307,5 +307,9 @@ IGNITION_ADD_PLUGIN(Magnetometer, System, Magnetometer::ISystemPostUpdate ) +IGNITION_ADD_PLUGIN_ALIAS(Magnetometer, + "gz::sim::systems::Magnetometer") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(Magnetometer, "ignition::gazebo::systems::Magnetometer") diff --git a/src/systems/magnetometer/Magnetometer.hh b/src/systems/magnetometer/Magnetometer.hh index 8feda59e5e..854eb44a3b 100644 --- a/src/systems/magnetometer/Magnetometer.hh +++ b/src/systems/magnetometer/Magnetometer.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_MAGNETOMETER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_MAGNETOMETER_HH_ +#ifndef GZ_SIM_SYSTEMS_MAGNETOMETER_HH_ +#define GZ_SIM_SYSTEMS_MAGNETOMETER_HH_ #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declarations. diff --git a/src/systems/mecanum_drive/MecanumDrive.cc b/src/systems/mecanum_drive/MecanumDrive.cc index 3b1ff40312..d873627ac4 100644 --- a/src/systems/mecanum_drive/MecanumDrive.cc +++ b/src/systems/mecanum_drive/MecanumDrive.cc @@ -39,8 +39,8 @@ #include "gz/sim/Model.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; /// \brief Velocity command. @@ -58,18 +58,18 @@ struct Commands Commands() : lin(0.0), lat(0.0), ang(0.0) {} }; -class ignition::gazebo::systems::MecanumDrivePrivate +class gz::sim::systems::MecanumDrivePrivate { /// \brief Callback for velocity subscription /// \param[in] _msg Velocity message - public: void OnCmdVel(const ignition::msgs::Twist &_msg); + public: void OnCmdVel(const gz::msgs::Twist &_msg); /// \brief Update the linear and angular velocities. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateVelocity(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateVelocity(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm); /// \brief Ignition communication node. public: transport::Node node; @@ -141,10 +141,10 @@ class ignition::gazebo::systems::MecanumDrivePrivate public: transport::Node::Publisher tfPub; /// \brief Linear velocity limiter. - public: std::unique_ptr limiterLin; + public: std::unique_ptr limiterLin; /// \brief Angular velocity limiter. - public: std::unique_ptr limiterAng; + public: std::unique_ptr limiterAng; /// \brief Previous control command. public: Commands last0Cmd; @@ -187,7 +187,7 @@ void MecanumDrive::Configure(const Entity &_entity, if (!this->dataPtr->model.Valid(_ecm)) { - ignerr << "MecanumDrive plugin should be attached to a model entity. " + gzerr << "MecanumDrive plugin should be attached to a model entity. " << "Failed to initialize." << std::endl; return; } @@ -231,8 +231,8 @@ void MecanumDrive::Configure(const Entity &_entity, this->dataPtr->wheelRadius).first; // Instantiate the speed limiters. - this->dataPtr->limiterLin = std::make_unique(); - this->dataPtr->limiterAng = std::make_unique(); + this->dataPtr->limiterLin = std::make_unique(); + this->dataPtr->limiterAng = std::make_unique(); // Parse speed limiter parameters. if (_sdf->HasElement("min_velocity")) @@ -321,20 +321,20 @@ void MecanumDrive::Configure(const Entity &_entity, if (_sdf->HasElement("child_frame_id")) this->dataPtr->sdfChildFrameId = _sdf->Get("child_frame_id"); - ignmsg << "MecanumDrive subscribing to twist messages on [" << topic << "]" + gzmsg << "MecanumDrive subscribing to twist messages on [" << topic << "]" << std::endl; } ////////////////////////////////////////////////// -void MecanumDrive::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void MecanumDrive::PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("MecanumDrive::PreUpdate"); // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -355,7 +355,7 @@ void MecanumDrive::PreUpdate(const ignition::gazebo::UpdateInfo &_info, this->dataPtr->frontLeftJoints.push_back(joint); else if (warnedModels.find(modelName) == warnedModels.end()) { - ignwarn << "Failed to find left joint [" << name << "] for model [" + gzwarn << "Failed to find left joint [" << name << "] for model [" << modelName << "]" << std::endl; warned = true; } @@ -368,7 +368,7 @@ void MecanumDrive::PreUpdate(const ignition::gazebo::UpdateInfo &_info, this->dataPtr->frontRightJoints.push_back(joint); else if (warnedModels.find(modelName) == warnedModels.end()) { - ignwarn << "Failed to find right joint [" << name << "] for model [" + gzwarn << "Failed to find right joint [" << name << "] for model [" << modelName << "]" << std::endl; warned = true; } @@ -381,7 +381,7 @@ void MecanumDrive::PreUpdate(const ignition::gazebo::UpdateInfo &_info, this->dataPtr->backLeftJoints.push_back(joint); else if (warnedModels.find(modelName) == warnedModels.end()) { - ignwarn << "Failed to find left joint [" << name << "] for model [" + gzwarn << "Failed to find left joint [" << name << "] for model [" << modelName << "]" << std::endl; warned = true; } @@ -394,7 +394,7 @@ void MecanumDrive::PreUpdate(const ignition::gazebo::UpdateInfo &_info, this->dataPtr->backRightJoints.push_back(joint); else if (warnedModels.find(modelName) == warnedModels.end()) { - ignwarn << "Failed to find right joint [" << name << "] for model [" + gzwarn << "Failed to find right joint [" << name << "] for model [" << modelName << "]" << std::endl; warned = true; } @@ -416,7 +416,7 @@ void MecanumDrive::PreUpdate(const ignition::gazebo::UpdateInfo &_info, if (warnedModels.find(modelName) != warnedModels.end()) { - ignmsg << "Found joints for model [" << modelName + gzmsg << "Found joints for model [" << modelName << "], plugin will start working." << std::endl; warnedModels.erase(modelName); } @@ -505,8 +505,8 @@ void MecanumDrive::PostUpdate(const UpdateInfo &_info, ////////////////////////////////////////////////// void MecanumDrivePrivate::UpdateVelocity( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &/*_ecm*/) + const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &/*_ecm*/) { IGN_PROFILE("MecanumDrive::UpdateVelocity"); @@ -560,10 +560,14 @@ void MecanumDrivePrivate::OnCmdVel(const msgs::Twist &_msg) } IGNITION_ADD_PLUGIN(MecanumDrive, - ignition::gazebo::System, + gz::sim::System, MecanumDrive::ISystemConfigure, MecanumDrive::ISystemPreUpdate, MecanumDrive::ISystemPostUpdate) +IGNITION_ADD_PLUGIN_ALIAS(MecanumDrive, + "gz::sim::systems::MecanumDrive") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(MecanumDrive, "ignition::gazebo::systems::MecanumDrive") diff --git a/src/systems/mecanum_drive/MecanumDrive.hh b/src/systems/mecanum_drive/MecanumDrive.hh index 38b7e342fe..4cc910eee1 100644 --- a/src/systems/mecanum_drive/MecanumDrive.hh +++ b/src/systems/mecanum_drive/MecanumDrive.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_MECANUMDRIVE_HH_ -#define IGNITION_GAZEBO_SYSTEMS_MECANUMDRIVE_HH_ +#ifndef GZ_SIM_SYSTEMS_MECANUMDRIVE_HH_ +#define GZ_SIM_SYSTEMS_MECANUMDRIVE_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declaration @@ -78,14 +78,14 @@ namespace systems /// /// ``: Custom `frame_id` field that this system will use as the /// origin of the odometry transform in both the `` - /// `ignition.msgs.Pose_V` message and the `` - /// `ignition.msgs.Odometry` message. This element if optional, and the + /// `gz.msgs.Pose_V` message and the `` + /// `gz.msgs.Odometry` message. This element if optional, and the /// default value is `{name_of_model}/odom`. /// /// ``: Custom `child_frame_id` that this system will use as /// the target of the odometry trasnform in both the `` - /// `ignition.msgs.Pose_V` message and the `` - /// `ignition.msgs.Odometry` message. This element if optional, + /// `gz.msgs.Pose_V` message and the `` + /// `gz.msgs.Odometry` message. This element if optional, /// and the default value is `{name_of_model}/{name_of_link}`. class MecanumDrive : public System, @@ -107,8 +107,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/model_photo_shoot/ModelPhotoShoot.cc b/src/systems/model_photo_shoot/ModelPhotoShoot.cc index 65182115cc..0408093bd4 100644 --- a/src/systems/model_photo_shoot/ModelPhotoShoot.cc +++ b/src/systems/model_photo_shoot/ModelPhotoShoot.cc @@ -38,32 +38,32 @@ #include "gz/sim/rendering/Events.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; /// \brief Private ModelPhotoShoot data class. -class ignition::gazebo::systems::ModelPhotoShootPrivate +class gz::sim::systems::ModelPhotoShootPrivate { /// \brief Callback for pos rendering operations. public: void PerformPostRenderingOperations(); /// \brief Save a pitcture with the camera from the given pose. - public: void SavePicture (const ignition::rendering::CameraPtr _camera, - const ignition::math::Pose3d &_pose, + public: void SavePicture (const gz::rendering::CameraPtr _camera, + const gz::math::Pose3d &_pose, const std::string &_fileName) const; /// \brief Name of the loaded model. public: std::string modelName; /// \brief model - public: std::shared_ptr model; + public: std::shared_ptr model; /// \brief model world pose - public: ignition::math::Pose3d modelPose3D; + public: gz::math::Pose3d modelPose3D; /// \brief Connection to pre-render event callback. - public: ignition::common::ConnectionPtr connection{nullptr}; + public: gz::common::ConnectionPtr connection{nullptr}; /// \brief Boolean to control we only take the pictures once. public: bool takePicture{true}; @@ -82,21 +82,21 @@ ModelPhotoShoot::ModelPhotoShoot() } ////////////////////////////////////////////////// -void ModelPhotoShoot::Configure(const ignition::gazebo::Entity &_entity, +void ModelPhotoShoot::Configure(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) { std::string saveDataLocation = _sdf->Get("translation_data_file"); if (saveDataLocation.empty()) { - igndbg << "No data location specified, skipping translaiton data" + gzdbg << "No data location specified, skipping translaiton data" "saving.\n"; } else { - igndbg << "Saving translation data to: " + gzdbg << "Saving translation data to: " << saveDataLocation << std::endl; this->dataPtr->savingFile.open(saveDataLocation); } @@ -107,25 +107,25 @@ void ModelPhotoShoot::Configure(const ignition::gazebo::Entity &_entity, } this->dataPtr->connection = - _eventMgr.Connect(std::bind( + _eventMgr.Connect(std::bind( &ModelPhotoShootPrivate::PerformPostRenderingOperations, this->dataPtr.get())); - this->dataPtr->model = std::make_shared(_entity); + this->dataPtr->model = std::make_shared(_entity); this->dataPtr->modelName = this->dataPtr->model->Name(_ecm); // Get the pose of the model this->dataPtr->modelPose3D = - ignition::gazebo::worldPose(this->dataPtr->model->Entity(), _ecm); + gz::sim::worldPose(this->dataPtr->model->Entity(), _ecm); } ////////////////////////////////////////////////// void ModelPhotoShoot::PreUpdate( - const ignition::gazebo::UpdateInfo &, - ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::UpdateInfo &, + gz::sim::EntityComponentManager &_ecm) { if (this->dataPtr->randomPoses) { - std::vector joints = this->dataPtr->model->Joints(_ecm); + std::vector joints = this->dataPtr->model->Joints(_ecm); unsigned seed = std::chrono::system_clock::now().time_since_epoch().count(); std::default_random_engine generator(seed); @@ -168,25 +168,25 @@ void ModelPhotoShoot::PreUpdate( } else { - ignerr << "No jointAxisComp found, ignoring joint: " << + gzerr << "No jointAxisComp found, ignoring joint: " << jointNameComp->Data() << std::endl; } } else { - ignerr << "Model Photo Shoot only supports single axis joints. " + gzerr << "Model Photo Shoot only supports single axis joints. " "Skipping joint: "<< jointNameComp->Data() << std::endl; } } else { - igndbg << "Ignoring fixed joint: " << jointNameComp->Data() << + gzdbg << "Ignoring fixed joint: " << jointNameComp->Data() << std::endl; } } else { - ignerr << "No jointNameComp found on entity: " << joint << + gzerr << "No jointNameComp found on entity: " << joint << std:: endl; } } @@ -198,19 +198,19 @@ void ModelPhotoShoot::PreUpdate( ////////////////////////////////////////////////// void ModelPhotoShootPrivate::PerformPostRenderingOperations() { - ignition::rendering::ScenePtr scene = - ignition::rendering::sceneFromFirstRenderEngine(); - ignition::rendering::VisualPtr modelVisual = + gz::rendering::ScenePtr scene = + gz::rendering::sceneFromFirstRenderEngine(); + gz::rendering::VisualPtr modelVisual = scene->VisualByName(this->modelName); - ignition::rendering::VisualPtr root = scene->RootVisual(); + gz::rendering::VisualPtr root = scene->RootVisual(); if (modelVisual && this->takePicture) { scene->SetAmbientLight(0.3, 0.3, 0.3); // create directional light - ignition::rendering::DirectionalLightPtr light0 = + gz::rendering::DirectionalLightPtr light0 = scene->CreateDirectionalLight(); light0->SetDirection(-0.5, 0.5, -1); light0->SetDiffuseColor(0.8, 0.8, 0.8); @@ -218,7 +218,7 @@ void ModelPhotoShootPrivate::PerformPostRenderingOperations() root->AddChild(light0); // create point light - ignition::rendering::PointLightPtr light2 = scene->CreatePointLight(); + gz::rendering::PointLightPtr light2 = scene->CreatePointLight(); light2->SetDiffuseColor(0.5, 0.5, 0.5); light2->SetSpecularColor(0.5, 0.5, 0.5); light2->SetLocalPosition(3, 5, 5); @@ -226,23 +226,23 @@ void ModelPhotoShootPrivate::PerformPostRenderingOperations() for (unsigned int i = 0; i < scene->NodeCount(); ++i) { - auto camera = std::dynamic_pointer_cast( + auto camera = std::dynamic_pointer_cast( scene->NodeByIndex(i)); if (nullptr != camera && camera->Name() == "photo_shoot::link::camera") { // Compute the translation we have to apply to the cameras to // center the model in the image. - ignition::math::AxisAlignedBox bbox = modelVisual->LocalBoundingBox(); + gz::math::AxisAlignedBox bbox = modelVisual->LocalBoundingBox(); double scaling = 1.0 / bbox.Size().Max(); - ignition::math::Vector3d bboxCenter = bbox.Center(); - ignition::math::Vector3d translation = + gz::math::Vector3d bboxCenter = bbox.Center(); + gz::math::Vector3d translation = bboxCenter + this->modelPose3D.Pos(); if (this->savingFile.is_open()) { this->savingFile << "Translation: " << translation << std::endl; this->savingFile << "Scaling: " << scaling << std::endl; } - ignition::math::Pose3d pose; + gz::math::Pose3d pose; // Perspective view pose.Pos().Set(1.6 / scaling + translation.X(), -1.6 / scaling + translation.Y(), @@ -286,29 +286,33 @@ void ModelPhotoShootPrivate::PerformPostRenderingOperations() ////////////////////////////////////////////////// void ModelPhotoShootPrivate::SavePicture( - const ignition::rendering::CameraPtr _camera, - const ignition::math::Pose3d &_pose, + const gz::rendering::CameraPtr _camera, + const gz::math::Pose3d &_pose, const std::string &_fileName) const { unsigned int width = _camera->ImageWidth(); unsigned int height = _camera->ImageHeight(); - ignition::common::Image image; + gz::common::Image image; _camera->SetWorldPose(_pose); auto cameraImage = _camera->CreateImage(); _camera->Capture(cameraImage); auto formatStr = - ignition::rendering::PixelUtil::Name(_camera->ImageFormat()); - auto format = ignition::common::Image::ConvertPixelFormat(formatStr); + gz::rendering::PixelUtil::Name(_camera->ImageFormat()); + auto format = gz::common::Image::ConvertPixelFormat(formatStr); image.SetFromData(cameraImage.Data(), width, height, format); image.SavePNG(_fileName); - igndbg << "Saved image to [" << _fileName << "]" << std::endl; + gzdbg << "Saved image to [" << _fileName << "]" << std::endl; } -IGNITION_ADD_PLUGIN(ModelPhotoShoot, ignition::gazebo::System, +IGNITION_ADD_PLUGIN(ModelPhotoShoot, gz::sim::System, ModelPhotoShoot::ISystemConfigure, ModelPhotoShoot::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(ModelPhotoShoot, + "gz::sim::systems::ModelPhotoShoot") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(ModelPhotoShoot, "ignition::gazebo::systems::ModelPhotoShoot") diff --git a/src/systems/model_photo_shoot/ModelPhotoShoot.hh b/src/systems/model_photo_shoot/ModelPhotoShoot.hh index 9a14609c6a..dc6f982bf7 100644 --- a/src/systems/model_photo_shoot/ModelPhotoShoot.hh +++ b/src/systems/model_photo_shoot/ModelPhotoShoot.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_MODELPHOTOSHOOT_HH_ -#define IGNITION_GAZEBO_SYSTEMS_MODELPHOTOSHOOT_HH_ +#ifndef GZ_SIM_SYSTEMS_MODELPHOTOSHOOT_HH_ +#define GZ_SIM_SYSTEMS_MODELPHOTOSHOOT_HH_ #include @@ -23,12 +23,12 @@ #include "gz/sim/System.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declarations. @@ -77,14 +77,14 @@ namespace systems public: ~ModelPhotoShoot() override = default; // Documentation inherited - public: void Configure(const ignition::gazebo::Entity &_id, + public: void Configure(const gz::sim::Entity &_id, const std::shared_ptr &_sdf, - ignition::gazebo::EntityComponentManager &_ecm, - ignition::gazebo::EventManager &_eventMgr) override; + gz::sim::EntityComponentManager &_ecm, + gz::sim::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; /// \brief Private data pointer private: std::unique_ptr dataPtr; diff --git a/src/systems/multicopter_control/Common.cc b/src/systems/multicopter_control/Common.cc index cfd5f2437d..c953ecae88 100644 --- a/src/systems/multicopter_control/Common.cc +++ b/src/systems/multicopter_control/Common.cc @@ -32,12 +32,12 @@ #include "gz/sim/components/LinearVelocity.hh" #include "gz/sim/components/AngularVelocity.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { namespace multicopter_control @@ -56,7 +56,7 @@ RotorConfiguration loadRotorConfiguration(const EntityComponentManager &_ecm, Rotor rotor; if (!elem->HasElement("jointName")) { - ignerr << "Please specify jointName for rotor index " << count + gzerr << "Please specify jointName for rotor index " << count << std::endl; continue; } @@ -66,7 +66,7 @@ RotorConfiguration loadRotorConfiguration(const EntityComponentManager &_ecm, components::ParentEntity(_model.Entity())); if (kNullEntity == joint) { - ignerr << "Joint with name " << jointName << " could not be found in " + gzerr << "Joint with name " << jointName << " could not be found in " << "model " << _model.Name(_ecm) << " while processing rotor " << "index " << count << std::endl; continue; @@ -86,7 +86,7 @@ RotorConfiguration loadRotorConfiguration(const EntityComponentManager &_ecm, if (kNullEntity == childLink) { - ignerr << "Child link of joint " << jointName << " with name " + gzerr << "Child link of joint " << jointName << " with name " << childLinkName << " could not be found in model " << _model.Name(_ecm) << " while processing rotor index " << count << std::endl; @@ -116,7 +116,7 @@ RotorConfiguration loadRotorConfiguration(const EntityComponentManager &_ecm, if (!elem->HasElement("forceConstant")) { - ignerr << "Please specify forceConstant for rotor index " << count + gzerr << "Please specify forceConstant for rotor index " << count << std::endl; continue; } @@ -145,7 +145,7 @@ RotorConfiguration loadRotorConfiguration(const EntityComponentManager &_ecm, if (!elem->HasElement("momentConstant")) { - ignerr << "Please specify momentConstant for rotor index " << count + gzerr << "Please specify momentConstant for rotor index " << count << std::endl; continue; } @@ -153,7 +153,7 @@ RotorConfiguration loadRotorConfiguration(const EntityComponentManager &_ecm, if (!elem->HasElement("direction")) { - ignerr << "Please specify direction for rotor index " << count + gzerr << "Please specify direction for rotor index " << count << std::endl; continue; } @@ -198,7 +198,7 @@ std::optional calculateAllocationMatrix( int rank = lu.rank(); if (rank < 4) { - ignerr << "The rank of the allocation matrix is " << lu.rank() + gzerr << "The rank of the allocation matrix is " << lu.rank() << ", it should have rank 4, to have a fully controllable system," << " check your configuration." << std::endl; return std::nullopt; @@ -238,7 +238,7 @@ std::optional getFrameData(const EntityComponentManager &_ecm, if (!poseComp) { - ignerr << "WorldPose component not found on link entity " << _link + gzerr << "WorldPose component not found on link entity " << _link << std::endl; return std::nullopt; } @@ -247,7 +247,7 @@ std::optional getFrameData(const EntityComponentManager &_ecm, if (!velComp) { - ignerr << "WorldLinearVelocity component not found on link entity " << _link + gzerr << "WorldLinearVelocity component not found on link entity " << _link << std::endl; return std::nullopt; } @@ -255,7 +255,7 @@ std::optional getFrameData(const EntityComponentManager &_ecm, if (!angVelComp) { - ignerr << "AngularVelocity component not found on link entity " << _link + gzerr << "AngularVelocity component not found on link entity " << _link << std::endl; return std::nullopt; } @@ -287,5 +287,5 @@ std::optional getFrameData(const EntityComponentManager &_ecm, } // namespace multicopter_control } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/src/systems/multicopter_control/Common.hh b/src/systems/multicopter_control/Common.hh index ca39eb2b46..17393c26cf 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_SIM_SYSTEMS_MULTICOPTERVELOCITYCONTROL_COMMON_HH_ +#define GZ_SIM_SYSTEMS_MULTICOPTERVELOCITYCONTROL_COMMON_HH_ #include #include @@ -30,12 +30,12 @@ #include "Parameters.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { namespace multicopter_control @@ -116,7 +116,7 @@ namespace multicopter_control } // namespace multicopter_control } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz #endif diff --git a/src/systems/multicopter_control/LeeVelocityController.cc b/src/systems/multicopter_control/LeeVelocityController.cc index b0e79b21cb..1690d760bb 100644 --- a/src/systems/multicopter_control/LeeVelocityController.cc +++ b/src/systems/multicopter_control/LeeVelocityController.cc @@ -17,12 +17,12 @@ #include "LeeVelocityController.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { namespace multicopter_control @@ -205,5 +205,5 @@ Eigen::Vector3d LeeVelocityController::ComputeDesiredAngularAcc( } // namespace multicopter_control } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz diff --git a/src/systems/multicopter_control/LeeVelocityController.hh b/src/systems/multicopter_control/LeeVelocityController.hh index e871894a0e..954b646f32 100644 --- a/src/systems/multicopter_control/LeeVelocityController.hh +++ b/src/systems/multicopter_control/LeeVelocityController.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_MULTICOPTER_CONTROL_LEEVELOCITYCONTROLLER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_MULTICOPTER_CONTROL_LEEVELOCITYCONTROLLER_HH_ +#ifndef GZ_SIM_SYSTEMS_MULTICOPTER_CONTROL_LEEVELOCITYCONTROLLER_HH_ +#define GZ_SIM_SYSTEMS_MULTICOPTER_CONTROL_LEEVELOCITYCONTROLLER_HH_ #include #include @@ -25,12 +25,12 @@ #include "Common.hh" #include "LeeVelocityController.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { namespace multicopter_control @@ -109,7 +109,7 @@ namespace multicopter_control } // namespace multicopter_control } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz #endif diff --git a/src/systems/multicopter_control/MulticopterVelocityControl.cc b/src/systems/multicopter_control/MulticopterVelocityControl.cc index 210b6d79ea..f050fbde7e 100644 --- a/src/systems/multicopter_control/MulticopterVelocityControl.cc +++ b/src/systems/multicopter_control/MulticopterVelocityControl.cc @@ -44,8 +44,8 @@ #include "MulticopterVelocityControl.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; using namespace multicopter_control; @@ -59,7 +59,7 @@ void MulticopterVelocityControl::Configure(const Entity &_entity, if (!this->model.Valid(_ecm)) { - ignerr << "MulticopterVelocityControl plugin should be attached to a model " + gzerr << "MulticopterVelocityControl plugin should be attached to a model " << "entity. Failed to initialize." << std::endl; return; } @@ -73,7 +73,7 @@ void MulticopterVelocityControl::Configure(const Entity &_entity, if (this->comLinkName.empty()) { - ignerr << "found an empty comLinkName parameter. Failed to initialize.\n"; + gzerr << "found an empty comLinkName parameter. Failed to initialize.\n"; return; } @@ -82,7 +82,7 @@ void MulticopterVelocityControl::Configure(const Entity &_entity, if (this->comLinkEntity == kNullEntity) { - ignerr << "Link " << this->comLinkName + gzerr << "Link " << this->comLinkName << " could not be found. Failed to initialize.\n"; return; } @@ -100,7 +100,7 @@ void MulticopterVelocityControl::Configure(const Entity &_entity, auto inertial = _ecm.Component(link); if (nullptr == inertial) { - ignerr << "Could not find inertial component on on link " + gzerr << "Could not find inertial component on on link " << this->comLinkName << std::endl; return; } @@ -127,7 +127,7 @@ void MulticopterVelocityControl::Configure(const Entity &_entity, } else { - ignerr << "Please specify rotorConfiguration.\n"; + gzerr << "Please specify rotorConfiguration.\n"; } this->rotorVelocities.resize(vehicleParams.rotorConfiguration.size()); @@ -136,7 +136,7 @@ void MulticopterVelocityControl::Configure(const Entity &_entity, if (kNullEntity == worldEntity) { - ignerr << "World entity missing." << std::endl; + gzerr << "World entity missing." << std::endl; return; } @@ -145,7 +145,7 @@ void MulticopterVelocityControl::Configure(const Entity &_entity, if (nullptr == gravityComp) { - ignerr << "World missing gravity." << std::endl; + gzerr << "World missing gravity." << std::endl; return; } @@ -160,7 +160,7 @@ void MulticopterVelocityControl::Configure(const Entity &_entity, } else { - ignerr << "Please specify velocityGain for MulticopterVelocityControl.\n"; + gzerr << "Please specify velocityGain for MulticopterVelocityControl.\n"; return; } @@ -171,7 +171,7 @@ void MulticopterVelocityControl::Configure(const Entity &_entity, } else { - ignerr << "Please specify attitudeGain for MulticopterVelocityControl.\n"; + gzerr << "Please specify attitudeGain for MulticopterVelocityControl.\n"; return; } @@ -182,7 +182,7 @@ void MulticopterVelocityControl::Configure(const Entity &_entity, } else { - ignerr << "Please specify angularRateGain MulticopterVelocityControl.\n"; + gzerr << "Please specify angularRateGain MulticopterVelocityControl.\n"; return; } @@ -228,7 +228,7 @@ void MulticopterVelocityControl::Configure(const Entity &_entity, if (nullptr == this->velocityController) { - ignerr << "Error while creating the LeeVelocityController\n"; + gzerr << "Error while creating the LeeVelocityController\n"; return; } @@ -263,7 +263,7 @@ void MulticopterVelocityControl::Configure(const Entity &_entity, sdfClone->Get("robotNamespace")); if (this->robotNamespace.empty()) { - ignerr << "Robot namespace [" + gzerr << "Robot namespace [" << sdfClone->Get("robotNamespace") <<"] is invalid." << std::endl; return; @@ -271,7 +271,7 @@ void MulticopterVelocityControl::Configure(const Entity &_entity, } else { - ignerr << "Please specify a robotNamespace.\n"; + gzerr << "Please specify a robotNamespace.\n"; return; } @@ -281,7 +281,7 @@ void MulticopterVelocityControl::Configure(const Entity &_entity, this->commandSubTopic); if (this->commandSubTopic.empty()) { - ignerr << "Invalid command sub-topic." << std::endl; + gzerr << "Invalid command sub-topic." << std::endl; return; } @@ -291,7 +291,7 @@ void MulticopterVelocityControl::Configure(const Entity &_entity, this->enableSubTopic); if (this->enableSubTopic.empty()) { - ignerr << "Invalid enable sub-topic." << std::endl; + gzerr << "Invalid enable sub-topic." << std::endl; return; } @@ -299,13 +299,13 @@ void MulticopterVelocityControl::Configure(const Entity &_entity, std::string topic{this->robotNamespace + "/" + this->commandSubTopic}; this->node.Subscribe(topic, &MulticopterVelocityControl::OnTwist, this); - ignmsg << "MulticopterVelocityControl subscribing to Twist messages on [" + gzmsg << "MulticopterVelocityControl subscribing to Twist messages on [" << topic << "]" << std::endl; std::string enableTopic{this->robotNamespace + "/" + this->enableSubTopic}; this->node.Subscribe(enableTopic, &MulticopterVelocityControl::OnEnable, this); - ignmsg << "MulticopterVelocityControl subscribing to Boolean messages on [" + gzmsg << "MulticopterVelocityControl subscribing to Boolean messages on [" << enableTopic << "]" << std::endl; // Create the Actuators component to take control of rotor speeds @@ -320,8 +320,8 @@ void MulticopterVelocityControl::Configure(const Entity &_entity, ////////////////////////////////////////////////// void MulticopterVelocityControl::PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("MulticopterVelocityControl::PreUpdate"); @@ -333,7 +333,7 @@ void MulticopterVelocityControl::PreUpdate( // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -412,7 +412,7 @@ void MulticopterVelocityControl::OnEnable( ////////////////////////////////////////////////// void MulticopterVelocityControl::PublishRotorVelocities( - ignition::gazebo::EntityComponentManager &_ecm, + gz::sim::EntityComponentManager &_ecm, const Eigen::VectorXd &_vels) { if (_vels.size() != this->rotorVelocitiesMsg.velocity_size()) @@ -449,10 +449,15 @@ void MulticopterVelocityControl::PublishRotorVelocities( } IGNITION_ADD_PLUGIN(MulticopterVelocityControl, - ignition::gazebo::System, + gz::sim::System, 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 3c791adb51..8f035e3cd3 100644 --- a/src/systems/multicopter_control/MulticopterVelocityControl.hh +++ b/src/systems/multicopter_control/MulticopterVelocityControl.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_HH_ -#define IGNITION_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_HH_ +#ifndef GZ_SIM_SYSTEMS_MULTICOPTERVELOCITYCONTROL_HH_ +#define GZ_SIM_SYSTEMS_MULTICOPTERVELOCITYCONTROL_HH_ #include #include @@ -30,12 +30,12 @@ #include "Common.hh" #include "LeeVelocityController.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { /// \brief This is a velocity controller for multicopters that allows control @@ -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 3d174c8a8c..2e354b1fac 100644 --- a/src/systems/multicopter_control/Parameters.hh +++ b/src/systems/multicopter_control/Parameters.hh @@ -15,20 +15,20 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_PARAMETERS_HH_ -#define IGNITION_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_PARAMETERS_HH_ +#ifndef GZ_SIM_SYSTEMS_MULTICOPTERVELOCITYCONTROL_PARAMETERS_HH_ +#define GZ_SIM_SYSTEMS_MULTICOPTERVELOCITYCONTROL_PARAMETERS_HH_ #include #include #include "gz/sim/config.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { namespace multicopter_control @@ -92,7 +92,7 @@ namespace multicopter_control } // namespace multicopter_control } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz #endif diff --git a/src/systems/multicopter_motor_model/MulticopterMotorModel.cc b/src/systems/multicopter_motor_model/MulticopterMotorModel.cc index 0a92b25247..af38a82bdd 100644 --- a/src/systems/multicopter_motor_model/MulticopterMotorModel.cc +++ b/src/systems/multicopter_motor_model/MulticopterMotorModel.cc @@ -97,8 +97,8 @@ class FirstOrderFilter { T previousState; }; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; /// \brief Constants for specifying clockwise (kCw) and counter-clockwise (kCcw) @@ -115,10 +115,10 @@ enum class MotorType { kForce }; -class ignition::gazebo::systems::MulticopterMotorModelPrivate +class gz::sim::systems::MulticopterMotorModelPrivate { /// \brief Callback for actuator commands. - public: void OnActuatorMsg(const ignition::msgs::Actuators &_msg); + public: void OnActuatorMsg(const gz::msgs::Actuators &_msg); /// \brief Apply link forces and moments based on propeller state. public: void UpdateForcesAndMoments(EntityComponentManager &_ecm); @@ -234,7 +234,7 @@ void MulticopterMotorModel::Configure(const Entity &_entity, if (!this->dataPtr->model.Valid(_ecm)) { - ignerr << "MulticopterMotorModel plugin should be attached to a model " + gzerr << "MulticopterMotorModel plugin should be attached to a model " << "entity. Failed to initialize." << std::endl; return; } @@ -250,7 +250,7 @@ void MulticopterMotorModel::Configure(const Entity &_entity, } else { - ignerr << "Please specify a robotNamespace.\n"; + gzerr << "Please specify a robotNamespace.\n"; } // Get params from SDF @@ -261,7 +261,7 @@ void MulticopterMotorModel::Configure(const Entity &_entity, if (this->dataPtr->jointName.empty()) { - ignerr << "MulticopterMotorModel found an empty jointName parameter. " + gzerr << "MulticopterMotorModel found an empty jointName parameter. " << "Failed to initialize."; return; } @@ -273,7 +273,7 @@ void MulticopterMotorModel::Configure(const Entity &_entity, if (this->dataPtr->linkName.empty()) { - ignerr << "MulticopterMotorModel found an empty linkName parameter. " + gzerr << "MulticopterMotorModel found an empty linkName parameter. " << "Failed to initialize."; return; } @@ -282,7 +282,7 @@ void MulticopterMotorModel::Configure(const Entity &_entity, this->dataPtr->motorNumber = sdfClone->GetElement("motorNumber")->Get(); else - ignerr << "Please specify a motorNumber.\n"; + gzerr << "Please specify a motorNumber.\n"; if (sdfClone->HasElement("turningDirection")) { @@ -293,11 +293,11 @@ void MulticopterMotorModel::Configure(const Entity &_entity, else if (turningDirection == "ccw") this->dataPtr->turningDirection = turning_direction::kCcw; else - ignerr << "Please only use 'cw' or 'ccw' as turningDirection.\n"; + gzerr << "Please only use 'cw' or 'ccw' as turningDirection.\n"; } else { - ignerr << "Please specify a turning direction ('cw' or 'ccw').\n"; + gzerr << "Please specify a turning direction ('cw' or 'ccw').\n"; } if (sdfClone->HasElement("motorType")) @@ -308,22 +308,22 @@ void MulticopterMotorModel::Configure(const Entity &_entity, else if (motorType == "position") { this->dataPtr->motorType = MotorType::kPosition; - ignerr << "motorType 'position' not supported" << std::endl; + gzerr << "motorType 'position' not supported" << std::endl; } else if (motorType == "force") { this->dataPtr->motorType = MotorType::kForce; - ignerr << "motorType 'force' not supported" << std::endl; + gzerr << "motorType 'force' not supported" << std::endl; } else { - ignerr << "Please only use 'velocity', 'position' or " + gzerr << "Please only use 'velocity', 'position' or " "'force' as motorType.\n"; } } else { - ignwarn << "motorType not specified, using velocity.\n"; + gzwarn << "motorType not specified, using velocity.\n"; this->dataPtr->motorType = MotorType::kVelocity; } @@ -361,7 +361,7 @@ void MulticopterMotorModel::Configure(const Entity &_entity, this->dataPtr->robotNamespace + "/" + this->dataPtr->commandSubTopic); if (topic.empty()) { - ignerr << "Failed to create topic for [" << this->dataPtr->robotNamespace + gzerr << "Failed to create topic for [" << this->dataPtr->robotNamespace << "]" << std::endl; return; } @@ -370,15 +370,15 @@ void MulticopterMotorModel::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void MulticopterMotorModel::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void MulticopterMotorModel::PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("MulticopterMotorModel::PreUpdate"); // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -469,7 +469,7 @@ void MulticopterMotorModel::PreUpdate(const ignition::gazebo::UpdateInfo &_info, ////////////////////////////////////////////////// void MulticopterMotorModelPrivate::OnActuatorMsg( - const ignition::msgs::Actuators &_msg) + const gz::msgs::Actuators &_msg) { std::lock_guard lock(this->recvdActuatorsMsgMutex); this->recvdActuatorsMsg = _msg; @@ -505,7 +505,7 @@ void MulticopterMotorModelPrivate::UpdateForcesAndMoments( { if (this->motorNumber > msg->velocity_size() - 1) { - ignerr << "You tried to access index " << this->motorNumber + gzerr << "You tried to access index " << this->motorNumber << " of the Actuator velocity array which is of size " << msg->velocity_size() << std::endl; return; @@ -545,7 +545,7 @@ void MulticopterMotorModelPrivate::UpdateForcesAndMoments( double motorRotVel = jointVelocity->Data()[0]; if (motorRotVel / (2 * IGN_PI) > 1 / (2 * this->samplingTime)) { - ignerr << "Aliasing on motor [" << this->motorNumber + gzerr << "Aliasing on motor [" << this->motorNumber << "] might occur. Consider making smaller simulation time " "steps or raising the rotorVelocitySlowdownSim param.\n"; } @@ -559,8 +559,8 @@ void MulticopterMotorModelPrivate::UpdateForcesAndMoments( realMotorVelocity * realMotorVelocity * this->motorConstant; - using Pose = ignition::math::Pose3d; - using Vector3 = ignition::math::Vector3d; + using Pose = gz::math::Pose3d; + using Vector3 = gz::math::Vector3d; Link link(this->linkEntity); const auto worldPose = link.WorldPose(_ecm); @@ -573,7 +573,7 @@ void MulticopterMotorModelPrivate::UpdateForcesAndMoments( this->jointEntity); if (!jointPose) { - ignerr << "joint " << this->jointName << " has no Pose" + gzerr << "joint " << this->jointName << " has no Pose" << "component" << std::endl; return; } @@ -585,7 +585,7 @@ void MulticopterMotorModelPrivate::UpdateForcesAndMoments( this->jointEntity); if (!jointAxisComp) { - ignerr << "joint " << this->jointName << " has no JointAxis" + gzerr << "joint " << this->jointName << " has no JointAxis" << "component" << std::endl; return; } @@ -671,9 +671,13 @@ void MulticopterMotorModelPrivate::UpdateForcesAndMoments( } IGNITION_ADD_PLUGIN(MulticopterMotorModel, - ignition::gazebo::System, + gz::sim::System, 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 19ed209491..8e821709a3 100644 --- a/src/systems/multicopter_motor_model/MulticopterMotorModel.hh +++ b/src/systems/multicopter_motor_model/MulticopterMotorModel.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_MULTICOPTERMOTORMODEL_HH_ -#define IGNITION_GAZEBO_SYSTEMS_MULTICOPTERMOTORMODEL_HH_ +#ifndef GZ_SIM_SYSTEMS_MULTICOPTERMOTORMODEL_HH_ +#define GZ_SIM_SYSTEMS_MULTICOPTERMOTORMODEL_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declaration @@ -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/navsat/NavSat.cc b/src/systems/navsat/NavSat.cc index 1c8d20ff65..ead58a5ce1 100644 --- a/src/systems/navsat/NavSat.cc +++ b/src/systems/navsat/NavSat.cc @@ -44,12 +44,12 @@ #include "gz/sim/EntityComponentManager.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; /// \brief Private NavSat data class. -class ignition::gazebo::systems::NavSat::Implementation +class gz::sim::systems::NavSat::Implementation { /// \brief A map of NavSat entity to its sensor public: std::unordered_mapdataPtr->entitySensorMap.find(entity); if (it == this->dataPtr->entitySensorMap.end()) { - ignerr << "Entity [" << entity + gzerr << "Entity [" << entity << "] isn't in sensor map, this shouldn't happen." << std::endl; continue; } @@ -127,7 +127,7 @@ void NavSat::PostUpdate(const UpdateInfo &_info, // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -170,7 +170,7 @@ void NavSat::Implementation::AddSensor( this->sensorFactory.CreateSensor(data); if (nullptr == sensor) { - ignerr << "Failed to create sensor [" << sensorScopedName << "]" + gzerr << "Failed to create sensor [" << sensorScopedName << "]" << std::endl; return; } @@ -229,7 +229,7 @@ void NavSat::Implementation::Update(const EntityComponentManager &_ecm) if (it == this->entitySensorMap.end()) { - ignerr << "Failed to update NavSat sensor entity [" << _entity + gzerr << "Failed to update NavSat sensor entity [" << _entity << "]. Entity not found." << std::endl; return true; } @@ -238,7 +238,7 @@ void NavSat::Implementation::Update(const EntityComponentManager &_ecm) auto latLonEle = sphericalCoordinates(_entity, _ecm); if (!latLonEle) { - ignwarn << "Failed to update NavSat sensor enity [" << _entity + gzwarn << "Failed to update NavSat sensor enity [" << _entity << "]. Spherical coordinates not set." << std::endl; return true; } @@ -265,7 +265,7 @@ void NavSat::Implementation::RemoveSensors(const EntityComponentManager &_ecm) auto sensorId = this->entitySensorMap.find(_entity); if (sensorId == this->entitySensorMap.end()) { - ignerr << "Internal error, missing NavSat sensor for entity [" + gzerr << "Internal error, missing NavSat sensor for entity [" << _entity << "]" << std::endl; return true; } @@ -281,4 +281,7 @@ IGNITION_ADD_PLUGIN(NavSat, System, NavSat::ISystemPostUpdate ) +IGNITION_ADD_PLUGIN_ALIAS(NavSat, "gz::sim::systems::NavSat") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(NavSat, "ignition::gazebo::systems::NavSat") diff --git a/src/systems/navsat/NavSat.hh b/src/systems/navsat/NavSat.hh index ad4d5e4176..d7b48dc7b8 100644 --- a/src/systems/navsat/NavSat.hh +++ b/src/systems/navsat/NavSat.hh @@ -14,26 +14,26 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_NAVSAT_HH_ -#define IGNITION_GAZEBO_SYSTEMS_NAVSAT_HH_ +#ifndef GZ_SIM_SYSTEMS_NAVSAT_HH_ +#define GZ_SIM_SYSTEMS_NAVSAT_HH_ #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { /// \class NavSat NavSat.hh gz/sim/systems/NavSat.hh /// \brief System that handles navigation satellite sensors, such as GPS, /// that reports position and velocity in spherical coordinates (latitude / - /// longitude) over Ignition Transport. + /// longitude) over Gazebo Transport. /// /// The NavSat sensors rely on the world origin's spherical coordinates /// being set, for example through SDF's `` tag diff --git a/src/systems/odometry_publisher/OdometryPublisher.cc b/src/systems/odometry_publisher/OdometryPublisher.cc index 8d2e4e7781..2bbed0f63a 100644 --- a/src/systems/odometry_publisher/OdometryPublisher.cc +++ b/src/systems/odometry_publisher/OdometryPublisher.cc @@ -39,18 +39,18 @@ #include "gz/sim/Model.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; -class ignition::gazebo::systems::OdometryPublisherPrivate +class gz::sim::systems::OdometryPublisherPrivate { /// \brief Calculates odometry and publishes an odometry message. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateOdometry(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm); /// \brief Ignition communication node. public: transport::Node node; @@ -98,7 +98,7 @@ class ignition::gazebo::systems::OdometryPublisherPrivate public: math::clock::time_point lastUpdateTime; /// \brief Allow specifying constant xyz and rpy offsets - public: ignition::math::Pose3d offset = {0, 0, 0, 0, 0, 0}; + public: gz::math::Pose3d offset = {0, 0, 0, 0, 0, 0}; /// \brief Gaussian noise public: double gaussianNoise = 0.0; @@ -136,7 +136,7 @@ void OdometryPublisher::Configure(const Entity &_entity, if (!this->dataPtr->model.Valid(_ecm)) { - ignerr << "OdometryPublisher system plugin should be attached to a model" + gzerr << "OdometryPublisher system plugin should be attached to a model" << " entity. Failed to initialize." << std::endl; return; } @@ -144,7 +144,7 @@ void OdometryPublisher::Configure(const Entity &_entity, this->dataPtr->odomFrame = this->dataPtr->model.Name(_ecm) + "/" + "odom"; if (!_sdf->HasElement("odom_frame")) { - ignwarn << "OdometryPublisher system plugin missing , " + gzwarn << "OdometryPublisher system plugin missing , " << "defaults to \"" << this->dataPtr->odomFrame << "\"" << std::endl; } else @@ -154,14 +154,14 @@ void OdometryPublisher::Configure(const Entity &_entity, if (_sdf->HasElement("xyz_offset")) { - this->dataPtr->offset.Pos() = _sdf->Get( + this->dataPtr->offset.Pos() = _sdf->Get( "xyz_offset"); } if (_sdf->HasElement("rpy_offset")) { this->dataPtr->offset.Rot() = - ignition::math::Quaterniond(_sdf->Get( + gz::math::Quaterniond(_sdf->Get( "rpy_offset")); } @@ -174,7 +174,7 @@ void OdometryPublisher::Configure(const Entity &_entity, + "/" + "base_footprint"; if (!_sdf->HasElement("robot_base_frame")) { - ignwarn << "OdometryPublisher system plugin missing , " + gzwarn << "OdometryPublisher system plugin missing , " << "defaults to \"" << this->dataPtr->robotBaseFrame << "\"" << std::endl; } else @@ -185,7 +185,7 @@ void OdometryPublisher::Configure(const Entity &_entity, this->dataPtr->dimensions = 2; if (!_sdf->HasElement("dimensions")) { - igndbg << "OdometryPublisher system plugin missing , " + gzdbg << "OdometryPublisher system plugin missing , " << "defaults to \"" << this->dataPtr->dimensions << "\"" << std::endl; } else @@ -193,7 +193,7 @@ void OdometryPublisher::Configure(const Entity &_entity, this->dataPtr->dimensions = _sdf->Get("dimensions"); if (this->dataPtr->dimensions != 2 && this->dataPtr->dimensions != 3) { - ignerr << "OdometryPublisher system plugin must be 2D or 3D " + gzerr << "OdometryPublisher system plugin must be 2D or 3D " << "not " << this->dataPtr->dimensions << "D. Failed to initialize." << std::endl; return; @@ -222,7 +222,7 @@ void OdometryPublisher::Configure(const Entity &_entity, std::string odomTopicValid {transport::TopicUtils::AsValidTopic(odomTopic)}; if (odomTopicValid.empty()) { - ignerr << "Failed to generate odom topic [" + gzerr << "Failed to generate odom topic [" << odomTopic << "]" << std::endl; } else @@ -235,7 +235,7 @@ void OdometryPublisher::Configure(const Entity &_entity, transport::TopicUtils::AsValidTopic(odomCovTopic)}; if (odomCovTopicValid.empty()) { - ignerr << "Failed to generate odom topic [" + gzerr << "Failed to generate odom topic [" << odomCovTopic << "]" << std::endl; } else @@ -246,15 +246,15 @@ void OdometryPublisher::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void OdometryPublisher::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void OdometryPublisher::PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("OdometryPublisher::PreUpdate"); // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -283,8 +283,8 @@ void OdometryPublisher::PostUpdate(const UpdateInfo &_info, ////////////////////////////////////////////////// void OdometryPublisherPrivate::UpdateOdometry( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("OdometryPublisher::UpdateOdometry"); // Record start time. @@ -337,17 +337,17 @@ void OdometryPublisherPrivate::UpdateOdometry( std::get<1>(this->linearMean).Push(linearVelocityY); msg.mutable_twist()->mutable_linear()->set_x( std::get<0>(this->linearMean).Mean() + - ignition::math::Rand::DblNormal(0, this->gaussianNoise)); + gz::math::Rand::DblNormal(0, this->gaussianNoise)); msg.mutable_twist()->mutable_linear()->set_y( std::get<1>(this->linearMean).Mean() + - ignition::math::Rand::DblNormal(0, this->gaussianNoise)); + gz::math::Rand::DblNormal(0, this->gaussianNoise)); msg.mutable_twist()->mutable_linear()->set_z( - ignition::math::Rand::DblNormal(0, this->gaussianNoise)); + gz::math::Rand::DblNormal(0, this->gaussianNoise)); msg.mutable_twist()->mutable_angular()->set_x( - ignition::math::Rand::DblNormal(0, this->gaussianNoise)); + gz::math::Rand::DblNormal(0, this->gaussianNoise)); msg.mutable_twist()->mutable_angular()->set_y( - ignition::math::Rand::DblNormal(0, this->gaussianNoise)); + gz::math::Rand::DblNormal(0, this->gaussianNoise)); } // Get velocities and roll/pitch rates assuming 3D else if (this->dimensions == 3) @@ -377,26 +377,26 @@ void OdometryPublisherPrivate::UpdateOdometry( std::get<1>(this->angularMean).Push(pitchDiff / dt.count()); msg.mutable_twist()->mutable_linear()->set_x( std::get<0>(this->linearMean).Mean() + - ignition::math::Rand::DblNormal(0, this->gaussianNoise)); + gz::math::Rand::DblNormal(0, this->gaussianNoise)); msg.mutable_twist()->mutable_linear()->set_y( std::get<1>(this->linearMean).Mean() + - ignition::math::Rand::DblNormal(0, this->gaussianNoise)); + gz::math::Rand::DblNormal(0, this->gaussianNoise)); msg.mutable_twist()->mutable_linear()->set_z( std::get<2>(this->linearMean).Mean() + - ignition::math::Rand::DblNormal(0, this->gaussianNoise)); + gz::math::Rand::DblNormal(0, this->gaussianNoise)); msg.mutable_twist()->mutable_angular()->set_x( std::get<0>(this->angularMean).Mean() + - ignition::math::Rand::DblNormal(0, this->gaussianNoise)); + gz::math::Rand::DblNormal(0, this->gaussianNoise)); msg.mutable_twist()->mutable_angular()->set_y( std::get<1>(this->angularMean).Mean() + - ignition::math::Rand::DblNormal(0, this->gaussianNoise)); + gz::math::Rand::DblNormal(0, this->gaussianNoise)); } // Set yaw rate std::get<2>(this->angularMean).Push(yawDiff / dt.count()); msg.mutable_twist()->mutable_angular()->set_z( std::get<2>(this->angularMean).Mean() + - ignition::math::Rand::DblNormal(0, this->gaussianNoise)); + gz::math::Rand::DblNormal(0, this->gaussianNoise)); // Set the time stamp in the header. msg.mutable_header()->mutable_stamp()->CopyFrom( @@ -491,10 +491,14 @@ void OdometryPublisherPrivate::UpdateOdometry( } IGNITION_ADD_PLUGIN(OdometryPublisher, - ignition::gazebo::System, + gz::sim::System, OdometryPublisher::ISystemConfigure, OdometryPublisher::ISystemPreUpdate, OdometryPublisher::ISystemPostUpdate) +IGNITION_ADD_PLUGIN_ALIAS(OdometryPublisher, + "gz::sim::systems::OdometryPublisher") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(OdometryPublisher, "ignition::gazebo::systems::OdometryPublisher") diff --git a/src/systems/odometry_publisher/OdometryPublisher.hh b/src/systems/odometry_publisher/OdometryPublisher.hh index b69cc68f7b..16d84f0891 100644 --- a/src/systems/odometry_publisher/OdometryPublisher.hh +++ b/src/systems/odometry_publisher/OdometryPublisher.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_ODOMETRYPUBLISHER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_ODOMETRYPUBLISHER_HH_ +#ifndef GZ_SIM_SYSTEMS_ODOMETRYPUBLISHER_HH_ +#define GZ_SIM_SYSTEMS_ODOMETRYPUBLISHER_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declaration @@ -34,7 +34,7 @@ namespace systems /// \brief Odometry Publisher which can be attached to any entity in /// order to periodically publish 2D or 3D odometry data in the form of - /// ignition::msgs::Odometry messages. + /// gz::msgs::Odometry messages. /// /// # System Parameters /// @@ -92,8 +92,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/optical_tactile_plugin/OpticalTactilePlugin.cc b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc index f98e9532d9..1bd87b6249 100644 --- a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc +++ b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc @@ -43,12 +43,12 @@ #include "OpticalTactilePlugin.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; using namespace optical_tactile_sensor; -class ignition::gazebo::systems::OpticalTactilePluginPrivate +class gz::sim::systems::OpticalTactilePluginPrivate { /// \brief Load the Contact sensor from an sdf element /// \param[in] _ecm Immutable reference to the EntityComponentManager @@ -56,12 +56,12 @@ class ignition::gazebo::systems::OpticalTactilePluginPrivate /// \brief Actual function that enables the plugin. /// \param[in] _req Whether to enable the plugin or disable it. - public: void Enable(const ignition::msgs::Boolean &_req); + public: void Enable(const gz::msgs::Boolean &_req); /// \brief Callback for the depth camera /// \param[in] _msg Message from the subscribed topic public: void DepthCameraCallback( - const ignition::msgs::PointCloudPacked &_msg); + const gz::msgs::PointCloudPacked &_msg); /// \brief Map the (i,j) coordinates defined in the top-left corner of the /// camera into its corresponding (X,Y,Z) measurement with respect to the @@ -72,13 +72,13 @@ class ignition::gazebo::systems::OpticalTactilePluginPrivate /// of the image, pointing downwards /// \param[in] _msgBuffer Buffer with the point cloud data /// \returns The corresponding (X,Y,Z) point - public: ignition::math::Vector3f MapPointCloudData(const uint64_t &_i, + public: gz::math::Vector3f MapPointCloudData(const uint64_t &_i, const uint64_t &_j, const char *_msgBuffer); /// \brief Check if a specific point from the depth camera is inside /// the contact surface. /// \param[in] _point Point from the depth camera - public: bool PointInsideSensor(ignition::math::Vector3f _point); + public: bool PointInsideSensor(gz::math::Vector3f _point); /// \brief Computes the normal forces of the Optical Tactile sensor /// \param[in] _msg Message from the depth camera @@ -89,7 +89,7 @@ class ignition::gazebo::systems::OpticalTactilePluginPrivate /// 34644101/calculate-surface-normals-from-depth-image- /// using-neighboring-pixels-cross-produc public: void ComputeNormalForces( - const ignition::msgs::PointCloudPacked &_msg, + const gz::msgs::PointCloudPacked &_msg, const bool _visualizeForces); /// \brief Resolution of the visualization in pixels to skip. @@ -108,11 +108,11 @@ class ignition::gazebo::systems::OpticalTactilePluginPrivate public: transport::Node node; /// \brief Entity representing the contact sensor of the plugin - public: ignition::gazebo::Entity sensorCollisionEntity; + public: gz::sim::Entity sensorCollisionEntity; /// \brief Entity representing the collision of the object in contact with /// the optical tactile sensor. - public: ignition::gazebo::Entity objectCollisionEntity; + public: gz::sim::Entity objectCollisionEntity; /// \brief Whether the plugin is enabled. public: std::atomic enabled{true}; @@ -127,13 +127,13 @@ class ignition::gazebo::systems::OpticalTactilePluginPrivate public: double forceLength{0.01}; /// \brief Pose of the sensor model - public: ignition::math::Pose3f tactileSensorWorldPose; + public: gz::math::Pose3f tactileSensorWorldPose; /// \brief Pose of the sensor model in the previous iteration - public: ignition::math::Pose3f prevTactileSensorWorldPose; + public: gz::math::Pose3f prevTactileSensorWorldPose; /// \brief Offset between depth camera pose and model pose - public: ignition::math::Pose3f depthCameraOffset; + public: gz::math::Pose3f depthCameraOffset; /// \brief Whether a new message has been returned by the depth camera public: bool newCameraMsg{false}; @@ -142,7 +142,7 @@ class ignition::gazebo::systems::OpticalTactilePluginPrivate public: float cameraUpdateRate{1}; /// \brief Message returned by the depth camera - public: ignition::msgs::PointCloudPacked cameraMsg; + public: gz::msgs::PointCloudPacked cameraMsg; /// \brief Mutex for variables mutated by the camera callback. /// The variables are: newCameraMsg, cameraMsg. @@ -153,7 +153,7 @@ class ignition::gazebo::systems::OpticalTactilePluginPrivate public: bool visualizeSensor{false}; /// \brief Size of the contact sensor - public: ignition::math::Vector3d sensorSize{0.005, 0.02, 0.02}; + public: gz::math::Vector3d sensorSize{0.005, 0.02, 0.02}; /// \brief Extended sensing distance. The sensor will output data coming from /// its volume plus this distance. @@ -169,7 +169,7 @@ class ignition::gazebo::systems::OpticalTactilePluginPrivate public: bool initErrorPrinted{false}; /// \brief Normal forces publisher - public: ignition::transport::Node::Publisher normalForcesPub; + public: gz::transport::Node::Publisher normalForcesPub; /// \brief Namespace for transport topics public: std::string ns{"optical_tactile_sensor"}; @@ -191,7 +191,7 @@ void OpticalTactilePlugin::Configure(const Entity &_entity, if (!this->dataPtr->model.Valid(_ecm)) { - ignerr << "Optical tactile plugin should be attached to a model entity. " + gzerr << "Optical tactile plugin should be attached to a model entity. " << "Failed to initialize." << std::endl; return; } @@ -200,7 +200,7 @@ void OpticalTactilePlugin::Configure(const Entity &_entity, if (!_sdf->HasElement("enabled")) { - igndbg << "Missing parameter , " + gzdbg << "Missing parameter , " << "setting to " << this->dataPtr->enabled << std::endl; } else @@ -210,14 +210,14 @@ void OpticalTactilePlugin::Configure(const Entity &_entity, if (!_sdf->HasElement("visualization_resolution")) { - igndbg << "Missing parameter , " + gzdbg << "Missing parameter , " << "setting to " << this->dataPtr->visualizationResolution << std::endl; } else { if (_sdf->Get("visualization_resolution") < 0) { - ignwarn << "Parameter must be positive, " + gzwarn << "Parameter must be positive, " << "setting to " << this->dataPtr->visualizationResolution << std::endl; } else @@ -229,7 +229,7 @@ void OpticalTactilePlugin::Configure(const Entity &_entity, if (!_sdf->HasElement("visualize_forces")) { - igndbg << "Missing parameter , " + gzdbg << "Missing parameter , " << "setting to " << this->dataPtr->visualizeForces << std::endl; } else @@ -239,7 +239,7 @@ void OpticalTactilePlugin::Configure(const Entity &_entity, if (!_sdf->HasElement("visualize_contacts")) { - igndbg << "Missing parameter , " + gzdbg << "Missing parameter , " << "setting to " << this->dataPtr->visualizeContacts << std::endl; } else @@ -249,14 +249,14 @@ void OpticalTactilePlugin::Configure(const Entity &_entity, if (!_sdf->HasElement("extended_sensing")) { - igndbg << "Missing parameter , " + gzdbg << "Missing parameter , " << "setting to " << this->dataPtr->extendedSensing << std::endl; } else { if (_sdf->Get("extended_sensing") < 0) { - ignwarn << "Parameter must be positive, " + gzwarn << "Parameter must be positive, " << "setting to " << this->dataPtr->extendedSensing << std::endl; } else @@ -267,7 +267,7 @@ void OpticalTactilePlugin::Configure(const Entity &_entity, if (!_sdf->HasElement("visualize_sensor")) { - igndbg << "Missing parameter , " + gzdbg << "Missing parameter , " << "setting to " << this->dataPtr->visualizeSensor << std::endl; } else @@ -277,14 +277,14 @@ void OpticalTactilePlugin::Configure(const Entity &_entity, if (!_sdf->HasElement("force_length")) { - igndbg << "Missing parameter , " + gzdbg << "Missing parameter , " << "setting to " << this->dataPtr->forceLength << std::endl; } else { if (_sdf->Get("force_length") < 0) { - ignwarn << "Parameter must be positive, " + gzwarn << "Parameter must be positive, " << "setting to " << this->dataPtr->forceLength << std::endl; } else @@ -295,7 +295,7 @@ void OpticalTactilePlugin::Configure(const Entity &_entity, if (!_sdf->HasElement("namespace")) { - igndbg << "Missing parameter , " + gzdbg << "Missing parameter , " << "setting to " << this->dataPtr->ns << std::endl; } else @@ -322,8 +322,8 @@ void OpticalTactilePlugin::Configure(const Entity &_entity, this->dataPtr->sensorSize = _sdf->GetParent()->GetElement("link")->GetElement("collision")-> GetElement("geometry")->GetElement("box")-> - Get("size"); - igndbg << "Setting sensor size to box collision size: [" + Get("size"); + gzdbg << "Setting sensor size to box collision size: [" << this->dataPtr->sensorSize << "]" << std::endl; } } @@ -334,15 +334,15 @@ void OpticalTactilePlugin::Configure(const Entity &_entity, // Advertise topic for normal forces std::string normalForcesTopic = "/" + this->dataPtr->ns + "/normal_forces"; this->dataPtr->normalForcesPub = - this->dataPtr->node.Advertise(normalForcesTopic); + this->dataPtr->node.Advertise(normalForcesTopic); if (!this->dataPtr->normalForcesPub) { - ignerr << "Error advertising topic [" << normalForcesTopic << "]" + gzerr << "Error advertising topic [" << normalForcesTopic << "]" << std::endl; } else { - ignmsg << "Topic publishing normal forces [" << normalForcesTopic << "]" + gzmsg << "Topic publishing normal forces [" << normalForcesTopic << "]" << std::endl; } @@ -351,12 +351,12 @@ void OpticalTactilePlugin::Configure(const Entity &_entity, if (!this->dataPtr->node.Advertise(enableService, &OpticalTactilePluginPrivate::Enable, this->dataPtr.get())) { - ignerr << "Error advertising service [" << enableService << "]" + gzerr << "Error advertising service [" << enableService << "]" << std::endl; } else { - ignmsg << "Service to enable tactile sensor [" << enableService << "]" + gzmsg << "Service to enable tactile sensor [" << enableService << "]" << std::endl; } } @@ -394,12 +394,12 @@ void OpticalTactilePlugin::PreUpdate(const UpdateInfo &_info, } // Get the tactile sensor pose, i.e. the model pose - ignition::math::Pose3d tactileSensorPose = + gz::math::Pose3d tactileSensorPose = _ecm.Component( this->dataPtr->model.Entity())->Data(); // Depth camera data is float, so convert Pose3d to Pose3f - this->dataPtr->tactileSensorWorldPose = ignition::math::Pose3f( + this->dataPtr->tactileSensorWorldPose = gz::math::Pose3f( tactileSensorPose.Pos().X(), tactileSensorPose.Pos().Y(), tactileSensorPose.Pos().Z(), @@ -412,8 +412,8 @@ void OpticalTactilePlugin::PreUpdate(const UpdateInfo &_info, ////////////////////////////////////////////////// void OpticalTactilePlugin::PostUpdate( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("OpticalTactilePlugin::PostUpdate"); @@ -473,7 +473,7 @@ void OpticalTactilePluginPrivate::Load(const EntityComponentManager &_ecm) { if (!this->initErrorPrinted) { - ignerr << "Plugin must have exactly 1 link (only printed once)" + gzerr << "Plugin must have exactly 1 link (only printed once)" << std::endl; this->initErrorPrinted = true; } @@ -488,7 +488,7 @@ void OpticalTactilePluginPrivate::Load(const EntityComponentManager &_ecm) { if (!this->initErrorPrinted) { - ignerr << "Link must have at least 1 collision (only printed once)" + gzerr << "Link must have at least 1 collision (only printed once)" << std::endl; this->initErrorPrinted = true; } @@ -512,7 +512,7 @@ void OpticalTactilePluginPrivate::Load(const EntityComponentManager &_ecm) { if (!this->initErrorPrinted) { - ignerr << "Contact sensor geometry must be a box" + gzerr << "Contact sensor geometry must be a box" << " (only printed once)" << std::endl; this->initErrorPrinted = true; } @@ -550,7 +550,7 @@ void OpticalTactilePluginPrivate::Load(const EntityComponentManager &_ecm) { if (!this->initErrorPrinted) { - ignerr << "Link must have exactly 1 depth camera sensor and " + gzerr << "Link must have exactly 1 depth camera sensor and " << "1 contact sensor (only printed once)" << std::endl; this->initErrorPrinted = true; } @@ -562,7 +562,7 @@ void OpticalTactilePluginPrivate::Load(const EntityComponentManager &_ecm) { if (!this->initErrorPrinted) { - ignerr << "Depth camera should have an value " + gzerr << "Depth camera should have an value " << "(only printed once)" << std::endl; this->initErrorPrinted = true; } @@ -571,7 +571,7 @@ void OpticalTactilePluginPrivate::Load(const EntityComponentManager &_ecm) this->cameraUpdateRate = depthCameraSdf.UpdateRate(); // Depth camera data is float, so convert Pose3d to Pose3f - this->depthCameraOffset = ignition::math::Pose3f( + this->depthCameraOffset = gz::math::Pose3f( depthCameraPose.Data().Pos().X(), depthCameraPose.Data().Pos().Y(), depthCameraPose.Data().Pos().Z(), @@ -583,13 +583,13 @@ void OpticalTactilePluginPrivate::Load(const EntityComponentManager &_ecm) // Configure subscriber for depth camera images if (!depthCameraSdf.Element()->HasElement("topic")) { - ignwarn << "Depth camera publishing to __default__ topic. " + gzwarn << "Depth camera publishing to __default__ topic. " << "It's possible that two depth cameras are publishing into the same " << "topic" << std::endl; } else { - igndbg << "Depth camera publishing to " + gzdbg << "Depth camera publishing to " << depthCameraSdf.Topic() << " topic" << std::endl; } @@ -600,7 +600,7 @@ void OpticalTactilePluginPrivate::Load(const EntityComponentManager &_ecm) { if (!this->initErrorPrinted) { - ignerr << "Error subscribing to topic " << "[" << topic << "]. " + gzerr << "Error subscribing to topic " << "[" << topic << "]. " << " must not contain '/' (only printing once)" << std::endl; this->initErrorPrinted = true; } @@ -621,11 +621,11 @@ void OpticalTactilePluginPrivate::Load(const EntityComponentManager &_ecm) } ////////////////////////////////////////////////// -void OpticalTactilePluginPrivate::Enable(const ignition::msgs::Boolean &_req) +void OpticalTactilePluginPrivate::Enable(const gz::msgs::Boolean &_req) { if (_req.data() != this->enabled) { - ignmsg << "Enabling optical tactile sensor with namespace [" << this->ns + gzmsg << "Enabling optical tactile sensor with namespace [" << this->ns << "]: " << _req.data() << std::endl; } @@ -639,7 +639,7 @@ void OpticalTactilePluginPrivate::Enable(const ignition::msgs::Boolean &_req) ////////////////////////////////////////////////// void OpticalTactilePluginPrivate::DepthCameraCallback( - const ignition::msgs::PointCloudPacked &_msg) + const gz::msgs::PointCloudPacked &_msg) { // This check avoids running the callback at t=0 and getting // unexpected markers in the scene @@ -654,7 +654,7 @@ void OpticalTactilePluginPrivate::DepthCameraCallback( { if (field.datatype() != float32Type) { - ignerr << "FLOAT32 is expected for a casting to float *" << std::endl; + gzerr << "FLOAT32 is expected for a casting to float *" << std::endl; return; } } @@ -669,13 +669,13 @@ void OpticalTactilePluginPrivate::DepthCameraCallback( } ////////////////////////////////////////////////// -ignition::math::Vector3f OpticalTactilePluginPrivate::MapPointCloudData( +gz::math::Vector3f OpticalTactilePluginPrivate::MapPointCloudData( const uint64_t &_i, const uint64_t &_j, const char *_msgBuffer) { IGN_PROFILE("OpticalTactilePlugin::MapPointCloudData"); // Initialize return variable - ignition::math::Vector3f measuredPoint(0, 0, 0); + gz::math::Vector3f measuredPoint(0, 0, 0); // Nothing left to do if failed to initialize. if (!this->initialized) @@ -706,9 +706,9 @@ ignition::math::Vector3f OpticalTactilePluginPrivate::MapPointCloudData( bool pointInside = this->PointInsideSensor(measuredPoint); if (!pointInside) { - measuredPoint.X() = ignition::math::INF_F; - measuredPoint.Y() = ignition::math::INF_F; - measuredPoint.Z() = ignition::math::INF_F; + measuredPoint.X() = gz::math::INF_F; + measuredPoint.Y() = gz::math::INF_F; + measuredPoint.Z() = gz::math::INF_F; } return measuredPoint; @@ -716,7 +716,7 @@ ignition::math::Vector3f OpticalTactilePluginPrivate::MapPointCloudData( ////////////////////////////////////////////////// bool OpticalTactilePluginPrivate::PointInsideSensor( - ignition::math::Vector3f _point) + gz::math::Vector3f _point) { IGN_PROFILE("OpticalTactilePlugin::PointInsideSensor"); @@ -745,7 +745,7 @@ bool OpticalTactilePluginPrivate::PointInsideSensor( ////////////////////////////////////////////////// void OpticalTactilePluginPrivate::ComputeNormalForces( - const ignition::msgs::PointCloudPacked &_msg, + const gz::msgs::PointCloudPacked &_msg, const bool _visualizeForces) { IGN_PROFILE("OpticalTactilePlugin::ComputeNormalForces"); @@ -758,22 +758,22 @@ void OpticalTactilePluginPrivate::ComputeNormalForces( const char *msgBuffer = _msg.data().data(); // Declare variables for storing the XYZ points - ignition::math::Vector3f p1, p2, p3, p4, markerPosition; + gz::math::Vector3f p1, p2, p3, p4, markerPosition; // Message for publishing normal forces - ignition::msgs::Image normalsMsg; + gz::msgs::Image normalsMsg; normalsMsg.set_width(_msg.width()); normalsMsg.set_height(_msg.height()); normalsMsg.set_step(3 * sizeof(float) * _msg.width()); - normalsMsg.set_pixel_format_type(ignition::msgs::PixelFormatType::R_FLOAT32); + normalsMsg.set_pixel_format_type(gz::msgs::PixelFormatType::R_FLOAT32); uint32_t bufferSize = 3 * sizeof(float) * _msg.width() * _msg.height(); std::shared_ptr normalForcesBuffer(new char[bufferSize]); uint32_t bufferIndex; // Marker messages representing the normal forces - ignition::msgs::Marker positionMarkerMsg; - ignition::msgs::Marker forceMarkerMsg; + gz::msgs::Marker positionMarkerMsg; + gz::msgs::Marker forceMarkerMsg; // We don't get the image's edges because there are no adjacent points to // compute the forces @@ -792,14 +792,14 @@ void OpticalTactilePluginPrivate::ComputeNormalForces( float dxdi = (p1.X() - p2.X()) / std::abs(p1.Y() - p2.Y()); float dxdj = (p3.X() - p4.X()) / std::abs(p3.Z() - p4.Z()); - ignition::math::Vector3f direction(-1, -dxdi, -dxdj); + gz::math::Vector3f direction(-1, -dxdi, -dxdj); // todo(anyone) multiply vector by contact forces info // todo(anyone) Replace with MatrixX and use vector multiplication instead // of for-loops once the following issue is completed: - // https://github.com/ignitionrobotics/ign-math/issues/144 - ignition::math::Vector3f normalForce = direction.Normalized(); + // https://github.com/gazebosim/gz-math/issues/144 + gz::math::Vector3f normalForce = direction.Normalized(); // Add force to buffer // Forces buffer is composed of XYZ coordinates, while _msg buffer is @@ -833,10 +833,14 @@ void OpticalTactilePluginPrivate::ComputeNormalForces( } IGNITION_ADD_PLUGIN(OpticalTactilePlugin, - ignition::gazebo::System, + gz::sim::System, OpticalTactilePlugin::ISystemConfigure, OpticalTactilePlugin::ISystemPreUpdate, OpticalTactilePlugin::ISystemPostUpdate) +IGNITION_ADD_PLUGIN_ALIAS(OpticalTactilePlugin, + "gz::sim::systems::OpticalTactilePlugin") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(OpticalTactilePlugin, "ignition::gazebo::systems::OpticalTactilePlugin") diff --git a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh index 2ab466778d..80cb1e71ba 100644 --- a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh +++ b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh @@ -15,19 +15,19 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_OPTICAL_TACTILE_PLUGIN_HH_ -#define IGNITION_GAZEBO_SYSTEMS_OPTICAL_TACTILE_PLUGIN_HH_ +#ifndef GZ_SIM_SYSTEMS_OPTICAL_TACTILE_PLUGIN_HH_ +#define GZ_SIM_SYSTEMS_OPTICAL_TACTILE_PLUGIN_HH_ #include #include #include "Visualization.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { @@ -111,15 +111,15 @@ 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; }; } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz #endif diff --git a/src/systems/optical_tactile_plugin/Visualization.cc b/src/systems/optical_tactile_plugin/Visualization.cc index 6b0570a156..5f1bad70fd 100644 --- a/src/systems/optical_tactile_plugin/Visualization.cc +++ b/src/systems/optical_tactile_plugin/Visualization.cc @@ -21,18 +21,18 @@ #include "Visualization.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; using namespace optical_tactile_sensor; ////////////////////////////////////////////////// OpticalTactilePluginVisualization::OpticalTactilePluginVisualization( std::string &_modelName, - ignition::math::Vector3d &_sensorSize, + gz::math::Vector3d &_sensorSize, double &_forceLength, float &_cameraUpdateRate, - ignition::math::Pose3f &_depthCameraOffset, + gz::math::Pose3f &_depthCameraOffset, int &_visualizationResolution) : modelName(_modelName), sensorSize(_sensorSize), @@ -45,36 +45,36 @@ OpticalTactilePluginVisualization::OpticalTactilePluginVisualization( ////////////////////////////////////////////////// void OpticalTactilePluginVisualization::InitializeSensorMarkerMsg( - ignition::msgs::Marker &_sensorMarkerMsg) + gz::msgs::Marker &_sensorMarkerMsg) { // Reset all fields - _sensorMarkerMsg = ignition::msgs::Marker(); + _sensorMarkerMsg = gz::msgs::Marker(); // Initialize the marker for visualizing the sensor as a grey transparent box _sensorMarkerMsg.set_ns("sensor_" + this->modelName); _sensorMarkerMsg.set_id(1); - _sensorMarkerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); - _sensorMarkerMsg.set_type(ignition::msgs::Marker::BOX); - _sensorMarkerMsg.set_visibility(ignition::msgs::Marker::GUI); - ignition::msgs::Set(_sensorMarkerMsg.mutable_scale(), this->sensorSize); + _sensorMarkerMsg.set_action(gz::msgs::Marker::ADD_MODIFY); + _sensorMarkerMsg.set_type(gz::msgs::Marker::BOX); + _sensorMarkerMsg.set_visibility(gz::msgs::Marker::GUI); + gz::msgs::Set(_sensorMarkerMsg.mutable_scale(), this->sensorSize); // Set material properties - ignition::msgs::Set(_sensorMarkerMsg.mutable_material()-> + gz::msgs::Set(_sensorMarkerMsg.mutable_material()-> mutable_ambient(), math::Color(0.5, 0.5, 0.5, 0.75)); - ignition::msgs::Set(_sensorMarkerMsg.mutable_material()-> + gz::msgs::Set(_sensorMarkerMsg.mutable_material()-> mutable_diffuse(), math::Color(0.5, 0.5, 0.5, 0.75)); } ////////////////////////////////////////////////// void OpticalTactilePluginVisualization::RequestSensorMarkerMsg( - ignition::math::Pose3f const &_sensorPose) + gz::math::Pose3f const &_sensorPose) { - ignition::msgs::Marker sensorMarkerMsg; + gz::msgs::Marker sensorMarkerMsg; this->InitializeSensorMarkerMsg(sensorMarkerMsg); - ignition::msgs::Set(sensorMarkerMsg.mutable_pose(), - ignition::math::Pose3d(_sensorPose.Pos().X(), + gz::msgs::Set(sensorMarkerMsg.mutable_pose(), + gz::math::Pose3d(_sensorPose.Pos().X(), _sensorPose.Pos().Y(), _sensorPose.Pos().Z(), _sensorPose.Rot().W(), _sensorPose.Rot().X(), _sensorPose.Rot().Y(), _sensorPose.Rot().Z())); @@ -84,42 +84,42 @@ void OpticalTactilePluginVisualization::RequestSensorMarkerMsg( ////////////////////////////////////////////////// void OpticalTactilePluginVisualization::InitializeContactsMarkerMsg( - ignition::msgs::Marker &_contactsMarkerMsg) + gz::msgs::Marker &_contactsMarkerMsg) { // Reset all fields - _contactsMarkerMsg = ignition::msgs::Marker(); + _contactsMarkerMsg = gz::msgs::Marker(); // Initialize the marker for visualizing the physical contacts as red lines _contactsMarkerMsg.set_ns("contacts_" + this->modelName); _contactsMarkerMsg.set_id(1); - _contactsMarkerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); - _contactsMarkerMsg.set_type(ignition::msgs::Marker::LINE_LIST); - _contactsMarkerMsg.set_visibility(ignition::msgs::Marker::GUI); + _contactsMarkerMsg.set_action(gz::msgs::Marker::ADD_MODIFY); + _contactsMarkerMsg.set_type(gz::msgs::Marker::LINE_LIST); + _contactsMarkerMsg.set_visibility(gz::msgs::Marker::GUI); - ignition::msgs::Set(_contactsMarkerMsg.mutable_material()-> + gz::msgs::Set(_contactsMarkerMsg.mutable_material()-> mutable_ambient(), math::Color(1, 0, 0, 1)); - ignition::msgs::Set(_contactsMarkerMsg.mutable_material()-> + gz::msgs::Set(_contactsMarkerMsg.mutable_material()-> mutable_diffuse(), math::Color(1, 0, 0, 1)); _contactsMarkerMsg.mutable_lifetime()->set_sec(1); } ////////////////////////////////////////////////// void OpticalTactilePluginVisualization::AddContactToMarkerMsg( - ignition::msgs::Contact const &_contact, - ignition::msgs::Marker &_contactMarkerMsg) + gz::msgs::Contact const &_contact, + gz::msgs::Marker &_contactMarkerMsg) { // todo(anyone) once available, use normal field in the Contact message - ignition::math::Vector3d contactNormal(0, 0, 0.03); + gz::math::Vector3d contactNormal(0, 0, 0.03); // For each contact, add a line marker starting from the contact position, // ending at the endpoint of the normal. for (auto const &position : _contact.position()) { - ignition::math::Vector3d startPoint = ignition::msgs::Convert(position); - ignition::math::Vector3d endPoint = startPoint + contactNormal; + gz::math::Vector3d startPoint = gz::msgs::Convert(position); + gz::math::Vector3d endPoint = startPoint + contactNormal; - ignition::msgs::Set(_contactMarkerMsg.add_point(), startPoint); - ignition::msgs::Set(_contactMarkerMsg.add_point(), endPoint); + gz::msgs::Set(_contactMarkerMsg.add_point(), startPoint); + gz::msgs::Set(_contactMarkerMsg.add_point(), endPoint); } } @@ -127,7 +127,7 @@ void OpticalTactilePluginVisualization::AddContactToMarkerMsg( void OpticalTactilePluginVisualization::RequestContactsMarkerMsg( const components::ContactSensorData *_contacts) { - ignition::msgs::Marker contactsMarkerMsg; + gz::msgs::Marker contactsMarkerMsg; this->InitializeContactsMarkerMsg(contactsMarkerMsg); for (const auto &contact : _contacts->Data().contact()) @@ -140,42 +140,42 @@ void OpticalTactilePluginVisualization::RequestContactsMarkerMsg( ////////////////////////////////////////////////// void OpticalTactilePluginVisualization::InitializeNormalForcesMarkerMsgs( - ignition::msgs::Marker &_positionMarkerMsg, - ignition::msgs::Marker &_forceMarkerMsg) + gz::msgs::Marker &_positionMarkerMsg, + gz::msgs::Marker &_forceMarkerMsg) { - _positionMarkerMsg = ignition::msgs::Marker(); - _forceMarkerMsg = ignition::msgs::Marker(); + _positionMarkerMsg = gz::msgs::Marker(); + _forceMarkerMsg = gz::msgs::Marker(); // Initialize marker messages for position and force of the contacts // Positions computed from camera _positionMarkerMsg.set_ns("positions_" + this->modelName); _positionMarkerMsg.set_id(1); - _positionMarkerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); - _positionMarkerMsg.set_type(ignition::msgs::Marker::POINTS); - _positionMarkerMsg.set_visibility(ignition::msgs::Marker::GUI); - ignition::msgs::Set(_positionMarkerMsg.mutable_scale(), - ignition::math::Vector3d(1, 1, 1)); + _positionMarkerMsg.set_action(gz::msgs::Marker::ADD_MODIFY); + _positionMarkerMsg.set_type(gz::msgs::Marker::POINTS); + _positionMarkerMsg.set_visibility(gz::msgs::Marker::GUI); + gz::msgs::Set(_positionMarkerMsg.mutable_scale(), + gz::math::Vector3d(1, 1, 1)); _forceMarkerMsg.set_ns("forces_" + this->modelName); _forceMarkerMsg.set_id(1); - _forceMarkerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); - _forceMarkerMsg.set_type(ignition::msgs::Marker::LINE_LIST); - _forceMarkerMsg.set_visibility(ignition::msgs::Marker::GUI); + _forceMarkerMsg.set_action(gz::msgs::Marker::ADD_MODIFY); + _forceMarkerMsg.set_type(gz::msgs::Marker::LINE_LIST); + _forceMarkerMsg.set_visibility(gz::msgs::Marker::GUI); // Set material properties and lifetime // Blue points for positions - ignition::msgs::Set(_positionMarkerMsg.mutable_material()-> + gz::msgs::Set(_positionMarkerMsg.mutable_material()-> mutable_ambient(), math::Color(0, 0, 1, 1)); - ignition::msgs::Set(_positionMarkerMsg.mutable_material()-> + gz::msgs::Set(_positionMarkerMsg.mutable_material()-> mutable_diffuse(), math::Color(0, 0, 1, 1)); _positionMarkerMsg.mutable_lifetime()->set_nsec( static_cast(this->cameraUpdateRate * 1000000000)); // Green lines for forces - ignition::msgs::Set(_forceMarkerMsg.mutable_material()-> + gz::msgs::Set(_forceMarkerMsg.mutable_material()-> mutable_ambient(), math::Color(0, 1, 0, 1)); - ignition::msgs::Set(_forceMarkerMsg.mutable_material()-> + gz::msgs::Set(_forceMarkerMsg.mutable_material()-> mutable_diffuse(), math::Color(0, 1, 0, 1)); _forceMarkerMsg.mutable_lifetime()->set_sec( static_cast(this->cameraUpdateRate * 1000000000)); @@ -183,11 +183,11 @@ void OpticalTactilePluginVisualization::InitializeNormalForcesMarkerMsgs( ////////////////////////////////////////////////// void OpticalTactilePluginVisualization::AddNormalForceToMarkerMsgs( - ignition::msgs::Marker &_positionMarkerMsg, - ignition::msgs::Marker &_forceMarkerMsg, - ignition::math::Vector3f &_position, - ignition::math::Vector3f &_normalForce, - ignition::math::Pose3f &_sensorWorldPose) + gz::msgs::Marker &_positionMarkerMsg, + gz::msgs::Marker &_forceMarkerMsg, + gz::math::Vector3f &_position, + gz::math::Vector3f &_normalForce, + gz::math::Pose3f &_sensorWorldPose) { // Check if messages have been initialized if (!this->normalForcesMsgsAreInitialized) @@ -199,22 +199,22 @@ void OpticalTactilePluginVisualization::AddNormalForceToMarkerMsgs( // We need to compute the two points that form a normal force (start and end // points) with reference to the simulation origin - ignition::math::Vector3f normalForcePositionFromSensor( + gz::math::Vector3f normalForcePositionFromSensor( _position.X(), _position.Y(), _position.Z()); - ignition::math::Quaternionf normalForceOrientationFromSensor; + gz::math::Quaternionf normalForceOrientationFromSensor; normalForceOrientationFromSensor.SetFrom2Axes( - ignition::math::Vector3f(0, 0, 1), _normalForce); + gz::math::Vector3f(0, 0, 1), _normalForce); - ignition::math::Pose3f normalForcePoseFromSensor( + gz::math::Pose3f normalForcePoseFromSensor( normalForcePositionFromSensor, normalForceOrientationFromSensor); - ignition::math::Pose3f normalForcePoseFromWorld = _sensorWorldPose * + gz::math::Pose3f normalForcePoseFromWorld = _sensorWorldPose * this->depthCameraOffset * normalForcePoseFromSensor; normalForcePoseFromWorld.Correct(); // Get the start point of the normal force - ignition::math::Vector3f startPointFromWorld = + gz::math::Vector3f startPointFromWorld = normalForcePoseFromWorld.Pos(); // Move the normal force pose a distance of forceLength along the direction @@ -226,7 +226,7 @@ void OpticalTactilePluginVisualization::AddNormalForceToMarkerMsgs( normalForcePoseFromSensor; normalForcePoseFromWorld.Correct(); - ignition::math::Vector3f endPointFromWorld = + gz::math::Vector3f endPointFromWorld = normalForcePoseFromWorld.Pos(); // Check invalid points to avoid data transfer overhead @@ -234,23 +234,23 @@ void OpticalTactilePluginVisualization::AddNormalForceToMarkerMsgs( return; // Position - ignition::msgs::Set(_positionMarkerMsg.add_point(), - ignition::math::Vector3d(startPointFromWorld.X(), + gz::msgs::Set(_positionMarkerMsg.add_point(), + gz::math::Vector3d(startPointFromWorld.X(), startPointFromWorld.Y(), startPointFromWorld.Z())); // Normal - ignition::msgs::Set(_forceMarkerMsg.add_point(), - ignition::math::Vector3d(startPointFromWorld.X(), + gz::msgs::Set(_forceMarkerMsg.add_point(), + gz::math::Vector3d(startPointFromWorld.X(), startPointFromWorld.Y(), startPointFromWorld.Z())); - ignition::msgs::Set(_forceMarkerMsg.add_point(), - ignition::math::Vector3d(endPointFromWorld.X(), + gz::msgs::Set(_forceMarkerMsg.add_point(), + gz::math::Vector3d(endPointFromWorld.X(), endPointFromWorld.Y(), endPointFromWorld.Z())); } ////////////////////////////////////////////////// void OpticalTactilePluginVisualization::RequestNormalForcesMarkerMsgs( - ignition::msgs::Marker &_positionMarkerMsg, - ignition::msgs::Marker &_forceMarkerMsg) + gz::msgs::Marker &_positionMarkerMsg, + gz::msgs::Marker &_forceMarkerMsg) { this->node.Request("/marker", _positionMarkerMsg); this->node.Request("/marker", _forceMarkerMsg); @@ -262,18 +262,18 @@ void OpticalTactilePluginVisualization::RequestNormalForcesMarkerMsgs( ////////////////////////////////////////////////// void OpticalTactilePluginVisualization::RemoveNormalForcesAndContactsMarkers() { - ignition::msgs::Marker positionMarkerMsg; - ignition::msgs::Marker forceMarkerMsg; - ignition::msgs::Marker contactMarkerMsg; + gz::msgs::Marker positionMarkerMsg; + gz::msgs::Marker forceMarkerMsg; + gz::msgs::Marker contactMarkerMsg; positionMarkerMsg.set_ns("positions_" + this->modelName); - positionMarkerMsg.set_action(ignition::msgs::Marker::DELETE_ALL); + positionMarkerMsg.set_action(gz::msgs::Marker::DELETE_ALL); forceMarkerMsg.set_ns("forces_" + this->modelName); - forceMarkerMsg.set_action(ignition::msgs::Marker::DELETE_ALL); + forceMarkerMsg.set_action(gz::msgs::Marker::DELETE_ALL); contactMarkerMsg.set_ns("contacts_" + this->modelName); - contactMarkerMsg.set_action(ignition::msgs::Marker::DELETE_ALL); + contactMarkerMsg.set_action(gz::msgs::Marker::DELETE_ALL); this->node.Request("/marker", positionMarkerMsg); this->node.Request("/marker", forceMarkerMsg); diff --git a/src/systems/optical_tactile_plugin/Visualization.hh b/src/systems/optical_tactile_plugin/Visualization.hh index d3d57d446e..ef6711f309 100644 --- a/src/systems/optical_tactile_plugin/Visualization.hh +++ b/src/systems/optical_tactile_plugin/Visualization.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_OPTICAL_TACTILE_PLUGIN_VISUALIZATION_HH_ -#define IGNITION_GAZEBO_SYSTEMS_OPTICAL_TACTILE_PLUGIN_VISUALIZATION_HH_ +#ifndef GZ_SIM_SYSTEMS_OPTICAL_TACTILE_PLUGIN_VISUALIZATION_HH_ +#define GZ_SIM_SYSTEMS_OPTICAL_TACTILE_PLUGIN_VISUALIZATION_HH_ #include #include @@ -27,12 +27,12 @@ #include "gz/sim/components/ContactSensorData.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { @@ -57,38 +57,38 @@ namespace optical_tactile_sensor /// visualizationResolution attribute public: OpticalTactilePluginVisualization( std::string &_modelName, - ignition::math::Vector3d &_sensorSize, + gz::math::Vector3d &_sensorSize, double &_forceLength, float &_cameraUpdateRate, - ignition::math::Pose3f &_depthCameraOffset, + gz::math::Pose3f &_depthCameraOffset, int &_visualizationResolution); /// \brief Initialize the marker message representing the optical tactile /// sensor /// \param[out] _sensorMarkerMsg Message for visualizing the sensor private: void InitializeSensorMarkerMsg( - ignition::msgs::Marker &_sensorMarkerMsg); + gz::msgs::Marker &_sensorMarkerMsg); /// \brief Request the "/marker" service for the sensor marker. /// This can be helpful when debbuging, given that there shouldn't be a /// visual tag in the plugin's model /// \param[in] _sensorPose Pose of the optical tactile sensor public: void RequestSensorMarkerMsg( - ignition::math::Pose3f const &_sensorPose); + gz::math::Pose3f const &_sensorPose); /// \brief Initialize the marker message representing the contacts from the /// contact sensor /// \param[out] _contactsMarkerMsg Message for visualizing the contacts private: void InitializeContactsMarkerMsg( - ignition::msgs::Marker &_contactsMarkerMsg); + gz::msgs::Marker &_contactsMarkerMsg); /// \brief Add a contact to the marker message representing the contacts /// from the contact sensor based on physics /// \param[in] _contact Contact to be added /// \param[out] _contactsMarkerMsg Message for visualizing the contacts public: void AddContactToMarkerMsg( - ignition::msgs::Contact const &_contact, - ignition::msgs::Marker &_contactsMarkerMsg); + gz::msgs::Contact const &_contact, + gz::msgs::Marker &_contactsMarkerMsg); /// \brief Request the "/marker" service for the contacts marker. /// \param[in] _contacts Contacts to visualize @@ -101,8 +101,8 @@ namespace optical_tactile_sensor /// \param[out] _forceMarkerMsg Message for visualizing the contact /// normal forces private: void InitializeNormalForcesMarkerMsgs( - ignition::msgs::Marker &_positionMarkerMsg, - ignition::msgs::Marker &_forceMarkerMsg); + gz::msgs::Marker &_positionMarkerMsg, + gz::msgs::Marker &_forceMarkerMsg); /// \brief Create a marker messages representing the normal force computed /// from depth camera @@ -117,11 +117,11 @@ namespace optical_tactile_sensor /// \param[in] _sensorWorldPose Pose of the plugin's model referenced to /// the world's origin public: void AddNormalForceToMarkerMsgs( - ignition::msgs::Marker &_positionMarkerMsg, - ignition::msgs::Marker &_forceMarkerMsg, - ignition::math::Vector3f &_position, - ignition::math::Vector3f &_normalForce, - ignition::math::Pose3f &_sensorWorldPose); + gz::msgs::Marker &_positionMarkerMsg, + gz::msgs::Marker &_forceMarkerMsg, + gz::math::Vector3f &_position, + gz::math::Vector3f &_normalForce, + gz::math::Pose3f &_sensorWorldPose); /// \brief Request the "/marker" service for the marker messages /// representing the normal forces @@ -130,20 +130,20 @@ namespace optical_tactile_sensor /// \param[in] _forceMarkerMsg Message for visualizing the contact /// normal forces public: void RequestNormalForcesMarkerMsgs( - ignition::msgs::Marker &_positionMarkerMsg, - ignition::msgs::Marker &_forceMarkerMsg); + gz::msgs::Marker &_positionMarkerMsg, + gz::msgs::Marker &_forceMarkerMsg); /// \brief Remove all normal forces and contact markers public: void RemoveNormalForcesAndContactsMarkers(); /// \brief Transport node to request the /marker service - private: ignition::transport::Node node; + private: gz::transport::Node node; /// \brief Name of the model to which the sensor is attached private: std::string modelName; /// \brief Size of the contact sensor - private: ignition::math::Vector3d sensorSize; + private: gz::math::Vector3d sensorSize; /// \brief Length of the visualized force cylinder private: double forceLength; @@ -152,7 +152,7 @@ namespace optical_tactile_sensor private: float cameraUpdateRate; /// \brief Offset between depth camera pose and model pose - private: ignition::math::Pose3f depthCameraOffset; + private: gz::math::Pose3f depthCameraOffset; /// \brief Resolution of the sensor in pixels to skip. private: int visualizationResolution; @@ -163,7 +163,7 @@ namespace optical_tactile_sensor } // namespace optical_tactile_sensor } // namespace systems } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace gazebo -} // namespace ignition +} // namespace sim +} // namespace gz #endif diff --git a/src/systems/particle_emitter/ParticleEmitter.cc b/src/systems/particle_emitter/ParticleEmitter.cc index 874dbdb374..fadcaf8644 100644 --- a/src/systems/particle_emitter/ParticleEmitter.cc +++ b/src/systems/particle_emitter/ParticleEmitter.cc @@ -37,28 +37,28 @@ using namespace std::chrono_literals; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; // Private data class. -class ignition::gazebo::systems::ParticleEmitterPrivate +class gz::sim::systems::ParticleEmitterPrivate { /// \brief Callback for receiving particle emitter commands. /// \param[in] _msg Particle emitter message. - public: void OnCmd(const ignition::msgs::ParticleEmitter &_msg, + public: void OnCmd(const gz::msgs::ParticleEmitter &_msg, const transport::MessageInfo &_info); - public: bool EmittersService(ignition::msgs::ParticleEmitter_V &_res); + public: bool EmittersService(gz::msgs::ParticleEmitter_V &_res); /// \brief The transport node. - public: ignition::transport::Node node; + public: gz::transport::Node node; /// \brief Map of topic name to particle emitter entity. public: std::map emitterTopicMap; /// \brief Map of Entity to particle emitter command requested externally. - public: std::map userCmd; + public: std::map userCmd; /// \brief A mutex to protect the user command. public: std::mutex mutex; @@ -83,14 +83,14 @@ void ParticleEmitterPrivate::OnCmd(const msgs::ParticleEmitter &_msg, } else { - ignwarn << "Topic[" << _info.Topic() << "] is not known to the particle " + gzwarn << "Topic[" << _info.Topic() << "] is not known to the particle " "emitter system. The requested command will be ignored.\n"; } } ////////////////////////////////////////////////// bool ParticleEmitterPrivate::EmittersService( - ignition::msgs::ParticleEmitter_V &_res) + gz::msgs::ParticleEmitter_V &_res) { _res.Clear(); @@ -115,7 +115,7 @@ void ParticleEmitter::Configure(const Entity &_entity, const components::Name *name = _ecm.Component(_entity); if (name == nullptr) { - ignerr << "World with id: " << _entity + gzerr << "World with id: " << _entity << " has no name. ParticleEmitter cannot create transport topics\n"; return; } @@ -124,19 +124,19 @@ void ParticleEmitter::Configure(const Entity &_entity, if (this->dataPtr->node.Advertise(emittersService, &ParticleEmitterPrivate::EmittersService, this->dataPtr.get())) { - ignmsg << "Serving particle emitter information on [" + gzmsg << "Serving particle emitter information on [" << emittersService << "]" << std::endl; } else { - ignerr << "Something went wrong, failed to advertise [" << emittersService + gzerr << "Something went wrong, failed to advertise [" << emittersService << "]" << std::endl; } } ////////////////////////////////////////////////// -void ParticleEmitter::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void ParticleEmitter::PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("ParticleEmitter::PreUpdate"); @@ -176,11 +176,11 @@ void ParticleEmitter::PreUpdate(const ignition::gazebo::UpdateInfo &_info, if (!this->dataPtr->node.Subscribe( topic, &ParticleEmitterPrivate::OnCmd, this->dataPtr.get())) { - ignerr << "Error subscribing to topic [" << topic << "]. " + gzerr << "Error subscribing to topic [" << topic << "]. " << "Particle emitter will not receive updates." << std::endl; return false; } - ignmsg << "Particle emitter[" + gzmsg << "Particle emitter[" << scopedName(_entity, _ecm, "::", false) << "] subscribed " << "to command messages on topic[" << topic << "]\n"; @@ -247,9 +247,13 @@ void ParticleEmitter::PreUpdate(const ignition::gazebo::UpdateInfo &_info, } IGNITION_ADD_PLUGIN(ParticleEmitter, - ignition::gazebo::System, + gz::sim::System, ParticleEmitter::ISystemConfigure, ParticleEmitter::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(ParticleEmitter, + "gz::sim::systems::ParticleEmitter") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(ParticleEmitter, "ignition::gazebo::systems::ParticleEmitter") diff --git a/src/systems/particle_emitter/ParticleEmitter.hh b/src/systems/particle_emitter/ParticleEmitter.hh index 06fb0ae988..b2878f9381 100644 --- a/src/systems/particle_emitter/ParticleEmitter.hh +++ b/src/systems/particle_emitter/ParticleEmitter.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_PARTICLE_EMITTER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_PARTICLE_EMITTER_HH_ +#ifndef GZ_SIM_SYSTEMS_PARTICLE_EMITTER_HH_ +#define GZ_SIM_SYSTEMS_PARTICLE_EMITTER_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { class ParticleEmitterPrivate; @@ -54,8 +54,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/particle_emitter2/ParticleEmitter2.cc b/src/systems/particle_emitter2/ParticleEmitter2.cc index 15eef178b7..da5577e2c3 100644 --- a/src/systems/particle_emitter2/ParticleEmitter2.cc +++ b/src/systems/particle_emitter2/ParticleEmitter2.cc @@ -37,28 +37,28 @@ using namespace std::chrono_literals; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; // Private data class. -class ignition::gazebo::systems::ParticleEmitter2Private +class gz::sim::systems::ParticleEmitter2Private { /// \brief Callback for receiving particle emitter commands. /// \param[in] _msg Particle emitter message. - public: void OnCmd(const ignition::msgs::ParticleEmitter &_msg, + public: void OnCmd(const gz::msgs::ParticleEmitter &_msg, const transport::MessageInfo &_info); - public: bool EmittersService(ignition::msgs::ParticleEmitter_V &_res); + public: bool EmittersService(gz::msgs::ParticleEmitter_V &_res); /// \brief The transport node. - public: ignition::transport::Node node; + public: gz::transport::Node node; /// \brief Map of topic name to particle emitter entity. public: std::map emitterTopicMap; /// \brief Map of Entity to particle emitter command requested externally. - public: std::map userCmd; + public: std::map userCmd; /// \brief A mutex to protect the user command. public: std::mutex mutex; @@ -83,14 +83,14 @@ void ParticleEmitter2Private::OnCmd(const msgs::ParticleEmitter &_msg, } else { - ignwarn << "Topic[" << _info.Topic() << "] is not known to the particle " + gzwarn << "Topic[" << _info.Topic() << "] is not known to the particle " "emitter system. The requested command will be ignored.\n"; } } ////////////////////////////////////////////////// bool ParticleEmitter2Private::EmittersService( - ignition::msgs::ParticleEmitter_V &_res) + gz::msgs::ParticleEmitter_V &_res) { _res.Clear(); @@ -115,7 +115,7 @@ void ParticleEmitter2::Configure(const Entity &_entity, const components::Name *name = _ecm.Component(_entity); if (name == nullptr) { - ignerr << "World with id: " << _entity + gzerr << "World with id: " << _entity << " has no name. ParticleEmitter2 cannot create transport topics\n"; return; } @@ -124,19 +124,19 @@ void ParticleEmitter2::Configure(const Entity &_entity, if (this->dataPtr->node.Advertise(emittersService, &ParticleEmitter2Private::EmittersService, this->dataPtr.get())) { - ignmsg << "Serving particle emitter information on [" + gzmsg << "Serving particle emitter information on [" << emittersService << "]" << std::endl; } else { - ignerr << "Something went wrong, failed to advertise [" << emittersService + gzerr << "Something went wrong, failed to advertise [" << emittersService << "]" << std::endl; } } ////////////////////////////////////////////////// -void ParticleEmitter2::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void ParticleEmitter2::PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("ParticleEmitter2::PreUpdate"); @@ -176,11 +176,11 @@ void ParticleEmitter2::PreUpdate(const ignition::gazebo::UpdateInfo &_info, if (!this->dataPtr->node.Subscribe( topic, &ParticleEmitter2Private::OnCmd, this->dataPtr.get())) { - ignerr << "Error subscribing to topic [" << topic << "]. " + gzerr << "Error subscribing to topic [" << topic << "]. " << "Particle emitter will not receive updates." << std::endl; return false; } - ignmsg << "Particle emitter[" + gzmsg << "Particle emitter[" << scopedName(_entity, _ecm, "::", false) << "] subscribed " << "to command messages on topic[" << topic << "]\n"; @@ -247,9 +247,13 @@ void ParticleEmitter2::PreUpdate(const ignition::gazebo::UpdateInfo &_info, } IGNITION_ADD_PLUGIN(ParticleEmitter2, - ignition::gazebo::System, + gz::sim::System, ParticleEmitter2::ISystemConfigure, ParticleEmitter2::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(ParticleEmitter2, + "gz::sim::systems::ParticleEmitter2") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(ParticleEmitter2, "ignition::gazebo::systems::ParticleEmitter2") diff --git a/src/systems/particle_emitter2/ParticleEmitter2.hh b/src/systems/particle_emitter2/ParticleEmitter2.hh index 81b00f3082..df35b8e40a 100644 --- a/src/systems/particle_emitter2/ParticleEmitter2.hh +++ b/src/systems/particle_emitter2/ParticleEmitter2.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_PARTICLE_EMITTER2_HH_ -#define IGNITION_GAZEBO_SYSTEMS_PARTICLE_EMITTER2_HH_ +#ifndef GZ_SIM_SYSTEMS_PARTICLE_EMITTER2_HH_ +#define GZ_SIM_SYSTEMS_PARTICLE_EMITTER2_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { class ParticleEmitter2Private; @@ -41,18 +41,18 @@ namespace systems /// `/model/{model_name}/link/{link_name}/particle_emitter/{emitter_name}/cmd` /// /// \todo(nkoenig) Plan for ParticleEmitter and ParticleEmitter2: - /// 1. Deprecate ParticleEmitter in Ignition Fortress. - /// 2. Remove ParticleEmitter in Ignition G. - /// 3. Copy ParticleEmitter2 to ParticleEmitter in Ignition G. - /// 4. Deprecrate ParticleEmitter2 in Ignition G. - /// 5. Remove ParticleEmitter2 in Ignition H. + /// 1. Deprecate ParticleEmitter in Gazebo Fortress. + /// 2. Remove ParticleEmitter in Gazebo G. + /// 3. Copy ParticleEmitter2 to ParticleEmitter in Gazebo G. + /// 4. Deprecrate ParticleEmitter2 in Gazebo G. + /// 5. Remove ParticleEmitter2 in Gazebo H. class ParticleEmitter2 : public System, public ISystemConfigure, public ISystemPreUpdate { /// \brief Constructor - public: IGN_DEPRECATED(7) ParticleEmitter2(); + public: GZ_DEPRECATED(7) ParticleEmitter2(); // Documentation inherited public: void Configure(const Entity &_entity, @@ -62,8 +62,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/perfect_comms/PerfectComms.cc b/src/systems/perfect_comms/PerfectComms.cc index 75b7eefe81..ee226d1b0c 100644 --- a/src/systems/perfect_comms/PerfectComms.cc +++ b/src/systems/perfect_comms/PerfectComms.cc @@ -24,17 +24,17 @@ #include "gz/sim/Util.hh" #include "PerfectComms.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; -class ignition::gazebo::systems::PerfectComms::Implementation +class gz::sim::systems::PerfectComms::Implementation { }; ////////////////////////////////////////////////// PerfectComms::PerfectComms() - : dataPtr(ignition::utils::MakeUniqueImpl()) + : dataPtr(gz::utils::MakeUniqueImpl()) { } @@ -58,7 +58,7 @@ void PerfectComms::Step( { if (content.entity == kNullEntity) { - auto entities = gazebo::entitiesFromScopedName(content.modelName, _ecm); + auto entities = sim::entitiesFromScopedName(content.modelName, _ecm); if (entities.empty()) continue; @@ -107,9 +107,13 @@ void PerfectComms::Step( } IGNITION_ADD_PLUGIN(PerfectComms, - ignition::gazebo::System, + gz::sim::System, comms::ICommsModel::ISystemConfigure, comms::ICommsModel::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(PerfectComms, + "gz::sim::systems::PerfectComms") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(PerfectComms, "ignition::gazebo::systems::PerfectComms") diff --git a/src/systems/perfect_comms/PerfectComms.hh b/src/systems/perfect_comms/PerfectComms.hh index 14e200b518..be936d0137 100644 --- a/src/systems/perfect_comms/PerfectComms.hh +++ b/src/systems/perfect_comms/PerfectComms.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_PERFECTCOMMS_HH_ -#define IGNITION_GAZEBO_SYSTEMS_PERFECTCOMMS_HH_ +#ifndef GZ_SIM_SYSTEMS_PERFECTCOMMS_HH_ +#define GZ_SIM_SYSTEMS_PERFECTCOMMS_HH_ #include @@ -24,12 +24,12 @@ #include "gz/sim/comms/ICommsModel.hh" #include "gz/sim/System.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declarations. @@ -50,7 +50,7 @@ namespace systems EventManager &_eventMgr) override; // Documentation inherited. - public: void Step(const ignition::gazebo::UpdateInfo &_info, + public: void Step(const gz::sim::UpdateInfo &_info, const comms::Registry &_currentRegistry, comms::Registry &_newRegistry, EntityComponentManager &_ecm) override; diff --git a/src/systems/performer_detector/PerformerDetector.cc b/src/systems/performer_detector/PerformerDetector.cc index 9ce92bd417..0349581774 100644 --- a/src/systems/performer_detector/PerformerDetector.cc +++ b/src/systems/performer_detector/PerformerDetector.cc @@ -37,8 +37,8 @@ #include "PerformerDetector.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; ///////////////////////////////////////////////// @@ -50,7 +50,7 @@ void PerformerDetector::Configure(const Entity &_entity, this->model = Model(_entity); if (!this->model.Valid(_ecm)) { - ignerr << "PerformerDetector should be attached to a model entity. " + gzerr << "PerformerDetector should be attached to a model entity. " << "Failed to initialize." << std::endl; return; } @@ -73,7 +73,7 @@ void PerformerDetector::Configure(const Entity &_entity, if (!hasGeometry) { - ignerr << "'' is a required parameter for " + gzerr << "'' is a required parameter for " "PerformerDetector. Failed to initialize.\n"; return; } @@ -95,19 +95,19 @@ void PerformerDetector::Configure(const Entity &_entity, this->extraHeaderData[key] = value; else if (key.empty() && !value.empty()) { - ignerr << "Performer detector[" << this->detectorName << "] has an " + gzerr << "Performer detector[" << this->detectorName << "] has an " << "empty with an associated of [" << value << "]. " << "This will be ignored.\n"; } else if (value.empty() && !key.empty()) { - ignerr << "Performer detector[" << this->detectorName << "] has an " + gzerr << "Performer detector[" << this->detectorName << "] has an " << "empty with an associated of [" << key << "]. " << "This will be ignored.\n"; } else { - ignerr << "Performer detector[" << this->detectorName << "] has an " + gzerr << "Performer detector[" << this->detectorName << "] has an " << "empty element. This will be " << "ignored\n"; } @@ -120,7 +120,7 @@ void PerformerDetector::Configure(const Entity &_entity, "/performer_detector/status"}; auto topic = _sdf->Get("topic", defaultTopic).first; - ignmsg << "PerformerDetector publishing messages on " + gzmsg << "PerformerDetector publishing messages on " << "[" << topic << "]" << std::endl; transport::Node node; @@ -130,8 +130,8 @@ void PerformerDetector::Configure(const Entity &_entity, ////////////////////////////////////////////////// void PerformerDetector::PostUpdate( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) { IGN_PROFILE("PerformerDetector::PostUpdate"); @@ -173,7 +173,7 @@ void PerformerDetector::PostUpdate( auto perfBox = _geometry->Data().BoxShape(); if (nullptr == perfBox) { - ignerr << "Internal error: geometry of performer [" << _entity + gzerr << "Internal error: geometry of performer [" << _entity << "] missing box." << std::endl; return true; } @@ -260,9 +260,13 @@ void PerformerDetector::Publish( } IGNITION_ADD_PLUGIN(PerformerDetector, - ignition::gazebo::System, + gz::sim::System, 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 d2bb251a85..db72e2a296 100644 --- a/src/systems/performer_detector/PerformerDetector.hh +++ b/src/systems/performer_detector/PerformerDetector.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_PERFORMERDETECTOR_HH_ -#define IGNITION_GAZEBO_SYSTEMS_PERFORMERDETECTOR_HH_ +#ifndef GZ_SIM_SYSTEMS_PERFORMERDETECTOR_HH_ +#define GZ_SIM_SYSTEMS_PERFORMERDETECTOR_HH_ #include #include @@ -28,22 +28,22 @@ #include "gz/sim/Model.hh" #include "gz/sim/System.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { /// \brief A system system that publishes on a topic when a performer enters /// 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 - /// publishes an ignition.msgs.Pose message with the pose of the detected + /// gz::math::AxisAlignedBox. When a performer is detected, the system + /// publishes an gz.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 /// entity of the detected performer respectively. The header of the Pose @@ -66,7 +66,7 @@ namespace systems /// ``: Custom topic to be used for publishing when a performer is /// detected. If not set, the default topic with the following pattern would /// be used "/model//performer_detector/status". The topic type - /// is ignition.msgs.Pose + /// is gz.msgs.Pose /// ``: Detection region. Currently, only the `` geometry is /// supported. The position of the geometry is derived from the pose of the /// containing model. @@ -95,8 +95,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/CanonicalLinkModelTracker.hh b/src/systems/physics/CanonicalLinkModelTracker.hh index 9c63331647..0d59c5751d 100644 --- a/src/systems/physics/CanonicalLinkModelTracker.hh +++ b/src/systems/physics/CanonicalLinkModelTracker.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_PHYSICS_CANONICAL_LINK_MODEL_TRACKER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_PHYSICS_CANONICAL_LINK_MODEL_TRACKER_HH_ +#ifndef GZ_SIM_SYSTEMS_PHYSICS_CANONICAL_LINK_MODEL_TRACKER_HH_ +#define GZ_SIM_SYSTEMS_PHYSICS_CANONICAL_LINK_MODEL_TRACKER_HH_ #include #include @@ -26,9 +26,9 @@ #include "gz/sim/components/Model.hh" #include "gz/sim/config.hh" -namespace ignition::gazebo +namespace gz::sim { -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems::physics_system { /// \brief Helper class that keeps track of which models have a particular diff --git a/src/systems/physics/EntityFeatureMap.hh b/src/systems/physics/EntityFeatureMap.hh index 0fa6464fc5..1946a0c78f 100644 --- a/src/systems/physics/EntityFeatureMap.hh +++ b/src/systems/physics/EntityFeatureMap.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_PHYSICS_ENTITY_FEATURE_MAP_HH_ -#define IGNITION_GAZEBO_SYSTEMS_PHYSICS_ENTITY_FEATURE_MAP_HH_ +#ifndef GZ_SIM_SYSTEMS_PHYSICS_ENTITY_FEATURE_MAP_HH_ +#define GZ_SIM_SYSTEMS_PHYSICS_ENTITY_FEATURE_MAP_HH_ #include #include @@ -29,9 +29,9 @@ #include "gz/sim/Entity.hh" -namespace ignition::gazebo +namespace gz::sim { -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems::physics_system { // \brief Helper class that associates Gazebo entities with Physics entities @@ -94,7 +94,7 @@ namespace systems::physics_system /// requested feature. public: template PhysicsEntityPtr - EntityCast(gazebo::Entity _entity) const + EntityCast(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 32dbb73118..155aa884fe 100644 --- a/src/systems/physics/EntityFeatureMap_TEST.cc +++ b/src/systems/physics/EntityFeatureMap_TEST.cc @@ -34,8 +34,8 @@ #include "../../../test/helpers/EnvTestFixture.hh" #include "gz/sim/EntityComponentManager.hh" -using namespace ignition; -using namespace ignition::gazebo::systems::physics_system; +using namespace gz; +using namespace gz::sim::systems::physics_system; struct MinimumFeatureList : physics::FeatureList const std::string pluginLib = "libignition-physics-dartsim-plugin.so"; common::SystemPaths systemPaths; - systemPaths.AddPluginPaths({IGNITION_PHYSICS_ENGINE_INSTALL_DIR}); + systemPaths.AddPluginPaths({GZ_PHYSICS_ENGINE_INSTALL_DIR}); auto pathToLib = systemPaths.FindSharedLibrary(pluginLib); ASSERT_FALSE(pathToLib.empty()) << "Failed to find plugin [" << pluginLib << "]"; // Load engine plugin - ignition::plugin::Loader pluginLoader; + gz::plugin::Loader pluginLoader; auto plugins = pluginLoader.LoadLib(pathToLib); ASSERT_FALSE(plugins.empty()) << "Unable to load the [" << pathToLib << "] library."; @@ -82,7 +82,7 @@ class EntityFeatureMapFixture: public InternalFixture<::testing::Test> << pathToLib << "]"; this->engine = - ignition::physics::RequestEngine::From(plugin); ASSERT_NE(nullptr, this->engine); @@ -93,7 +93,7 @@ class EntityFeatureMapFixture: public InternalFixture<::testing::Test> public: EnginePtrType engine; }; -// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +// See https://github.com/gazebosim/gz-sim/issues/1175 TEST_F(EntityFeatureMapFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(AddCastRemoveEntity)) { @@ -113,13 +113,13 @@ TEST_F(EntityFeatureMapFixture, // 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; + sim::Entity gazeboWorld1Entity = 123; + 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(sim::kNullEntity, testMap.Get(testWorld1)); EXPECT_EQ(0u, testMap.TotalMapEntryCount()); testMap.AddEntity(gazeboWorld1Entity, testWorld1); @@ -168,12 +168,12 @@ TEST_F(EntityFeatureMapFixture, testMap.Remove(gazeboWorld1Entity); EXPECT_FALSE(testMap.HasEntity(gazeboWorld1Entity)); EXPECT_EQ(nullptr, testMap.Get(gazeboWorld1Entity)); - EXPECT_EQ(gazebo::kNullEntity, testMap.Get(testWorld1)); + EXPECT_EQ(sim::kNullEntity, testMap.Get(testWorld1)); EXPECT_EQ(4u, 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(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 5e04a02e51..33e913a3b3 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -143,51 +143,51 @@ #include "EntityFeatureMap.hh" -using namespace ignition; -using namespace ignition::gazebo; -using namespace ignition::gazebo::systems; -using namespace ignition::gazebo::systems::physics_system; -namespace components = ignition::gazebo::components; +using namespace gz; +using namespace gz::sim; +using namespace gz::sim::systems; +using namespace gz::sim::systems::physics_system; +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. /// New features can't be added to this list in minor / patch releases, in /// order to maintain backwards compatibility with downstream physics plugins. - public: struct MinimumFeatureList : ignition::physics::FeatureList< - ignition::physics::FindFreeGroupFeature, - ignition::physics::SetFreeGroupWorldPose, - ignition::physics::FreeGroupFrameSemantics, - ignition::physics::LinkFrameSemantics, - ignition::physics::ForwardStep, - ignition::physics::RemoveModelFromWorld, - ignition::physics::sdf::ConstructSdfLink, - ignition::physics::sdf::ConstructSdfModel, - ignition::physics::sdf::ConstructSdfWorld + public: struct MinimumFeatureList : gz::physics::FeatureList< + gz::physics::FindFreeGroupFeature, + gz::physics::SetFreeGroupWorldPose, + gz::physics::FreeGroupFrameSemantics, + gz::physics::LinkFrameSemantics, + gz::physics::ForwardStep, + gz::physics::RemoveModelFromWorld, + gz::physics::sdf::ConstructSdfLink, + gz::physics::sdf::ConstructSdfModel, + gz::physics::sdf::ConstructSdfWorld >{}; /// \brief Engine type with just the minimum features. - public: using EnginePtrType = ignition::physics::EnginePtr< - ignition::physics::FeaturePolicy3d, MinimumFeatureList>; + public: using EnginePtrType = gz::physics::EnginePtr< + gz::physics::FeaturePolicy3d, MinimumFeatureList>; /// \brief World type with just the minimum features. - public: using WorldPtrType = ignition::physics::WorldPtr< - ignition::physics::FeaturePolicy3d, MinimumFeatureList>; + public: using WorldPtrType = gz::physics::WorldPtr< + gz::physics::FeaturePolicy3d, MinimumFeatureList>; /// \brief Model type with just the minimum features. - public: using ModelPtrType = ignition::physics::ModelPtr< - ignition::physics::FeaturePolicy3d, MinimumFeatureList>; + public: using ModelPtrType = gz::physics::ModelPtr< + gz::physics::FeaturePolicy3d, MinimumFeatureList>; /// \brief Link type with just the minimum features. - public: using LinkPtrType = ignition::physics::LinkPtr< - ignition::physics::FeaturePolicy3d, MinimumFeatureList>; + public: using LinkPtrType = gz::physics::LinkPtr< + gz::physics::FeaturePolicy3d, MinimumFeatureList>; /// \brief Free group type with just the minimum features. - public: using FreeGroupPtrType = ignition::physics::FreeGroupPtr< - ignition::physics::FeaturePolicy3d, MinimumFeatureList>; + public: using FreeGroupPtrType = gz::physics::FreeGroupPtr< + gz::physics::FeaturePolicy3d, MinimumFeatureList>; /// \brief Create physics entities /// \param[in] _ecm Constant reference to ECM. @@ -250,7 +250,7 @@ class ignition::gazebo::systems::PhysicsPrivate /// \param[in] _dt Duration /// \returns Output data from the physics engine (this currently contains /// data for links that experienced a pose change in the physics step) - public: ignition::physics::ForwardStep::Output Step( + public: gz::physics::ForwardStep::Output Step( const std::chrono::steady_clock::duration &_dt); /// \brief Get data of links that were updated in the latest physics step. @@ -265,7 +265,7 @@ class ignition::gazebo::systems::PhysicsPrivate /// properly (models must be updated in topological order). public: std::map ChangedLinks( EntityComponentManager &_ecm, - const ignition::physics::ForwardStep::Output &_updatedLinks); + const gz::physics::ForwardStep::Output &_updatedLinks); /// \brief Helper function to update the pose of a model. /// \param[in] _model The model to update. @@ -314,7 +314,7 @@ class ignition::gazebo::systems::PhysicsPrivate /// \param[in] _from An ancestor of the _to entity. /// \param[in] _to A descendant of the _from entity. /// \return Pose transform between the two entities - public: ignition::math::Pose3d RelativePose(const Entity &_from, + public: gz::math::Pose3d RelativePose(const Entity &_from, const Entity &_to, const EntityComponentManager &_ecm) const; /// \brief Enable contact surface customization for the given world. @@ -335,7 +335,7 @@ class ignition::gazebo::systems::PhysicsPrivate /// \brief Keep track of poses for links attached to non-static models. /// This allows for skipping pose updates if a link's pose didn't change /// after a physics step. - public: std::unordered_map linkWorldPoses; + public: std::unordered_map linkWorldPoses; /// \brief Keep a mapping of canonical links to models that have this /// canonical link. Useful for updating model poses efficiently after a @@ -451,18 +451,18 @@ class ignition::gazebo::systems::PhysicsPrivate public: struct FrictionPyramidSlipComplianceFeatureList : physics::FeatureList< MinimumFeatureList, - ignition::physics::GetShapeFrictionPyramidSlipCompliance, - ignition::physics::SetShapeFrictionPyramidSlipCompliance>{}; + gz::physics::GetShapeFrictionPyramidSlipCompliance, + gz::physics::SetShapeFrictionPyramidSlipCompliance>{}; ////////////////////////////////////////////////// // Joints /// \brief Feature list to handle joints. - public: struct JointFeatureList : ignition::physics::FeatureList< + public: struct JointFeatureList : gz::physics::FeatureList< MinimumFeatureList, - ignition::physics::GetBasicJointProperties, - ignition::physics::GetBasicJointState, - ignition::physics::SetBasicJointState, - ignition::physics::sdf::ConstructSdfJoint>{}; + gz::physics::GetBasicJointProperties, + gz::physics::GetBasicJointState, + gz::physics::SetBasicJointState, + gz::physics::sdf::ConstructSdfJoint>{}; ////////////////////////////////////////////////// @@ -485,50 +485,50 @@ class ignition::gazebo::systems::PhysicsPrivate // Collisions /// \brief Feature list to handle collisions. - public: struct CollisionFeatureList : ignition::physics::FeatureList< + public: struct CollisionFeatureList : gz::physics::FeatureList< MinimumFeatureList, - ignition::physics::sdf::ConstructSdfCollision>{}; + gz::physics::sdf::ConstructSdfCollision>{}; /// \brief Feature list to handle contacts information. - public: struct ContactFeatureList : ignition::physics::FeatureList< + public: struct ContactFeatureList : gz::physics::FeatureList< CollisionFeatureList, - ignition::physics::GetContactsFromLastStepFeature>{}; + gz::physics::GetContactsFromLastStepFeature>{}; /// \brief Feature list to change contacts before they are applied to physics. public: struct SetContactPropertiesCallbackFeatureList : - ignition::physics::FeatureList< + gz::physics::FeatureList< ContactFeatureList, - ignition::physics::SetContactPropertiesCallbackFeature>{}; + gz::physics::SetContactPropertiesCallbackFeature>{}; /// \brief Collision type with collision features. - public: using ShapePtrType = ignition::physics::ShapePtr< - ignition::physics::FeaturePolicy3d, CollisionFeatureList>; + public: using ShapePtrType = gz::physics::ShapePtr< + gz::physics::FeaturePolicy3d, CollisionFeatureList>; /// \brief World type with just the minimum features. Non-pointer. - public: using WorldShapeType = ignition::physics::World< - ignition::physics::FeaturePolicy3d, ContactFeatureList>; + public: using WorldShapeType = gz::physics::World< + gz::physics::FeaturePolicy3d, ContactFeatureList>; ////////////////////////////////////////////////// // Collision filtering with bitmasks /// \brief Feature list to filter collisions with bitmasks. - public: struct CollisionMaskFeatureList : ignition::physics::FeatureList< + public: struct CollisionMaskFeatureList : gz::physics::FeatureList< CollisionFeatureList, - ignition::physics::CollisionFilterMaskFeature>{}; + gz::physics::CollisionFilterMaskFeature>{}; ////////////////////////////////////////////////// // Link force /// \brief Feature list for applying forces to links. - public: struct LinkForceFeatureList : ignition::physics::FeatureList< - ignition::physics::AddLinkExternalForceTorque>{}; + public: struct LinkForceFeatureList : gz::physics::FeatureList< + gz::physics::AddLinkExternalForceTorque>{}; ////////////////////////////////////////////////// // Bounding box /// \brief Feature list for model bounding box. - public: struct BoundingBoxFeatureList : ignition::physics::FeatureList< + public: struct BoundingBoxFeatureList : gz::physics::FeatureList< MinimumFeatureList, - ignition::physics::GetModelBoundingBox>{}; + gz::physics::GetModelBoundingBox>{}; ////////////////////////////////////////////////// @@ -562,8 +562,8 @@ class ignition::gazebo::systems::PhysicsPrivate ////////////////////////////////////////////////// // World velocity command public: struct WorldVelocityCommandFeatureList : - ignition::physics::FeatureList< - ignition::physics::SetFreeGroupWorldVelocity>{}; + gz::physics::FeatureList< + gz::physics::SetFreeGroupWorldVelocity>{}; ////////////////////////////////////////////////// @@ -582,29 +582,29 @@ class ignition::gazebo::systems::PhysicsPrivate /// \brief Feature list for heightmaps. /// Include MinimumFeatureList so created collision can be automatically /// up-cast. - public: struct HeightmapFeatureList : ignition::physics::FeatureList< + public: struct HeightmapFeatureList : gz::physics::FeatureList< CollisionFeatureList, physics::heightmap::AttachHeightmapShapeFeature>{}; ////////////////////////////////////////////////// // Collision detector /// \brief Feature list for setting and getting the collision detector - public: struct CollisionDetectorFeatureList : ignition::physics::FeatureList< - ignition::physics::CollisionDetector>{}; + public: struct CollisionDetectorFeatureList : gz::physics::FeatureList< + gz::physics::CollisionDetector>{}; ////////////////////////////////////////////////// // Solver /// \brief Feature list for setting and getting the solver - public: struct SolverFeatureList : ignition::physics::FeatureList< - ignition::physics::Solver>{}; + public: struct SolverFeatureList : gz::physics::FeatureList< + gz::physics::Solver>{}; ////////////////////////////////////////////////// // Nested Models /// \brief Feature list to construct nested models - public: struct NestedModelFeatureList : ignition::physics::FeatureList< + public: struct NestedModelFeatureList : gz::physics::FeatureList< MinimumFeatureList, - ignition::physics::sdf::ConstructSdfNestedModel>{}; + gz::physics::sdf::ConstructSdfNestedModel>{}; ////////////////////////////////////////////////// /// \brief World EntityFeatureMap @@ -773,23 +773,23 @@ void Physics::Configure(const Entity &_entity, // * Engines installed with ign-physics common::SystemPaths systemPaths; systemPaths.SetPluginPathEnv(this->dataPtr->pluginPathEnv); - systemPaths.AddPluginPaths({IGNITION_PHYSICS_ENGINE_INSTALL_DIR}); + systemPaths.AddPluginPaths({GZ_PHYSICS_ENGINE_INSTALL_DIR}); auto pathToLib = systemPaths.FindSharedLibrary(pluginLib); if (pathToLib.empty()) { - ignerr << "Failed to find plugin [" << pluginLib + gzerr << "Failed to find plugin [" << pluginLib << "]. Have you checked the " << this->dataPtr->pluginPathEnv << " environment variable?" << std::endl; return; } // Load engine plugin - ignition::plugin::Loader pluginLoader; + gz::plugin::Loader pluginLoader; auto plugins = pluginLoader.LoadLib(pathToLib); if (plugins.empty()) { - ignerr << "Unable to load the [" << pathToLib << "] library.\n"; + gzerr << "Unable to load the [" << pathToLib << "] library.\n"; return; } @@ -798,7 +798,7 @@ void Physics::Configure(const Entity &_entity, physics::FeaturePolicy3d>>(); if (classNames.empty()) { - ignerr << "No physics plugins found in library [" << pathToLib << "]." + gzerr << "No physics plugins found in library [" << pathToLib << "]." << std::endl; return; } @@ -810,24 +810,24 @@ void Physics::Configure(const Entity &_entity, if (!plugin) { - ignwarn << "Failed to instantiate [" << className << "] from [" + gzwarn << "Failed to instantiate [" << className << "] from [" << pathToLib << "]" << std::endl; continue; } - this->dataPtr->engine = ignition::physics::RequestEngine< - ignition::physics::FeaturePolicy3d, + this->dataPtr->engine = gz::physics::RequestEngine< + gz::physics::FeaturePolicy3d, PhysicsPrivate::MinimumFeatureList>::From(plugin); if (nullptr != this->dataPtr->engine) { - igndbg << "Loaded [" << className << "] from library [" + gzdbg << "Loaded [" << className << "] from library [" << pathToLib << "]" << std::endl; break; } - auto missingFeatures = ignition::physics::RequestEngine< - ignition::physics::FeaturePolicy3d, + auto missingFeatures = gz::physics::RequestEngine< + gz::physics::FeaturePolicy3d, PhysicsPrivate::MinimumFeatureList>::MissingFeatureNames(plugin); std::stringstream msg; @@ -837,12 +837,12 @@ void Physics::Configure(const Entity &_entity, { msg << "- " << feature << std::endl; } - ignwarn << msg.str(); + gzwarn << msg.str(); } if (nullptr == this->dataPtr->engine) { - ignerr << "Failed to load a valid physics engine from [" << pathToLib + gzerr << "Failed to load a valid physics engine from [" << pathToLib << "]." << std::endl; return; @@ -863,7 +863,7 @@ void Physics::Update(const UpdateInfo &_info, EntityComponentManager &_ecm) { this->dataPtr->CreatePhysicsEntities(_ecm); this->dataPtr->UpdatePhysics(_ecm); - ignition::physics::ForwardStep::Output stepOutput; + gz::physics::ForwardStep::Output stepOutput; // Only step if not paused. if (!_info.paused) { @@ -886,7 +886,7 @@ void Physics::Reset(const UpdateInfo &, EntityComponentManager &_ecm) if (this->dataPtr->engine) { - igndbg << "Resetting Physics\n"; + gzdbg << "Resetting Physics\n"; this->dataPtr->ResetPhysics(_ecm); } } @@ -924,7 +924,7 @@ void PhysicsPrivate::CreateWorldEntities(const EntityComponentManager &_ecm, { if (_warnIfEntityExists) { - ignwarn << "World entity [" << _entity + gzwarn << "World entity [" << _entity << "] marked as new, but it's already on the map." << std::endl; } @@ -950,7 +950,7 @@ void PhysicsPrivate::CreateWorldEntities(const EntityComponentManager &_ecm, static bool informed{false}; if (!informed) { - igndbg << "Attempting to set physics options, but the " + gzdbg << "Attempting to set physics options, but the " << "phyiscs engine doesn't support feature " << "[CollisionDetectorFeature]. Options will be ignored." << std::endl; @@ -976,7 +976,7 @@ void PhysicsPrivate::CreateWorldEntities(const EntityComponentManager &_ecm, static bool informed{false}; if (!informed) { - igndbg << "Attempting to set physics options, but the " + gzdbg << "Attempting to set physics options, but the " << "phyiscs engine doesn't support feature " << "[SolverFeature]. Options will be ignored." << std::endl; @@ -1013,7 +1013,7 @@ void PhysicsPrivate::CreateModelEntities(const EntityComponentManager &_ecm, { if (_warnIfEntityExists) { - ignwarn << "Model entity [" << _entity + gzwarn << "Model entity [" << _entity << "] marked as new, but it's already on the map." << std::endl; } @@ -1052,7 +1052,7 @@ void PhysicsPrivate::CreateModelEntities(const EntityComponentManager &_ecm, static bool informed{false}; if (!informed) { - igndbg << "Attempting to construct nested models, but the " + gzdbg << "Attempting to construct nested models, but the " << "phyiscs engine doesn't support feature " << "[ConstructSdfNestedModelFeature]. " << "Nested model will be ignored." @@ -1087,7 +1087,7 @@ void PhysicsPrivate::CreateModelEntities(const EntityComponentManager &_ecm, static bool informed{false}; if (!informed) { - igndbg << "Attempting to construct nested models, but the " + gzdbg << "Attempting to construct nested models, but the " << "physics engine doesn't support feature " << "[ConstructSdfNestedModelFeature]. " << "Nested model will be ignored." @@ -1115,14 +1115,14 @@ void PhysicsPrivate::CreateModelEntities(const EntityComponentManager &_ecm, } else { - ignerr << "Model: '" << _name->Data() << "' not loaded. " + gzerr << "Model: '" << _name->Data() << "' not loaded. " << "Failed to create nested model." << std::endl; } } else { - ignwarn << "Model's parent entity [" << _parent->Data() + gzwarn << "Model's parent entity [" << _parent->Data() << "] not found on world / model map." << std::endl; return true; } @@ -1161,7 +1161,7 @@ void PhysicsPrivate::CreateLinkEntities(const EntityComponentManager &_ecm, { if (_warnIfEntityExists) { - ignwarn << "Link entity [" << _entity + gzwarn << "Link entity [" << _entity << "] marked as new, but it's already on the map." << std::endl; } @@ -1173,7 +1173,7 @@ void PhysicsPrivate::CreateLinkEntities(const EntityComponentManager &_ecm, // Check if parent model exists if (!this->entityModelMap.HasEntity(_parent->Data())) { - ignwarn << "Link's parent entity [" << _parent->Data() + gzwarn << "Link's parent entity [" << _parent->Data() << "] not found on model map." << std::endl; return true; } @@ -1233,7 +1233,7 @@ void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm, { if (_warnIfEntityExists) { - ignwarn << "Collision entity [" << _entity + gzwarn << "Collision entity [" << _entity << "] marked as new, but it's already on the map." << std::endl; } @@ -1243,7 +1243,7 @@ void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm, // Check if parent link exists if (!this->entityLinkMap.HasEntity(_parent->Data())) { - ignwarn << "Collision's parent entity [" << _parent->Data() + gzwarn << "Collision's parent entity [" << _parent->Data() << "] not found on link map." << std::endl; return true; } @@ -1263,17 +1263,17 @@ void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm, const sdf::Mesh *meshSdf = _geom->Data().MeshShape(); if (nullptr == meshSdf) { - ignwarn << "Mesh geometry for collision [" << _name->Data() + gzwarn << "Mesh geometry for collision [" << _name->Data() << "] missing mesh shape." << std::endl; return true; } - auto &meshManager = *ignition::common::MeshManager::Instance(); + auto &meshManager = *gz::common::MeshManager::Instance(); auto fullPath = asFullPath(meshSdf->Uri(), meshSdf->FilePath()); auto *mesh = meshManager.Load(fullPath); if (nullptr == mesh) { - ignwarn << "Failed to load mesh from [" << fullPath + gzwarn << "Failed to load mesh from [" << fullPath << "]." << std::endl; return true; } @@ -1285,7 +1285,7 @@ void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm, static bool informed{false}; if (!informed) { - igndbg << "Attempting to process mesh geometries, but the physics" + gzdbg << "Attempting to process mesh geometries, but the physics" << " engine doesn't support feature " << "[AttachMeshShapeFeature]. Meshes will be ignored." << std::endl; @@ -1309,7 +1309,7 @@ void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm, static bool informed{false}; if (!informed) { - igndbg << "Attempting to process heightmap geometries, but the " + gzdbg << "Attempting to process heightmap geometries, but the " << "physics engine doesn't support feature " << "[AttachHeightmapShapeFeature]. Heightmaps will be " << "ignored." << std::endl; @@ -1321,7 +1321,7 @@ void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm, auto heightmapSdf = _geom->Data().HeightmapShape(); if (nullptr == heightmapSdf) { - ignwarn << "Heightmap geometry for collision [" << _name->Data() + gzwarn << "Heightmap geometry for collision [" << _name->Data() << "] missing heightmap shape." << std::endl; return true; } @@ -1330,7 +1330,7 @@ void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm, heightmapSdf->FilePath())); if (fullPath.empty()) { - ignerr << "Heightmap geometry missing URI" << std::endl; + gzerr << "Heightmap geometry missing URI" << std::endl; return true; } @@ -1344,7 +1344,7 @@ void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm, auto img = std::make_shared(); if (img->Load(fullPath) < 0) { - ignerr << "Failed to load heightmap image data from [" + gzerr << "Failed to load heightmap image data from [" << fullPath << "]" << std::endl; return true; } @@ -1356,7 +1356,7 @@ void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm, auto dem = std::make_shared(); if (dem->Load(fullPath) < 0) { - ignerr << "Failed to load heightmap dem data from [" + gzerr << "Failed to load heightmap dem data from [" << fullPath << "]" << std::endl; return true; } @@ -1380,7 +1380,7 @@ void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm, static bool informed{false}; if (!informed) { - igndbg << "Attempting to process collisions, but the physics " + gzdbg << "Attempting to process collisions, but the physics " << "engine doesn't support feature " << "[ConstructSdfCollision]. Collisions will be ignored." << std::endl; @@ -1395,7 +1395,7 @@ void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm, if (nullptr == collisionPtrPhys) { - igndbg << "Failed to create collision [" << _name->Data() + gzdbg << "Failed to create collision [" << _name->Data() << "]. Does the physics engine support geometries of type [" << static_cast(_geom->Data().Type()) << "]?" << std::endl; return true; @@ -1417,7 +1417,7 @@ void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm, static bool informed{false}; if (!informed) { - igndbg << "Attempting to set collision bitmasks, but the physics " + gzdbg << "Attempting to set collision bitmasks, but the physics " << "engine doesn't support feature [CollisionFilterMask]. " << "Collision bitmasks will be ignored." << std::endl; informed = true; @@ -1465,7 +1465,7 @@ void PhysicsPrivate::CreateJointEntities(const EntityComponentManager &_ecm, { if (_warnIfEntityExists) { - ignwarn << "Joint entity [" << _entity + gzwarn << "Joint entity [" << _entity << "] marked as new, but it's already on the map." << std::endl; } @@ -1475,7 +1475,7 @@ void PhysicsPrivate::CreateJointEntities(const EntityComponentManager &_ecm, // Check if parent model exists if (!this->entityModelMap.HasEntity(_parentModel->Data())) { - ignwarn << "Joint's parent entity [" << _parentModel->Data() + gzwarn << "Joint's parent entity [" << _parentModel->Data() << "] not found on model map." << std::endl; return true; } @@ -1489,7 +1489,7 @@ void PhysicsPrivate::CreateJointEntities(const EntityComponentManager &_ecm, static bool informed{false}; if (!informed) { - igndbg << "Attempting to process joints, but the physics " + gzdbg << "Attempting to process joints, but the physics " << "engine doesn't support joint features. " << "Joints will be ignored." << std::endl; informed = true; @@ -1540,7 +1540,7 @@ void PhysicsPrivate::CreateJointEntities(const EntityComponentManager &_ecm, { if (_jointInfo->Data().jointType != "fixed") { - ignerr << "Detachable joint type [" << _jointInfo->Data().jointType + gzerr << "Detachable joint type [" << _jointInfo->Data().jointType << "] is currently not supported" << std::endl; return true; } @@ -1549,7 +1549,7 @@ void PhysicsPrivate::CreateJointEntities(const EntityComponentManager &_ecm, { if (_warnIfEntityExists) { - ignwarn << "Joint entity [" << _entity + gzwarn << "Joint entity [" << _entity << "] marked as new, but it's already on the map." << std::endl; } @@ -1561,7 +1561,7 @@ void PhysicsPrivate::CreateJointEntities(const EntityComponentManager &_ecm, this->entityLinkMap.Get(_jointInfo->Data().parentLink); if (!parentLinkPhys) { - ignwarn << "DetachableJoint's parent link entity [" + gzwarn << "DetachableJoint's parent link entity [" << _jointInfo->Data().parentLink << "] not found in link map." << std::endl; return true; @@ -1573,7 +1573,7 @@ void PhysicsPrivate::CreateJointEntities(const EntityComponentManager &_ecm, auto childLinkPhys = this->entityLinkMap.Get(childLinkEntity); if (!childLinkPhys) { - ignwarn << "Failed to find joint's child link [" << childLinkEntity + gzwarn << "Failed to find joint's child link [" << childLinkEntity << "]." << std::endl; return true; } @@ -1586,7 +1586,7 @@ void PhysicsPrivate::CreateJointEntities(const EntityComponentManager &_ecm, static bool informed{false}; if (!informed) { - igndbg << "Attempting to create a detachable joint, but the physics" + gzdbg << "Attempting to create a detachable joint, but the physics" << " engine doesn't support feature " << "[AttachFixedJointFeature]. Detachable joints will be " << "ignored." << std::endl; @@ -1611,7 +1611,7 @@ void PhysicsPrivate::CreateJointEntities(const EntityComponentManager &_ecm, // We let the joint be at the origin of the child link. jointPtrPhys->SetTransformFromParent(poseParentChild); - igndbg << "Creating detachable joint [" << _entity << "]" + gzdbg << "Creating detachable joint [" << _entity << "]" << std::endl; this->entityJointMap.AddEntity(_entity, jointPtrPhys); this->topLevelModelMap.insert(std::make_pair(_entity, @@ -1619,7 +1619,7 @@ void PhysicsPrivate::CreateJointEntities(const EntityComponentManager &_ecm, } else { - ignwarn << "DetachableJoint could not be created." << std::endl; + gzwarn << "DetachableJoint could not be created." << std::endl; } return true; }); @@ -1641,14 +1641,14 @@ void PhysicsPrivate::CreateJointEntities(const EntityComponentManager &_ecm, this->EnableContactSurfaceCustomization(world); } this->customContactSurfaceEntities[world].insert(_entity); - ignmsg << "Enabling contact surface customization for collision [" + gzmsg << "Enabling contact surface customization for collision [" << _name->Data() << "]" << std::endl; } else { if (this->customContactSurfaceEntities[world].erase(_entity) > 0) { - ignmsg << "Disabling contact surface customization for collision [" + gzmsg << "Disabling contact surface customization for collision [" << _name->Data() << "]" << std::endl; if (this->customContactSurfaceEntities[world].empty()) { @@ -1742,7 +1742,7 @@ void PhysicsPrivate::RemovePhysicsEntities(const EntityComponentManager &_ecm) { if (!this->entityJointMap.HasEntity(_entity)) { - ignwarn << "Failed to find joint [" << _entity + gzwarn << "Failed to find joint [" << _entity << "]." << std::endl; return true; } @@ -1755,7 +1755,7 @@ void PhysicsPrivate::RemovePhysicsEntities(const EntityComponentManager &_ecm) static bool informed{false}; if (!informed) { - igndbg << "Attempting to detach a joint, but the physics " + gzdbg << "Attempting to detach a joint, but the physics " << "engine doesn't support feature " << "[DetachJointFeature]. Joint won't be detached." << std::endl; @@ -1766,7 +1766,7 @@ void PhysicsPrivate::RemovePhysicsEntities(const EntityComponentManager &_ecm) return false; } - igndbg << "Detaching joint [" << _entity << "]" << std::endl; + gzdbg << "Detaching joint [" << _entity << "]" << std::endl; castEntity->Detach(); return true; }); @@ -1845,7 +1845,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) if (limits.size() != jointPhys->GetDegreesOfFreedom()) { - ignwarn << "There is a mismatch in the degrees of freedom " + gzwarn << "There is a mismatch in the degrees of freedom " << "between Joint [" << _name->Data() << "(Entity=" << _entity << ")] and its JointPositionLimitsCmd " << "component. The joint has " @@ -1876,7 +1876,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) if (limits.size() != jointPhys->GetDegreesOfFreedom()) { - ignwarn << "There is a mismatch in the degrees of freedom " + gzwarn << "There is a mismatch in the degrees of freedom " << "between Joint [" << _name->Data() << "(Entity=" << _entity << ")] and its JointVelocityLimitsCmd " << "component. The joint has " @@ -1907,7 +1907,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) if (limits.size() != jointPhys->GetDegreesOfFreedom()) { - ignwarn << "There is a mismatch in the degrees of freedom " + gzwarn << "There is a mismatch in the degrees of freedom " << "between Joint [" << _name->Data() << "(Entity=" << _entity << ")] and its JointEffortLimitsCmd " << "component. The joint has " @@ -1942,7 +1942,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) if (jointVelocity.size() != jointPhys->GetDegreesOfFreedom()) { - ignwarn << "There is a mismatch in the degrees of freedom " + gzwarn << "There is a mismatch in the degrees of freedom " << "between Joint [" << _name->Data() << "(Entity=" << _entity << ")] and its JointVelocityReset " << "component. The joint has " @@ -1967,7 +1967,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) if (jointPosition.size() != jointPhys->GetDegreesOfFreedom()) { - ignwarn << "There is a mismatch in the degrees of freedom " + gzwarn << "There is a mismatch in the degrees of freedom " << "between Joint [" << _name->Data() << "(Entity=" << _entity << ")] and its JointPositionyReset " << "component. The joint has " @@ -1990,7 +1990,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) { if (force->Data().size() != jointPhys->GetDegreesOfFreedom()) { - ignwarn << "There is a mismatch in the degrees of freedom between " + gzwarn << "There is a mismatch in the degrees of freedom between " << "Joint [" << _name->Data() << "(Entity=" << _entity << ")] and its JointForceCmd component. The joint has " << jointPhys->GetDegreesOfFreedom() << " while the " @@ -2011,7 +2011,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) if (velReset) { - ignwarn << "Found both JointVelocityReset and " + gzwarn << "Found both JointVelocityReset and " << "JointVelocityCmd components for Joint [" << _name->Data() << "(Entity=" << _entity << "]). Ignoring JointVelocityCmd component." @@ -2021,7 +2021,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) if (velocityCmd.size() != jointPhys->GetDegreesOfFreedom()) { - ignwarn << "There is a mismatch in the degrees of freedom" + gzwarn << "There is a mismatch in the degrees of freedom" << " between Joint [" << _name->Data() << "(Entity=" << _entity<< ")] and its " << "JointVelocityCmd component. The joint has " @@ -2055,7 +2055,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) { if (!this->entityLinkMap.HasEntity(_entity)) { - ignwarn << "Failed to find link [" << _entity + gzwarn << "Failed to find link [" << _entity << "]." << std::endl; return true; } @@ -2067,7 +2067,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) static bool informed{false}; if (!informed) { - igndbg << "Attempting to apply a wrench, but the physics " + gzdbg << "Attempting to apply a wrench, but the physics " << "engine doesn't support feature " << "[AddLinkExternalForceTorque]. Wrench will be ignored." << std::endl; @@ -2103,7 +2103,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) // world pose cmd currently not supported for nested models if (_entity != this->topLevelModelMap[_entity]) { - ignerr << "Unable to set world pose for nested models." + gzerr << "Unable to set world pose for nested models." << std::endl; return true; } @@ -2160,7 +2160,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) { if (!this->entityCollisionMap.HasEntity(_entity)) { - ignwarn << "Failed to find shape [" << _entity << "]." << std::endl; + gzwarn << "Failed to find shape [" << _entity << "]." << std::endl; return true; } @@ -2170,7 +2170,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) if (!slipComplianceShape) { - ignwarn << "Can't process Wheel Slip component, physics engine " + gzwarn << "Can't process Wheel Slip component, physics engine " << "missing SetShapeFrictionPyramidSlipCompliance" << std::endl; @@ -2201,7 +2201,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) // angular vel cmd currently not supported for nested models if (_entity != this->topLevelModelMap[_entity]) { - ignerr << "Unable to set angular velocity for nested models." + gzerr << "Unable to set angular velocity for nested models." << std::endl; return true; } @@ -2224,7 +2224,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) static bool informed{false}; if (!informed) { - igndbg << "Attempting to set model angular velocity, but the " + gzdbg << "Attempting to set model angular velocity, but the " << "physics engine doesn't support velocity commands. " << "Velocity won't be set." << std::endl; @@ -2250,7 +2250,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) // linear vel cmd currently not supported for nested models if (_entity != this->topLevelModelMap[_entity]) { - ignerr << "Unable to set linear velocity for nested models." + gzerr << "Unable to set linear velocity for nested models." << std::endl; return true; } @@ -2274,7 +2274,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) static bool informed{false}; if (!informed) { - igndbg << "Attempting to set model linear velocity, but the " + gzdbg << "Attempting to set model linear velocity, but the " << "physics engine doesn't support velocity commands. " << "Velocity won't be set." << std::endl; @@ -2296,7 +2296,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) { if (!this->entityLinkMap.HasEntity(_entity)) { - ignwarn << "Failed to find link [" << _entity + gzwarn << "Failed to find link [" << _entity << "]." << std::endl; return true; } @@ -2319,7 +2319,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) static bool informed{false}; if (!informed) { - igndbg << "Attempting to set link angular velocity, but the " + gzdbg << "Attempting to set link angular velocity, but the " << "physics engine doesn't support velocity commands. " << "Velocity won't be set." << std::endl; @@ -2348,7 +2348,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) { if (!this->entityLinkMap.HasEntity(_entity)) { - ignwarn << "Failed to find link [" << _entity + gzwarn << "Failed to find link [" << _entity << "]." << std::endl; return true; } @@ -2370,7 +2370,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) static bool informed{false}; if (!informed) { - igndbg << "Attempting to set link linear velocity, but the " + gzdbg << "Attempting to set link linear velocity, but the " << "physics engine doesn't support velocity commands. " << "Velocity won't be set." << std::endl; @@ -2403,7 +2403,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) { if (!this->entityModelMap.HasEntity(_entity)) { - ignwarn << "Failed to find model [" << _entity << "]." << std::endl; + gzwarn << "Failed to find model [" << _entity << "]." << std::endl; return true; } @@ -2415,7 +2415,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) static bool informed{false}; if (!informed) { - igndbg << "Attempting to get a bounding box, but the physics " + gzdbg << "Attempting to get a bounding box, but the physics " << "engine doesn't support feature " << "[GetModelBoundingBox]. Bounding box won't be populated." << std::endl; @@ -2459,7 +2459,7 @@ void PhysicsPrivate::ResetPhysics(EntityComponentManager &_ecm) auto linkPtrPhys = this->entityLinkMap.Get(_entity); if (nullptr == linkPtrPhys) { - ignwarn << "Failed to find link [" << _entity << "]." << std::endl; + gzwarn << "Failed to find link [" << _entity << "]." << std::endl; return true; } @@ -2484,7 +2484,7 @@ void PhysicsPrivate::ResetPhysics(EntityComponentManager &_ecm) static bool informed{false}; if (!informed) { - igndbg << "Attempting to reset link angular velocity, but the " + gzdbg << "Attempting to reset link angular velocity, but the " << "physics engine doesn't support velocity commands. " << "Velocity won't be reset." << std::endl; @@ -2506,7 +2506,7 @@ void PhysicsPrivate::ResetPhysics(EntityComponentManager &_ecm) static bool informed{false}; if (!informed) { - igndbg << "Attempting to set link linear velocity, but the " + gzdbg << "Attempting to set link linear velocity, but the " << "physics engine doesn't support velocity commands. " << "Velocity won't be set." << std::endl; @@ -2530,7 +2530,7 @@ void PhysicsPrivate::ResetPhysics(EntityComponentManager &_ecm) auto jointPhys = this->entityJointMap.Get(_entity); if (nullptr == jointPhys) { - ignwarn << "Failed to find joint [" << _entity << "]." << std::endl; + gzwarn << "Failed to find joint [" << _entity << "]." << std::endl; return true; } @@ -2556,7 +2556,7 @@ void PhysicsPrivate::ResetPhysics(EntityComponentManager &_ecm) _ecm.Each( [&](const Entity &_entity, const components::Model *) { - this->modelWorldPoses[_entity] = gazebo::worldPose(_entity, _ecm); + this->modelWorldPoses[_entity] = sim::worldPose(_entity, _ecm); return true; }); @@ -2564,13 +2564,13 @@ void PhysicsPrivate::ResetPhysics(EntityComponentManager &_ecm) } ////////////////////////////////////////////////// -ignition::physics::ForwardStep::Output PhysicsPrivate::Step( +gz::physics::ForwardStep::Output PhysicsPrivate::Step( const std::chrono::steady_clock::duration &_dt) { IGN_PROFILE("PhysicsPrivate::Step"); - ignition::physics::ForwardStep::Input input; - ignition::physics::ForwardStep::State state; - ignition::physics::ForwardStep::Output output; + gz::physics::ForwardStep::Input input; + gz::physics::ForwardStep::State state; + gz::physics::ForwardStep::Output output; input.Get() = _dt; @@ -2583,7 +2583,7 @@ ignition::physics::ForwardStep::Output PhysicsPrivate::Step( } ////////////////////////////////////////////////// -ignition::math::Pose3d PhysicsPrivate::RelativePose(const Entity &_from, +gz::math::Pose3d PhysicsPrivate::RelativePose(const Entity &_from, const Entity &_to, const EntityComponentManager &_ecm) const { math::Pose3d transform; @@ -2621,7 +2621,7 @@ ignition::math::Pose3d PhysicsPrivate::RelativePose(const Entity &_from, ////////////////////////////////////////////////// std::map PhysicsPrivate::ChangedLinks( EntityComponentManager &_ecm, - const ignition::physics::ForwardStep::Output &_updatedLinks) + const gz::physics::ForwardStep::Output &_updatedLinks) { IGN_PROFILE("Links Frame Data"); @@ -2629,23 +2629,23 @@ std::map PhysicsPrivate::ChangedLinks( // Check to see if the physics engine gave a list of changed poses. If not, we // will iterate through all of the links via the ECM to see which ones changed - if (_updatedLinks.Has()) + if (_updatedLinks.Has()) { for (const auto &link : - _updatedLinks.Query()->entries) + _updatedLinks.Query()->entries) { // get the gazebo entity that matches the updated physics link entity const auto linkPhys = this->entityLinkMap.GetPhysicsEntityPtr(link.body); if (nullptr == linkPhys) { - ignerr << "Internal error: a physics entity ptr with an ID of [" + gzerr << "Internal error: a physics entity ptr with an ID of [" << link.body << "] does not exist." << std::endl; continue; } auto entity = this->entityLinkMap.Get(linkPhys); if (entity == kNullEntity) { - ignerr << "Internal error: no gazebo entity matches the physics entity " + gzerr << "Internal error: no gazebo entity matches the physics entity " << "with ID [" << link.body << "]." << std::endl; continue; } @@ -2673,7 +2673,7 @@ std::map PhysicsPrivate::ChangedLinks( if (this->linkAddedToModel.find(_entity) == this->linkAddedToModel.end()) { - ignerr << "Internal error: link [" << _entity + gzerr << "Internal error: link [" << _entity << "] not in entity map" << std::endl; } return true; @@ -2684,7 +2684,7 @@ std::map PhysicsPrivate::ChangedLinks( // update the link pose if this is the first update, // or if the link pose has changed since the last update // (if the link pose hasn't changed, there's no need for a pose update) - const auto worldPoseMath3d = ignition::math::eigen3::convert( + const auto worldPoseMath3d = gz::math::eigen3::convert( frameData.pose); if ((this->linkWorldPoses.find(_entity) == this->linkWorldPoses.end()) || !this->pose3Eql(this->linkWorldPoses[_entity], worldPoseMath3d)) @@ -2771,7 +2771,7 @@ void PhysicsPrivate::UpdateModelPose(const Entity _model, // once the model pose has been updated, all descendant link poses of this // model must be updated (whether the link actually changed pose or not) // since link poses are saved w.r.t. their parent model - auto model = gazebo::Model(_model); + auto model = sim::Model(_model); for (const auto &childLink : model.Links(_ecm)) { // skip links that are already marked as a link to be updated @@ -2796,7 +2796,7 @@ void PhysicsPrivate::UpdateModelPose(const Entity _model, { auto staticComp = _ecm.Component(nestedModel); if (!staticComp || !staticComp->Data()) - ignerr << "Model [" << nestedModel << "] has no canonical link\n"; + gzerr << "Model [" << nestedModel << "] has no canonical link\n"; continue; } @@ -2828,7 +2828,7 @@ bool PhysicsPrivate::GetFrameDataRelativeToWorld(const Entity _entity, // Suppress error message if the link has just been added to the model. if (this->linkAddedToModel.find(_entity) == this->linkAddedToModel.end()) { - ignerr << "Internal error: entity [" << _entity + gzerr << "Internal error: entity [" << _entity << "] not in entity map" << std::endl; } return false; @@ -2926,7 +2926,7 @@ void PhysicsPrivate::UpdateSim(EntityComponentManager &_ecm, auto parentModelPoseIt = this->modelWorldPoses.find(parentEntity); if (parentModelPoseIt == this->modelWorldPoses.end()) { - ignerr << "Internal error: parent model [" << parentEntity + gzerr << "Internal error: parent model [" << parentEntity << "] does not have a world pose available for child entity[" << entity << "]" << std::endl; continue; @@ -3144,7 +3144,7 @@ void PhysicsPrivate::UpdateSim(EntityComponentManager &_ecm, this->LinkFrameDataAtOffset(linkPhys, _pose->Data()); auto entityWorldPose = math::eigen3::convert(entityFrameData.pose); - ignition::math::Vector3d entityWorldAngularVel = + gz::math::Vector3d entityWorldAngularVel = math::eigen3::convert(entityFrameData.angularVelocity); auto entityBodyAngularVel = @@ -3169,7 +3169,7 @@ void PhysicsPrivate::UpdateSim(EntityComponentManager &_ecm, this->LinkFrameDataAtOffset(linkPhys, _pose->Data()); auto entityWorldPose = math::eigen3::convert(entityFrameData.pose); - ignition::math::Vector3d entityWorldLinearAcc = + gz::math::Vector3d entityWorldLinearAcc = math::eigen3::convert(entityFrameData.linearAcceleration); auto entityBodyLinearAcc = @@ -3354,7 +3354,7 @@ void PhysicsPrivate::UpdateSim(EntityComponentManager &_ecm, static bool informed{false}; if (!informed) { - igndbg + gzdbg << "Attempting to get joint transmitted wrenches, but the " "physics engine doesn't support this feature. Values in the " "JointTransmittedWrench component will not be meaningful." @@ -3384,13 +3384,13 @@ void PhysicsPrivate::UpdateCollisions(EntityComponentManager &_ecm) if (worldEntity == kNullEntity) { - ignerr << "Missing world entity.\n"; + gzerr << "Missing world entity.\n"; return; } if (!this->entityWorldMap.HasEntity(worldEntity)) { - ignwarn << "Failed to find world [" << worldEntity << "]." << std::endl; + gzwarn << "Failed to find world [" << worldEntity << "]." << std::endl; return; } @@ -3401,7 +3401,7 @@ void PhysicsPrivate::UpdateCollisions(EntityComponentManager &_ecm) static bool informed{false}; if (!informed) { - igndbg << "Attempting process contacts, but the physics " + gzdbg << "Attempting process contacts, but the physics " << "engine doesn't support contact features. " << "Contacts won't be computed." << std::endl; @@ -3524,7 +3524,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 = "gz::sim::systems::Physics"; setContactPropertiesCallbackFeature->AddContactPropertiesCallback( callbackID, [this, _world](const GCFeatureWorld::Contact &_contact, @@ -3570,7 +3570,7 @@ void PhysicsPrivate::EnableContactSurfaceCustomization(const Entity &_world) this->worldContactCallbackIDs[_world] = callbackID; - ignmsg << "Enabled contact surface customization for world entity [" << _world + gzmsg << "Enabled contact surface customization for world entity [" << _world << "]" << std::endl; } @@ -3593,14 +3593,17 @@ void PhysicsPrivate::DisableContactSurfaceCustomization(const Entity &_world) setContactPropertiesCallbackFeature-> RemoveContactPropertiesCallback(this->worldContactCallbackIDs[_world]); - ignmsg << "Disabled contact surface customization for world entity [" + gzmsg << "Disabled contact surface customization for world entity [" << _world << "]" << std::endl; } IGNITION_ADD_PLUGIN(Physics, - ignition::gazebo::System, + gz::sim::System, Physics::ISystemConfigure, Physics::ISystemReset, 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 d4bc642043..927c54dd0d 100644 --- a/src/systems/physics/Physics.hh +++ b/src/systems/physics/Physics.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_PHYSICS_HH_ -#define IGNITION_GAZEBO_SYSTEMS_PHYSICS_HH_ +#ifndef GZ_SIM_SYSTEMS_PHYSICS_HH_ +#define GZ_SIM_SYSTEMS_PHYSICS_HH_ #include #include @@ -51,12 +51,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declarations. @@ -70,7 +70,7 @@ namespace systems /// ``` /// + /// name="gz::sim::systems::Physics"> /// /// false /// diff --git a/src/systems/pose_publisher/PosePublisher.cc b/src/systems/pose_publisher/PosePublisher.cc index 3e4305f0dd..627692a17d 100644 --- a/src/systems/pose_publisher/PosePublisher.cc +++ b/src/systems/pose_publisher/PosePublisher.cc @@ -50,12 +50,12 @@ #include "gz/sim/Conversions.hh" #include "gz/sim/Model.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace 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 @@ -156,12 +156,12 @@ class ignition::gazebo::systems::PosePublisherPrivate /// \brief A variable that gets populated with poses. This also here as a /// member variable to avoid repeated memory allocations and improve /// performance. - public: ignition::msgs::Pose poseMsg; + public: gz::msgs::Pose poseMsg; /// \brief A variable that gets populated with poses. This also here as a /// member variable to avoid repeated memory allocations and improve /// performance. - public: ignition::msgs::Pose_V poseVMsg; + public: gz::msgs::Pose_V poseVMsg; /// \brief True to publish a vector of poses. False to publish individual pose /// msgs. @@ -187,7 +187,7 @@ void PosePublisher::Configure(const Entity &_entity, if (!this->dataPtr->model.Valid(_ecm)) { - ignerr << "PosePublisher plugin should be attached to a model entity. " + gzerr << "PosePublisher plugin should be attached to a model entity. " << "Failed to initialize." << std::endl; return; } @@ -255,7 +255,7 @@ void PosePublisher::Configure(const Entity &_entity, if (poseTopic.empty()) { poseTopic = "/pose"; - ignerr << "Empty pose topic generated for pose_publisher system. " + gzerr << "Empty pose topic generated for pose_publisher system. " << "Setting to " << poseTopic << std::endl; } std::string staticPoseTopic = poseTopic + "_static"; @@ -263,23 +263,23 @@ void PosePublisher::Configure(const Entity &_entity, if (this->dataPtr->usePoseV) { this->dataPtr->posePub = - this->dataPtr->node.Advertise(poseTopic); + this->dataPtr->node.Advertise(poseTopic); if (this->dataPtr->staticPosePublisher) { this->dataPtr->poseStaticPub = - this->dataPtr->node.Advertise( + this->dataPtr->node.Advertise( staticPoseTopic); } } else { this->dataPtr->posePub = - this->dataPtr->node.Advertise(poseTopic); + this->dataPtr->node.Advertise(poseTopic); if (this->dataPtr->staticPosePublisher) { this->dataPtr->poseStaticPub = - this->dataPtr->node.Advertise( + this->dataPtr->node.Advertise( staticPoseTopic); } } @@ -294,7 +294,7 @@ void PosePublisher::PostUpdate(const UpdateInfo &_info, // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -484,7 +484,7 @@ void PosePublisherPrivate::InitializeEntitiesToPublish( { if (this->entitiesToPublish.find(ent) == this->entitiesToPublish.end()) { - ignwarn << "Entity id: '" << ent << "' not found when creating a list " + gzwarn << "Entity id: '" << ent << "' not found when creating a list " << "of dynamic entities in pose publisher." << std::endl; } } @@ -530,7 +530,7 @@ void PosePublisherPrivate::PublishPoses( IGN_PROFILE("PosePublisher::PublishPoses"); // publish poses - ignition::msgs::Pose *msg = nullptr; + gz::msgs::Pose *msg = nullptr; if (this->usePoseV) this->poseVMsg.Clear(); @@ -587,5 +587,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 8dda7e336d..db1a7e1d33 100644 --- a/src/systems/pose_publisher/PosePublisher.hh +++ b/src/systems/pose_publisher/PosePublisher.hh @@ -14,27 +14,27 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_POSEPUBLISHER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_POSEPUBLISHER_HH_ +#ifndef GZ_SIM_SYSTEMS_POSEPUBLISHER_HH_ +#define GZ_SIM_SYSTEMS_POSEPUBLISHER_HH_ #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declaration 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: @@ -49,8 +49,8 @@ namespace systems /// also published unless publish_model_pose is /// set to false /// 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/rf_comms/RFComms.cc b/src/systems/rf_comms/RFComms.cc index 716380ce89..40930c5d05 100644 --- a/src/systems/rf_comms/RFComms.cc +++ b/src/systems/rf_comms/RFComms.cc @@ -35,8 +35,8 @@ #include "gz/sim/Util.hh" #include "RFComms.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; /// \brief Parameters for simple log-normal fading model. @@ -113,7 +113,7 @@ struct RadioState double timeStamp; /// \brief Pose of the radio. - ignition::math::Pose3 pose; + gz::math::Pose3 pose; /// \brief Recent sent packet history. std::list> bytesSent; @@ -146,7 +146,7 @@ struct RFPower }; /// \brief Private RFComms data class. -class ignition::gazebo::systems::RFComms::Implementation +class gz::sim::systems::RFComms::Implementation { /// \brief Attempt communication between two nodes. /// @@ -249,7 +249,7 @@ std::tuple RFComms::Implementation::AttemptSend( _txState.bytesSent.pop_front(); } - // igndbg << "Bytes sent: " << _txState.bytesSentThisEpoch << " + " + // gzdbg << "Bytes sent: " << _txState.bytesSentThisEpoch << " + " // << _numBytes << " = " // << _txState.bytesSentThisEpoch + _numBytes << std::endl; @@ -260,7 +260,7 @@ std::tuple RFComms::Implementation::AttemptSend( // Check current epoch bitrate vs capacity and fail to send accordingly if (bitsSent > this->radioConfig.capacity * this->epochDuration) { - ignwarn << "Bitrate limited: " << bitsSent << "bits sent (limit: " + gzwarn << "Bitrate limited: " << bitsSent << "bits sent (limit: " << this->radioConfig.capacity * this->epochDuration << std::endl; return std::make_tuple(false, std::numeric_limits::lowest()); } @@ -287,13 +287,13 @@ std::tuple RFComms::Implementation::AttemptSend( double packetDropProb = 1.0 - exp(_numBytes * log(1 - ber)); - // igndbg << "TX power (dBm): " << this->radioConfig.txPower << "\n" << + // gzdbg << "TX power (dBm): " << this->radioConfig.txPower << "\n" << // "RX power (dBm): " << rxPower << "\n" << // "BER: " << ber << "\n" << // "# Bytes: " << _numBytes << "\n" << // "PER: " << packetDropProb << std::endl; - double randDraw = ignition::math::Rand::DblUniform(); + double randDraw = gz::math::Rand::DblUniform(); bool packetReceived = randDraw > packetDropProb; if (!packetReceived) @@ -307,7 +307,7 @@ std::tuple RFComms::Implementation::AttemptSend( _rxState.bytesReceived.pop_front(); } - // igndbg << "bytes received: " << _rxState.bytesReceivedThisEpoch + // gzdbg << "bytes received: " << _rxState.bytesReceivedThisEpoch // << " + " << _numBytes // << " = " << _rxState.bytesReceivedThisEpoch + _numBytes << std::endl; @@ -318,7 +318,7 @@ std::tuple RFComms::Implementation::AttemptSend( // Check current epoch bitrate vs capacity and fail to send accordingly. if (bitsReceived > this->radioConfig.capacity * this->epochDuration) { - // ignwarn << "Bitrate limited: " << bitsReceived + // gzwarn << "Bitrate limited: " << bitsReceived // << "bits received (limit: " // << this->radioConfig.capacity * this->epochDuration << std::endl; return std::make_tuple(false, std::numeric_limits::lowest()); @@ -333,7 +333,7 @@ std::tuple RFComms::Implementation::AttemptSend( ////////////////////////////////////////////////// RFComms::RFComms() - : dataPtr(ignition::utils::MakeUniqueImpl()) + : dataPtr(gz::utils::MakeUniqueImpl()) { } @@ -380,10 +380,10 @@ void RFComms::Load(const Entity &/*_entity*/, this->dataPtr->radioConfig.noiseFloor).first; } - igndbg << "Range configuration:" << std::endl + gzdbg << "Range configuration:" << std::endl << this->dataPtr->rangeConfig << std::endl; - igndbg << "Radio configuration:" << std::endl + gzdbg << "Radio configuration:" << std::endl << this->dataPtr->radioConfig << std::endl; } @@ -400,7 +400,7 @@ void RFComms::Step( // Associate entity if needed. if (content.entity == kNullEntity) { - auto entities = gazebo::entitiesFromScopedName(content.modelName, _ecm); + auto entities = sim::entitiesFromScopedName(content.modelName, _ecm); if (entities.empty()) continue; @@ -415,7 +415,7 @@ void RFComms::Step( else { // Update radio state. - const auto kPose = gazebo::worldPose(content.entity, _ecm); + const auto kPose = sim::worldPose(content.entity, _ecm); this->dataPtr->radioStates[address].pose = kPose; this->dataPtr->radioStates[address].timeStamp = std::chrono::duration(_info.simTime).count(); @@ -457,9 +457,13 @@ void RFComms::Step( } IGNITION_ADD_PLUGIN(RFComms, - ignition::gazebo::System, + gz::sim::System, comms::ICommsModel::ISystemConfigure, comms::ICommsModel::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(RFComms, + "gz::sim::systems::RFComms") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(RFComms, "ignition::gazebo::systems::RFComms") diff --git a/src/systems/rf_comms/RFComms.hh b/src/systems/rf_comms/RFComms.hh index 14e482b4aa..7aae54d36f 100644 --- a/src/systems/rf_comms/RFComms.hh +++ b/src/systems/rf_comms/RFComms.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_RFCOMMS_HH_ -#define IGNITION_GAZEBO_SYSTEMS_RFCOMMS_HH_ +#ifndef GZ_SIM_SYSTEMS_RFCOMMS_HH_ +#define GZ_SIM_SYSTEMS_RFCOMMS_HH_ #include @@ -24,12 +24,12 @@ #include "gz/sim/comms/ICommsModel.hh" #include "gz/sim/System.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { /// \brief A comms model that simulates communication using radio frequency @@ -65,7 +65,7 @@ namespace systems /// Here's an example: /// + /// name="gz::sim::systems::RFComms"> /// /// 500000.0 /// 1.5 @@ -95,7 +95,7 @@ namespace systems EventManager &_eventMgr) override; // Documentation inherited. - public: void Step(const ignition::gazebo::UpdateInfo &_info, + public: void Step(const gz::sim::UpdateInfo &_info, const comms::Registry &_currentRegistry, comms::Registry &_newRegistry, EntityComponentManager &_ecm) override; diff --git a/src/systems/scene_broadcaster/SceneBroadcaster.cc b/src/systems/scene_broadcaster/SceneBroadcaster.cc index 9496250f4d..e00c7bc8dd 100644 --- a/src/systems/scene_broadcaster/SceneBroadcaster.cc +++ b/src/systems/scene_broadcaster/SceneBroadcaster.cc @@ -67,12 +67,12 @@ using namespace std::chrono_literals; -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace 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< @@ -85,21 +85,21 @@ class ignition::gazebo::systems::SceneBroadcasterPrivate /// \brief Callback for scene info service. /// \param[out] _res Response containing the latest scene message. /// \return True if successful. - public: bool SceneInfoService(ignition::msgs::Scene &_res); + public: bool SceneInfoService(gz::msgs::Scene &_res); /// \brief Callback for scene graph service. /// \param[out] _res Response containing the the scene graph in DOT format. /// \return True if successful. - public: bool SceneGraphService(ignition::msgs::StringMsg &_res); + public: bool SceneGraphService(gz::msgs::StringMsg &_res); /// \brief Callback for state service. /// \param[out] _res Response containing the latest full state. /// \return True if successful. - public: bool StateService(ignition::msgs::SerializedStepMap &_res); + public: bool StateService(gz::msgs::SerializedStepMap &_res); /// \brief Callback for state service - non blocking. /// \param[out] _res Response containing the last available full state. - public: void StateAsyncService(const ignition::msgs::StringMsg &_req); + public: void StateAsyncService(const gz::msgs::StringMsg &_req); /// \brief Updates the scene graph when entities are added /// \param[in] _manager The entity component manager @@ -250,7 +250,7 @@ void SceneBroadcaster::Configure( const components::Name *name = _ecm.Component(_entity); if (name == nullptr) { - ignerr << "World with id: " << _entity + gzerr << "World with id: " << _entity << " has no name. SceneBroadcaster cannot create transport topics\n"; return; } @@ -499,7 +499,7 @@ void SceneBroadcasterPrivate::SetupTransport(const std::string &_worldName) auto ns = transport::TopicUtils::AsValidTopic("/world/" + _worldName); if (ns.empty()) { - ignerr << "Failed to create valid namespace for world [" << _worldName + gzerr << "Failed to create valid namespace for world [" << _worldName << "]" << std::endl; return; } @@ -514,7 +514,7 @@ void SceneBroadcasterPrivate::SetupTransport(const std::string &_worldName) this->node->Advertise(infoService, &SceneBroadcasterPrivate::SceneInfoService, this); - ignmsg << "Serving scene information on [" << opts.NameSpace() << "/" + gzmsg << "Serving scene information on [" << opts.NameSpace() << "/" << infoService << "]" << std::endl; // Scene graph service @@ -523,7 +523,7 @@ void SceneBroadcasterPrivate::SetupTransport(const std::string &_worldName) this->node->Advertise(graphService, &SceneBroadcasterPrivate::SceneGraphService, this); - ignmsg << "Serving graph information on [" << opts.NameSpace() << "/" + gzmsg << "Serving graph information on [" << opts.NameSpace() << "/" << graphService << "]" << std::endl; // State service @@ -534,7 +534,7 @@ void SceneBroadcasterPrivate::SetupTransport(const std::string &_worldName) this->node->Advertise(stateService, &SceneBroadcasterPrivate::StateService, this); - ignmsg << "Serving full state on [" << opts.NameSpace() << "/" + gzmsg << "Serving full state on [" << opts.NameSpace() << "/" << stateService << "]" << std::endl; // Async State service @@ -543,33 +543,33 @@ void SceneBroadcasterPrivate::SetupTransport(const std::string &_worldName) this->node->Advertise(stateAsyncService, &SceneBroadcasterPrivate::StateAsyncService, this); - ignmsg << "Serving full state (async) on [" << opts.NameSpace() << "/" + gzmsg << "Serving full state (async) on [" << opts.NameSpace() << "/" << stateAsyncService << "]" << std::endl; // Scene info topic std::string sceneTopic{ns + "/scene/info"}; - this->scenePub = this->node->Advertise(sceneTopic); + this->scenePub = this->node->Advertise(sceneTopic); - ignmsg << "Publishing scene information on [" << sceneTopic + gzmsg << "Publishing scene information on [" << sceneTopic << "]" << std::endl; // Entity deletion publisher std::string deletionTopic{ns + "/scene/deletion"}; this->deletionPub = - this->node->Advertise(deletionTopic); + this->node->Advertise(deletionTopic); - ignmsg << "Publishing entity deletions on [" << deletionTopic << "]" + gzmsg << "Publishing entity deletions on [" << deletionTopic << "]" << std::endl; // State topic std::string stateTopic{ns + "/state"}; this->statePub = - this->node->Advertise(stateTopic); + this->node->Advertise(stateTopic); - ignmsg << "Publishing state changes on [" << stateTopic << "]" + gzmsg << "Publishing state changes on [" << stateTopic << "]" << std::endl; // Pose info publisher @@ -580,7 +580,7 @@ void SceneBroadcasterPrivate::SetupTransport(const std::string &_worldName) this->posePub = this->node->Advertise(poseTopic, poseAdvertOpts); - ignmsg << "Publishing pose messages on [" << opts.NameSpace() << "/" + gzmsg << "Publishing pose messages on [" << opts.NameSpace() << "/" << poseTopic << "]" << std::endl; // Dynamic pose info publisher @@ -591,12 +591,12 @@ void SceneBroadcasterPrivate::SetupTransport(const std::string &_worldName) this->dyPosePub = this->node->Advertise(dyPoseTopic, dyPoseAdvertOpts); - ignmsg << "Publishing dynamic pose messages on [" << opts.NameSpace() << "/" + gzmsg << "Publishing dynamic pose messages on [" << opts.NameSpace() << "/" << dyPoseTopic << "]" << std::endl; } ////////////////////////////////////////////////// -bool SceneBroadcasterPrivate::SceneInfoService(ignition::msgs::Scene &_res) +bool SceneBroadcasterPrivate::SceneInfoService(gz::msgs::Scene &_res) { std::lock_guard lock(this->graphMutex); @@ -615,7 +615,7 @@ bool SceneBroadcasterPrivate::SceneInfoService(ignition::msgs::Scene &_res) ////////////////////////////////////////////////// void SceneBroadcasterPrivate::StateAsyncService( - const ignition::msgs::StringMsg &_req) + const gz::msgs::StringMsg &_req) { std::unique_lock lock(this->stateMutex); this->stateServiceRequest = true; @@ -624,7 +624,7 @@ void SceneBroadcasterPrivate::StateAsyncService( ////////////////////////////////////////////////// bool SceneBroadcasterPrivate::StateService( - ignition::msgs::SerializedStepMap &_res) + gz::msgs::SerializedStepMap &_res) { _res.Clear(); @@ -640,13 +640,13 @@ bool SceneBroadcasterPrivate::StateService( if (success) _res.CopyFrom(this->stepMsg); else - ignerr << "Timed out waiting for state" << std::endl; + gzerr << "Timed out waiting for state" << std::endl; return success; } ////////////////////////////////////////////////// -bool SceneBroadcasterPrivate::SceneGraphService(ignition::msgs::StringMsg &_res) +bool SceneBroadcasterPrivate::SceneGraphService(gz::msgs::StringMsg &_res) { std::lock_guard lock(this->graphMutex); @@ -916,22 +916,22 @@ void SceneBroadcasterPrivate::SceneGraphAddEntities( msgs::IMUSensor * imuMsg = sensorMsg->mutable_imu(); const auto * imu = imuComp->Data().ImuSensor(); - ignition::gazebo::set( + gz::sim::set( imuMsg->mutable_linear_acceleration()->mutable_x_noise(), imu->LinearAccelerationXNoise()); - ignition::gazebo::set( + gz::sim::set( imuMsg->mutable_linear_acceleration()->mutable_y_noise(), imu->LinearAccelerationYNoise()); - ignition::gazebo::set( + gz::sim::set( imuMsg->mutable_linear_acceleration()->mutable_z_noise(), imu->LinearAccelerationZNoise()); - ignition::gazebo::set( + gz::sim::set( imuMsg->mutable_angular_velocity()->mutable_x_noise(), imu->AngularVelocityXNoise()); - ignition::gazebo::set( + gz::sim::set( imuMsg->mutable_angular_velocity()->mutable_y_noise(), imu->AngularVelocityYNoise()); - ignition::gazebo::set( + gz::sim::set( imuMsg->mutable_angular_velocity()->mutable_z_noise(), imu->AngularVelocityZNoise()); } @@ -1174,11 +1174,15 @@ void SceneBroadcasterPrivate::RemoveFromGraph(const Entity _entity, IGNITION_ADD_PLUGIN(SceneBroadcaster, - ignition::gazebo::System, + gz::sim::System, SceneBroadcaster::ISystemConfigure, SceneBroadcaster::ISystemPostUpdate) // 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 4b3a1b8a34..bad06adf63 100644 --- a/src/systems/scene_broadcaster/SceneBroadcaster.hh +++ b/src/systems/scene_broadcaster/SceneBroadcaster.hh @@ -14,20 +14,20 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SCENEBROADCASTER_SYSTEM_HH_ -#define IGNITION_GAZEBO_SCENEBROADCASTER_SYSTEM_HH_ +#ifndef GZ_SIM_SCENEBROADCASTER_SYSTEM_HH_ +#define GZ_SIM_SCENEBROADCASTER_SYSTEM_HH_ #include #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { class SceneBroadcasterPrivate; @@ -35,7 +35,7 @@ namespace systems /** \class SceneBroadcaster SceneBroadcaster.hh \ * gz/sim/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 final: public System, diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc index 6159f7fb14..1e91e52ad5 100644 --- a/src/systems/sensors/Sensors.cc +++ b/src/systems/sensors/Sensors.cc @@ -60,12 +60,12 @@ #include "gz/sim/rendering/Events.hh" #include "gz/sim/rendering/RenderUtil.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace 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. @@ -100,7 +100,7 @@ class ignition::gazebo::systems::SensorsPrivate /// \brief Maps gazebo entity to its matching sensor ID /// /// Useful for detecting when a sensor Entity has been deleted and trigger - /// the destruction of the corresponding ignition::sensors Sensor object + /// the destruction of the corresponding gz::sensors Sensor object public: std::unordered_map entityToIdMap; /// \brief Flag to indicate if worker threads are running @@ -126,7 +126,7 @@ class ignition::gazebo::systems::SensorsPrivate public: std::condition_variable renderCv; /// \brief Connection to events::Stop event, used to stop thread - public: ignition::common::ConnectionPtr stopConn; + public: gz::common::ConnectionPtr stopConn; /// \brief Update time for the next rendering iteration public: std::chrono::steady_clock::duration updateTime; @@ -219,7 +219,7 @@ void SensorsPrivate::WaitForInit() { while (!this->initialized && this->running) { - igndbg << "Waiting for init" << std::endl; + gzdbg << "Waiting for init" << std::endl; std::unique_lock lock(this->renderMutex); // Wait to be ready for initialization or stopped running. // We need rendering sensors to be available to initialize. @@ -231,7 +231,7 @@ void SensorsPrivate::WaitForInit() if (this->doInit) { // Only initialize if there are rendering sensors - igndbg << "Initializing render context" << std::endl; + gzdbg << "Initializing render context" << std::endl; if (this->backgroundColor) this->renderUtil.SetBackgroundColor(*this->backgroundColor); if (this->ambientLight) @@ -245,7 +245,7 @@ void SensorsPrivate::WaitForInit() this->updateAvailable = false; this->renderCv.notify_one(); } - igndbg << "Rendering Thread initialized" << std::endl; + gzdbg << "Rendering Thread initialized" << std::endl; } ////////////////////////////////////////////////// @@ -346,7 +346,7 @@ void SensorsPrivate::RenderThread() { IGN_PROFILE_THREAD_NAME("RenderThread"); - igndbg << "SensorsPrivate::RenderThread started" << std::endl; + gzdbg << "SensorsPrivate::RenderThread started" << std::endl; // We have to wait for rendering sensors to be available this->WaitForInit(); @@ -360,13 +360,13 @@ void SensorsPrivate::RenderThread() for (const auto id : this->sensorIds) this->sensorManager.Remove(id); - igndbg << "SensorsPrivate::RenderThread stopped" << std::endl; + gzdbg << "SensorsPrivate::RenderThread stopped" << std::endl; } ////////////////////////////////////////////////// void SensorsPrivate::Run() { - igndbg << "SensorsPrivate::Run" << std::endl; + gzdbg << "SensorsPrivate::Run" << std::endl; this->running = true; this->renderThread = std::thread(&SensorsPrivate::RenderThread, this); } @@ -374,7 +374,7 @@ void SensorsPrivate::Run() ////////////////////////////////////////////////// void SensorsPrivate::Stop() { - igndbg << "SensorsPrivate::Stop" << std::endl; + gzdbg << "SensorsPrivate::Stop" << std::endl; std::unique_lock lock(this->renderMutex); this->running = false; @@ -447,7 +447,7 @@ void Sensors::Configure(const Entity &/*_id*/, EntityComponentManager &_ecm, EventManager &_eventMgr) { - igndbg << "Configuring Sensors system" << std::endl; + gzdbg << "Configuring Sensors system" << std::endl; // Setup rendering std::string engineName = @@ -536,7 +536,7 @@ void Sensors::PostUpdate(const UpdateInfo &_info, // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { - ignwarn << "Detected jump back in time [" + gzwarn << "Detected jump back in time [" << std::chrono::duration_cast(_info.dt).count() << "s]. System may not work properly." << std::endl; } @@ -552,7 +552,7 @@ void Sensors::PostUpdate(const UpdateInfo &_info, _ecm.HasComponentType(components::SegmentationCamera::typeId) || _ecm.HasComponentType(components::WideAngleCamera::typeId))) { - igndbg << "Initialization needed" << std::endl; + gzdbg << "Initialization needed" << std::endl; this->dataPtr->doInit = true; this->dataPtr->renderCv.notify_one(); } @@ -683,7 +683,7 @@ std::string Sensors::CreateSensor(const Entity &_entity, { if (_sdf.Type() == sdf::SensorType::NONE) { - ignerr << "Unable to create sensor. SDF sensor type is NONE." << std::endl; + gzerr << "Unable to create sensor. SDF sensor type is NONE." << std::endl; return std::string(); } @@ -727,7 +727,7 @@ std::string Sensors::CreateSensor(const Entity &_entity, if (nullptr == sensor) { - ignerr << "Failed to create sensor [" << _sdf.Name() + gzerr << "Failed to create sensor [" << _sdf.Name() << "]." << std::endl; return std::string(); } @@ -802,7 +802,7 @@ std::string Sensors::CreateSensor(const Entity &_entity, std::fabs(this->dataPtr->ambientTemperatureGradient * height); thermalSensor->SetAmbientTemperatureRange(tempRange); - ignmsg << "Setting ambient temperature to " + gzmsg << "Setting ambient temperature to " << this->dataPtr->ambientTemperature << " Kelvin and gradient to " << this->dataPtr->ambientTemperatureGradient << " K/m. " << "The resulting temperature range is: " << tempRange @@ -818,4 +818,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 0c0b05b663..3db5809815 100644 --- a/src/systems/sensors/Sensors.hh +++ b/src/systems/sensors/Sensors.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_SENSORS_HH_ -#define IGNITION_GAZEBO_SYSTEMS_SENSORS_HH_ +#ifndef GZ_SIM_SYSTEMS_SENSORS_HH_ +#define GZ_SIM_SYSTEMS_SENSORS_HH_ #include #include @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declarations. diff --git a/src/systems/shader_param/ShaderParam.cc b/src/systems/shader_param/ShaderParam.cc index 04680e7ca7..bec3f0c333 100644 --- a/src/systems/shader_param/ShaderParam.cc +++ b/src/systems/shader_param/ShaderParam.cc @@ -40,11 +40,11 @@ #include "gz/sim/rendering/RenderUtil.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; -class ignition::gazebo::systems::ShaderParamPrivate +class gz::sim::systems::ShaderParamPrivate { /// \brief Data structure for storing shader param info public: class ShaderParamValue @@ -86,7 +86,7 @@ class ignition::gazebo::systems::ShaderParamPrivate public: std::mutex mutex; /// \brief Connection to pre-render event callback - public: ignition::common::ConnectionPtr connection{nullptr}; + public: gz::common::ConnectionPtr connection{nullptr}; /// \brief Name of visual this plugin is attached to public: std::string visualName; @@ -150,7 +150,7 @@ void ShaderParam::Configure(const Entity &_entity, if (!paramElem->HasElement("shader") || !paramElem->HasElement("name")) { - ignerr << " must have and sdf elements" + gzerr << " must have and sdf elements" << std::endl; paramElem = paramElem->GetNextElement("param"); continue; @@ -192,7 +192,7 @@ void ShaderParam::Configure(const Entity &_entity, // parse path to shaders if (!sdf->HasElement("shader")) { - ignerr << "Unable to load shader param system. " + gzerr << "Unable to load shader param system. " << "Missing SDF element." << std::endl; return; } @@ -203,7 +203,7 @@ void ShaderParam::Configure(const Entity &_entity, if (!shaderElem->HasElement("vertex") || !shaderElem->HasElement("fragment")) { - ignerr << " must have and sdf elements" + gzerr << " must have and sdf elements" << std::endl; } else @@ -230,7 +230,7 @@ void ShaderParam::Configure(const Entity &_entity, } if (this->dataPtr->shaders.empty()) { - ignerr << "Unable to load shader param system. " + gzerr << "Unable to load shader param system. " << "No valid shaders." << std::endl; return; } @@ -243,14 +243,14 @@ void ShaderParam::Configure(const Entity &_entity, // the callback is executed in the rendering thread so do all // rendering operations in that thread this->dataPtr->connection = - _eventMgr.Connect( + _eventMgr.Connect( std::bind(&ShaderParamPrivate::OnUpdate, this->dataPtr.get())); } ////////////////////////////////////////////////// void ShaderParam::PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &) + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &) { IGN_PROFILE("ShaderParam::PreUpdate"); std::lock_guard lock(this->dataPtr->mutex); @@ -325,7 +325,7 @@ void ShaderParamPrivate::OnUpdate() // if both glsl and metal are specified, print a msg to inform that // metal is used instead of glsl if (it != this->shaders.end()) - ignmsg << "Using metal shaders. " << std::endl; + gzmsg << "Using metal shaders. " << std::endl; } #endif this->visual->SetMaterial(mat); @@ -486,9 +486,13 @@ void ShaderParamPrivate::OnUpdate() } IGNITION_ADD_PLUGIN(ShaderParam, - ignition::gazebo::System, + gz::sim::System, ShaderParam::ISystemConfigure, ShaderParam::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(ShaderParam, + "gz::sim::systems::ShaderParam") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(ShaderParam, "ignition::gazebo::systems::ShaderParam") diff --git a/src/systems/shader_param/ShaderParam.hh b/src/systems/shader_param/ShaderParam.hh index 98c3fb2e6e..a7a9e36363 100644 --- a/src/systems/shader_param/ShaderParam.hh +++ b/src/systems/shader_param/ShaderParam.hh @@ -15,19 +15,19 @@ * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_SHADER_PARAM_HH_ -#define IGNITION_GAZEBO_SYSTEMS_SHADER_PARAM_HH_ +#ifndef GZ_SIM_SYSTEMS_SHADER_PARAM_HH_ +#define GZ_SIM_SYSTEMS_SHADER_PARAM_HH_ #include #include "gz/sim/System.hh" -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declaration @@ -57,7 +57,7 @@ namespace systems /// /// \verbatim /// + /// name="gz::sim::systems::ShaderParam"> /// /// materials/my_vs.glsl /// materials/my_fs.glsl @@ -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/thermal/Thermal.cc b/src/systems/thermal/Thermal.cc index f469699822..19e03a635f 100644 --- a/src/systems/thermal/Thermal.cc +++ b/src/systems/thermal/Thermal.cc @@ -32,12 +32,12 @@ #include "gz/sim/EntityComponentManager.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; /// \brief Private Thermal data class. -class ignition::gazebo::systems::ThermalPrivate +class gz::sim::systems::ThermalPrivate { }; @@ -52,8 +52,8 @@ Thermal::~Thermal() = default; ////////////////////////////////////////////////// void Thermal::Configure(const Entity &_entity, const std::shared_ptr &_sdf, - gazebo::EntityComponentManager &_ecm, - gazebo::EventManager & /*_eventMgr*/) + sim::EntityComponentManager &_ecm, + sim::EventManager & /*_eventMgr*/) { const std::string temperatureTag = "temperature"; const std::string heatSignatureTag = "heat_signature"; @@ -62,7 +62,7 @@ void Thermal::Configure(const Entity &_entity, if (_sdf->HasElement(temperatureTag) && _sdf->HasElement(heatSignatureTag)) { - ignwarn << "Both <" << temperatureTag << "> and <" << heatSignatureTag + gzwarn << "Both <" << temperatureTag << "> and <" << heatSignatureTag << "> were specified, but the thermal system only uses one. " << "<" << heatSignatureTag << "> will be used.\n"; } @@ -78,7 +78,7 @@ void Thermal::Configure(const Entity &_entity, // make sure the specified heat signature can be found if (path.empty()) { - ignerr << "Failed to load thermal system. Heat signature [" + gzerr << "Failed to load thermal system. Heat signature [" << heatSignature << "] could not be found\n"; return; } @@ -109,7 +109,7 @@ void Thermal::Configure(const Entity &_entity, max = min; min = temporary; } - igndbg << "Thermal plugin, heat signature: using a minimum temperature of " + gzdbg << "Thermal plugin, heat signature: using a minimum temperature of " << min << " kelvin, and a max temperature of " << max << " kelvin.\n"; components::TemperatureRangeInfo rangeInfo; @@ -124,7 +124,7 @@ void Thermal::Configure(const Entity &_entity, } else { - ignerr << "Failed to load thermal system. " + gzerr << "Failed to load thermal system. " << "Neither <" << temperatureTag << "> or <" << heatSignatureTag << "> were specified.\n"; } @@ -135,4 +135,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 0da1c2c32c..2a6f611bfd 100644 --- a/src/systems/thermal/Thermal.hh +++ b/src/systems/thermal/Thermal.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_THERMAL_HH_ -#define IGNITION_GAZEBO_SYSTEMS_THERMAL_HH_ +#ifndef GZ_SIM_SYSTEMS_THERMAL_HH_ +#define GZ_SIM_SYSTEMS_THERMAL_HH_ #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declarations. @@ -47,7 +47,7 @@ namespace systems public: void Configure(const Entity &_entity, const std::shared_ptr &_sdf, EntityComponentManager &_ecm, - gazebo::EventManager &_eventMgr) final; + sim::EventManager &_eventMgr) final; /// \brief Private data pointer. private: std::unique_ptr dataPtr; diff --git a/src/systems/thermal/ThermalSensor.cc b/src/systems/thermal/ThermalSensor.cc index 030b9c7bcf..ba6354cbe5 100644 --- a/src/systems/thermal/ThermalSensor.cc +++ b/src/systems/thermal/ThermalSensor.cc @@ -29,12 +29,12 @@ #include "gz/sim/EntityComponentManager.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; /// \brief Private Thermal sensor data class. -class ignition::gazebo::systems::ThermalSensorPrivate +class gz::sim::systems::ThermalSensorPrivate { }; @@ -50,8 +50,8 @@ ThermalSensor::~ThermalSensor() = default; ////////////////////////////////////////////////// void ThermalSensor::Configure(const Entity &_entity, const std::shared_ptr &_sdf, - gazebo::EntityComponentManager &_ecm, - gazebo::EventManager & /*_eventMgr*/) + sim::EntityComponentManager &_ecm, + sim::EventManager & /*_eventMgr*/) { const std::string resolutionTag = "resolution"; const std::string minTempTag = "min_temp"; @@ -60,7 +60,7 @@ void ThermalSensor::Configure(const Entity &_entity, auto sensorComp = _ecm.Component(_entity); if (sensorComp == nullptr) { - ignerr << "The thermal sensor system can only be used to configure " + gzerr << "The thermal sensor system can only be used to configure " << "parameters of thermal camera sensor " << std::endl; return; } @@ -89,5 +89,9 @@ IGNITION_ADD_PLUGIN(ThermalSensor, System, ThermalSensor::ISystemConfigure ) +IGNITION_ADD_PLUGIN_ALIAS(ThermalSensor, + "gz::sim::systems::ThermalSensor") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(ThermalSensor, "ignition::gazebo::systems::ThermalSensor") diff --git a/src/systems/thermal/ThermalSensor.hh b/src/systems/thermal/ThermalSensor.hh index dae7094bb3..0734ff2bcf 100644 --- a/src/systems/thermal/ThermalSensor.hh +++ b/src/systems/thermal/ThermalSensor.hh @@ -14,20 +14,20 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_THERMALSENSOR_HH_ -#define IGNITION_GAZEBO_SYSTEMS_THERMALSENSOR_HH_ +#ifndef GZ_SIM_SYSTEMS_THERMALSENSOR_HH_ +#define GZ_SIM_SYSTEMS_THERMALSENSOR_HH_ #include #include #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declarations. @@ -48,7 +48,7 @@ namespace systems public: void Configure(const Entity &_entity, const std::shared_ptr &_sdf, EntityComponentManager &_ecm, - gazebo::EventManager &_eventMgr) final; + sim::EventManager &_eventMgr) final; /// \brief Private data pointer. private: std::unique_ptr dataPtr; diff --git a/src/systems/thruster/Thruster.cc b/src/systems/thruster/Thruster.cc index 3f42a19e33..0042ea2e84 100644 --- a/src/systems/thruster/Thruster.cc +++ b/src/systems/thruster/Thruster.cc @@ -39,11 +39,11 @@ #include "Thruster.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; -class ignition::gazebo::systems::ThrusterPrivateData +class gz::sim::systems::ThrusterPrivateData { /// \brief The mode of operation public: enum OperationMode { @@ -111,10 +111,10 @@ class ignition::gazebo::systems::ThrusterPrivateData public: double propellerDiameter = 0.02; /// \brief callback for handling thrust update - public: void OnCmdThrust(const ignition::msgs::Double &_msg); + public: void OnCmdThrust(const gz::msgs::Double &_msg); /// \brief callback for handling angular velocity update - public: void OnCmdAngVel(const ignition::msgs::Double &_msg); + public: void OnCmdAngVel(const gz::msgs::Double &_msg); /// \brief function which computes angular velocity from thrust /// \param[in] _thrust Thrust in N @@ -136,13 +136,13 @@ Thruster::Thruster(): ///////////////////////////////////////////////// void Thruster::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*/) { // Create model object, to access convenient functions - auto model = ignition::gazebo::Model(_entity); + auto model = gz::sim::Model(_entity); auto modelName = model.Name(_ecm); // Get namespace @@ -155,7 +155,7 @@ void Thruster::Configure( // Get joint name if (!_sdf->HasElement("joint_name")) { - ignerr << "Missing . Plugin won't be initialized." + gzerr << "Missing . Plugin won't be initialized." << std::endl; return; } @@ -190,13 +190,13 @@ void Thruster::Configure( this->dataPtr->jointEntity = model.JointByName(_ecm, jointName); if (kNullEntity == this->dataPtr->jointEntity) { - ignerr << "Failed to find joint [" << jointName << "] in model [" + gzerr << "Failed to find joint [" << jointName << "] in model [" << modelName << "]. Plugin not initialized." << std::endl; return; } this->dataPtr->jointAxis = - _ecm.Component( + _ecm.Component( this->dataPtr->jointEntity)->Data().Xyz(); this->dataPtr->jointPose = _ecm.Component( @@ -204,7 +204,7 @@ void Thruster::Configure( // Get link entity auto childLink = - _ecm.Component( + _ecm.Component( this->dataPtr->jointEntity); this->dataPtr->linkEntity = model.LinkByName(_ecm, childLink->Data()); @@ -213,7 +213,7 @@ void Thruster::Configure( // Keeping cmd_pos for backwards compatibility // TODO(chapulina) Deprecate cmd_pos, because the commands aren't positions std::string thrusterTopicOld = - ignition::transport::TopicUtils::AsValidTopic( + gz::transport::TopicUtils::AsValidTopic( "/model/" + ns + "/joint/" + jointName + "/cmd_pos"); this->dataPtr->node.Subscribe( @@ -222,7 +222,7 @@ void Thruster::Configure( this->dataPtr.get()); // Subscribe to force commands - std::string thrusterTopic = ignition::transport::TopicUtils::AsValidTopic( + std::string thrusterTopic = gz::transport::TopicUtils::AsValidTopic( "/model/" + ns + "/joint/" + jointName + "/cmd_thrust"); this->dataPtr->node.Subscribe( @@ -230,10 +230,10 @@ void Thruster::Configure( &ThrusterPrivateData::OnCmdThrust, this->dataPtr.get()); - ignmsg << "Thruster listening to commands in [" << thrusterTopic << "]" + gzmsg << "Thruster listening to commands in [" << thrusterTopic << "]" << std::endl; - std::string feedbackTopic = ignition::transport::TopicUtils::AsValidTopic( + std::string feedbackTopic = gz::transport::TopicUtils::AsValidTopic( "/model/" + ns + "/joint/" + jointName + "/ang_vel"); this->dataPtr->pub = this->dataPtr->node.Advertise( feedbackTopic @@ -241,9 +241,9 @@ void Thruster::Configure( } else { - igndbg << "Using angular velocity mode" << std::endl; + gzdbg << "Using angular velocity mode" << std::endl; // Subscribe to angvel commands - std::string thrusterTopic = ignition::transport::TopicUtils::AsValidTopic( + std::string thrusterTopic = gz::transport::TopicUtils::AsValidTopic( "/model/" + ns + "/joint/" + jointName + "/cmd_vel"); this->dataPtr->node.Subscribe( @@ -251,10 +251,10 @@ void Thruster::Configure( &ThrusterPrivateData::OnCmdAngVel, this->dataPtr.get()); - ignmsg << "Thruster listening to commands in [" << thrusterTopic << "]" + gzmsg << "Thruster listening to commands in [" << thrusterTopic << "]" << std::endl; - std::string feedbackTopic = ignition::transport::TopicUtils::AsValidTopic( + std::string feedbackTopic = gz::transport::TopicUtils::AsValidTopic( "/model/" + ns + "/joint/" + jointName + "/force"); this->dataPtr->pub = this->dataPtr->node.Advertise( feedbackTopic @@ -278,7 +278,7 @@ void Thruster::Configure( } if (maxThrustCmd < minThrustCmd) { - ignerr << " must be greater than or equal to " + gzerr << " must be greater than or equal to " << ". Revert to using default values: " << "min: " << this->dataPtr->cmdMin << ", " << "max: " << this->dataPtr->cmdMax << std::endl; @@ -296,7 +296,7 @@ void Thruster::Configure( if (!this->dataPtr->velocityControl) { - igndbg << "Using PID controller for propeller joint." << std::endl; + gzdbg << "Using PID controller for propeller joint." << std::endl; double p = 0.1; double i = 0; @@ -332,15 +332,15 @@ void Thruster::Configure( } else { - igndbg << "Using velocity control for propeller joint." << std::endl; + gzdbg << "Using velocity control for propeller joint." << std::endl; } } ///////////////////////////////////////////////// -void ThrusterPrivateData::OnCmdThrust(const ignition::msgs::Double &_msg) +void ThrusterPrivateData::OnCmdThrust(const gz::msgs::Double &_msg) { std::lock_guard lock(mtx); - this->thrust = ignition::math::clamp(ignition::math::fixnan(_msg.data()), + this->thrust = gz::math::clamp(gz::math::fixnan(_msg.data()), this->cmdMin, this->cmdMax); // Thrust is proportional to the Rotation Rate squared @@ -349,11 +349,11 @@ void ThrusterPrivateData::OnCmdThrust(const ignition::msgs::Double &_msg) } ///////////////////////////////////////////////// -void ThrusterPrivateData::OnCmdAngVel(const ignition::msgs::Double &_msg) +void ThrusterPrivateData::OnCmdAngVel(const gz::msgs::Double &_msg) { std::lock_guard lock(mtx); this->propellerAngVel = - ignition::math::clamp(ignition::math::fixnan(_msg.data()), + gz::math::clamp(gz::math::fixnan(_msg.data()), this->cmdMin, this->cmdMax); // Thrust is proportional to the Rotation Rate squared @@ -387,13 +387,13 @@ double ThrusterPrivateData::AngularVelToThrust(double _angVel) ///////////////////////////////////////////////// void Thruster::PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) + const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) { if (_info.paused) return; - ignition::gazebo::Link link(this->dataPtr->linkEntity); + gz::sim::Link link(this->dataPtr->linkEntity); // TODO(arjo129): add logic for custom coordinate frame // Convert joint axis to the world frame @@ -428,7 +428,7 @@ void Thruster::PreUpdate( else { auto velocityComp = - _ecm.Component( + _ecm.Component( this->dataPtr->jointEntity); if (velocityComp == nullptr) { @@ -465,4 +465,7 @@ IGNITION_ADD_PLUGIN( Thruster::ISystemConfigure, Thruster::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(Thruster, "gz::sim::systems::Thruster") + +// TODO(CH3): Deprecated, remove on version 8 IGNITION_ADD_PLUGIN_ALIAS(Thruster, "ignition::gazebo::systems::Thruster") diff --git a/src/systems/thruster/Thruster.hh b/src/systems/thruster/Thruster.hh index 45a3c30dd0..a85f00c249 100644 --- a/src/systems/thruster/Thruster.hh +++ b/src/systems/thruster/Thruster.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_GAZEBO_SYSTEMS_THRUSTER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_THRUSTER_HH_ +#ifndef GZ_SIM_SYSTEMS_THRUSTER_HH_ +#define GZ_SIM_SYSTEMS_THRUSTER_HH_ #include #include -namespace ignition +namespace gz { -namespace gazebo +namespace sim { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { // Forward declaration @@ -41,7 +41,7 @@ namespace systems /// Alternatively, one may send angular velocity commands to calculate the /// force to be applied using the said equation. In the default mode the /// plugin will publish angular velocity in radians per second on - /// `/model/{ns}/joint/{joint_name}/ang_vel` as an ignition.msgs.double. If + /// `/model/{ns}/joint/{joint_name}/ang_vel` as an gz.msgs.double. If /// is set to true it publishes force in Newtons instead to /// `/model/{ns}/joint/{joint_name}/force`. /// @@ -95,33 +95,33 @@ namespace systems /// To control the rudder of the craft run the following: /// ``` /// ign topic -t /model/tethys/joint/vertical_fins_joint/0/cmd_pos - /// -m ignition.msgs.Double -p 'data: -0.17' + /// -m gz.msgs.Double -p 'data: -0.17' /// ``` /// To apply a thrust you may run the following command: /// ``` /// ign topic -t /model/tethys/joint/propeller_joint/cmd_thrust - /// -m ignition.msgs.Double -p 'data: -31' + /// -m gz.msgs.Double -p 'data: -31' /// ``` /// The vehicle should move in a circle. class Thruster: - 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 Constructor public: Thruster(); /// Documentation inherited public: void Configure( - const ignition::gazebo::Entity &_entity, + 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; /// 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/touch_plugin/TouchPlugin.cc b/src/systems/touch_plugin/TouchPlugin.cc index 32937b1c14..44df38377d 100644 --- a/src/systems/touch_plugin/TouchPlugin.cc +++ b/src/systems/touch_plugin/TouchPlugin.cc @@ -38,11 +38,11 @@ #include "gz/sim/Model.hh" #include "gz/sim/Util.hh" -using namespace ignition; -using namespace gazebo; +using namespace gz; +using namespace sim; using namespace systems; -class ignition::gazebo::systems::TouchPluginPrivate +class gz::sim::systems::TouchPluginPrivate { // Initialize the plugin public: void Load(const EntityComponentManager &_ecm, @@ -121,7 +121,7 @@ void TouchPluginPrivate::Load(const EntityComponentManager &_ecm, // Get target substring if (!_sdf->HasElement("target")) { - ignerr << "Missing required parameter ." << std::endl; + gzerr << "Missing required parameter ." << std::endl; return; } @@ -160,14 +160,14 @@ void TouchPluginPrivate::Load(const EntityComponentManager &_ecm, // Namespace if (!_sdf->HasElement("namespace")) { - ignerr << "Missing required parameter " << std::endl; + gzerr << "Missing required parameter " << std::endl; return; } this->ns = transport::TopicUtils::AsValidTopic(_sdf->Get( "namespace")); if (this->ns.empty()) { - ignerr << " [" << _sdf->Get("namespace") + gzerr << " [" << _sdf->Get("namespace") << "] is invalid." << std::endl; return; } @@ -175,7 +175,7 @@ void TouchPluginPrivate::Load(const EntityComponentManager &_ecm, // Target time if (!_sdf->HasElement("time")) { - ignerr << "Missing required parameter "; diff --git a/test/worlds/ackermann_steering.sdf b/test/worlds/ackermann_steering.sdf index fbc52aacbe..9ad0ae27fe 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 f7fbf53d4b..743979f7b4 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 9f1a759749..3151f46472 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 0774b698a1..1e2fb3a2ea 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 a55700d14b..f6963b9554 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 aefeeb94a4..26cc83334c 100644 --- a/test/worlds/air_pressure.sdf +++ b/test/worlds/air_pressure.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::AirPressure"> + name="gz::sim::systems::SceneBroadcaster"> 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/battery.sdf b/test/worlds/battery.sdf index 9078867090..632dd80d74 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 @@ -73,7 +73,7 @@ + name="gz::sim::systems::LinearBatteryPlugin"> linear_battery_topics 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 a8b75f9899..63e045f2f9 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 88a6361b9a..c7c7f6b0a3 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/buoyancy_engine.sdf b/test/worlds/buoyancy_engine.sdf index e608990431..1016af4df2 100644 --- a/test/worlds/buoyancy_engine.sdf +++ b/test/worlds/buoyancy_engine.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Buoyancy"> 1000 @@ -57,7 +57,7 @@ + name="gz::sim::systems::BuoyancyEngine"> body buoyant_box 0.001 @@ -97,7 +97,7 @@ + name="gz::sim::systems::BuoyancyEngine"> body buoyant_box 0.001 diff --git a/test/worlds/buoyancy_graded_restoring_moments.sdf b/test/worlds/buoyancy_graded_restoring_moments.sdf index 13d831b2db..ff6a01be39 100644 --- a/test/worlds/buoyancy_graded_restoring_moments.sdf +++ b/test/worlds/buoyancy_graded_restoring_moments.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Buoyancy"> 1000 diff --git a/test/worlds/buoyancy_uniform_restoring_moments.sdf b/test/worlds/buoyancy_uniform_restoring_moments.sdf index 81a1bcadf3..2aa4851527 100644 --- a/test/worlds/buoyancy_uniform_restoring_moments.sdf +++ b/test/worlds/buoyancy_uniform_restoring_moments.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Buoyancy"> 1000 diff --git a/test/worlds/camera_distortion.sdf b/test/worlds/camera_distortion.sdf index dca73f8535..169fa08989 100644 --- a/test/worlds/camera_distortion.sdf +++ b/test/worlds/camera_distortion.sdf @@ -7,15 +7,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Sensors"> ogre 0 0 0 1 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 f1a67f0449..30b6f089f6 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"> 0 0 0 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/center_of_volume_graded.sdf b/test/worlds/center_of_volume_graded.sdf index 39c1b4d7a9..c845f5cb2e 100644 --- a/test/worlds/center_of_volume_graded.sdf +++ b/test/worlds/center_of_volume_graded.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Buoyancy"> 1000 @@ -23,11 +23,11 @@ + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> 0 0 0 0 0 0 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/collada_world_exporter_lights.sdf b/test/worlds/collada_world_exporter_lights.sdf index 86ae3a84ae..cca54d2565 100644 --- a/test/worlds/collada_world_exporter_lights.sdf +++ b/test/worlds/collada_world_exporter_lights.sdf @@ -7,7 +7,7 @@ + name="gz::sim::systems::ColladaWorldExporter"> diff --git a/test/worlds/collada_world_exporter_submesh.sdf b/test/worlds/collada_world_exporter_submesh.sdf index df8c052595..649375f8c9 100644 --- a/test/worlds/collada_world_exporter_submesh.sdf +++ b/test/worlds/collada_world_exporter_submesh.sdf @@ -10,12 +10,12 @@ + name="gz::sim::systems::Physics"> + 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/contact_with_entity_names.sdf b/test/worlds/contact_with_entity_names.sdf index 7c346e4aa5..7a0c6198d6 100644 --- a/test/worlds/contact_with_entity_names.sdf +++ b/test/worlds/contact_with_entity_names.sdf @@ -7,14 +7,14 @@ + name="gz::sim::systems::Physics"> true + name="gz::sim::systems::Contact"> diff --git a/test/worlds/contact_without_entity_names.sdf b/test/worlds/contact_without_entity_names.sdf index d842486015..0b9867c67a 100644 --- a/test/worlds/contact_without_entity_names.sdf +++ b/test/worlds/contact_without_entity_names.sdf @@ -7,14 +7,14 @@ + name="gz::sim::systems::Physics"> false + 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 2cc83a4b6c..d7c19c9bc4 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 89e791e83d..4cad3fad5d 100644 --- a/test/worlds/depth_camera_sensor.sdf +++ b/test/worlds/depth_camera_sensor.sdf @@ -7,11 +7,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 bf4b9c0535..79bb49c479 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 @@ -240,7 +240,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 eb52700393..9e348045be 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_nested.sdf b/test/worlds/diff_drive_nested.sdf index 1b7b914e34..8f6f2d70ee 100644 --- a/test/worlds/diff_drive_nested.sdf +++ b/test/worlds/diff_drive_nested.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::Physics"> @@ -227,7 +227,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint right_wheel_joint 1.25 @@ -245,7 +245,7 @@ + name="gz::sim::systems::JointStatePublisher"> 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/follow_actor.sdf b/test/worlds/follow_actor.sdf index c1ac2046fe..7a77def52d 100644 --- a/test/worlds/follow_actor.sdf +++ b/test/worlds/follow_actor.sdf @@ -9,7 +9,7 @@ --> + name="gz::sim::systems::Sensors"> ogre2 @@ -88,7 +88,7 @@ 0 -2 1.0 0 0 0 https://fuel.ignitionrobotics.org/1.0/chapulina/models/Walking actor + name="gz::sim::systems::FollowActor"> box 1.0 8.0 diff --git a/test/worlds/force_torque.sdf b/test/worlds/force_torque.sdf index eacc458c9c..2bb1d22d6b 100644 --- a/test/worlds/force_torque.sdf +++ b/test/worlds/force_torque.sdf @@ -4,9 +4,9 @@ 0 - - - + + + true 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/gpu_lidar_sensor.sdf b/test/worlds/gpu_lidar_sensor.sdf index 28d414d43d..354ebf413f 100644 --- a/test/worlds/gpu_lidar_sensor.sdf +++ b/test/worlds/gpu_lidar_sensor.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre2 diff --git a/test/worlds/graded_buoyancy.sdf b/test/worlds/graded_buoyancy.sdf index 964d6e378d..dfbd588483 100644 --- a/test/worlds/graded_buoyancy.sdf +++ b/test/worlds/graded_buoyancy.sdf @@ -1,6 +1,6 @@ @@ -13,19 +13,19 @@ + 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/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/imu_heading_deg.sdf b/test/worlds/imu_heading_deg.sdf index b93b2a3f0f..1ee49a8a37 100644 --- a/test/worlds/imu_heading_deg.sdf +++ b/test/worlds/imu_heading_deg.sdf @@ -8,11 +8,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Imu"> diff --git a/test/worlds/imu_named_frame.sdf b/test/worlds/imu_named_frame.sdf index e7256ec196..ac70abd51b 100644 --- a/test/worlds/imu_named_frame.sdf +++ b/test/worlds/imu_named_frame.sdf @@ -8,11 +8,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Imu"> diff --git a/test/worlds/imu_no_orientation.sdf b/test/worlds/imu_no_orientation.sdf index caf1e9f1e7..3f1b5d5829 100644 --- a/test/worlds/imu_no_orientation.sdf +++ b/test/worlds/imu_no_orientation.sdf @@ -8,11 +8,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Imu"> diff --git a/test/worlds/imu_rotating_demo.sdf b/test/worlds/imu_rotating_demo.sdf index da86f4bd13..34074af5f3 100644 --- a/test/worlds/imu_rotating_demo.sdf +++ b/test/worlds/imu_rotating_demo.sdf @@ -8,15 +8,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Imu"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/include_connected_nested_models.sdf b/test/worlds/include_connected_nested_models.sdf index 3e03aa35eb..51ac2b0d3a 100644 --- a/test/worlds/include_connected_nested_models.sdf +++ b/test/worlds/include_connected_nested_models.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/include_nested_models.sdf b/test/worlds/include_nested_models.sdf index 39e29f3a08..e98f0d5617 100644 --- a/test/worlds/include_nested_models.sdf +++ b/test/worlds/include_nested_models.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/joint_controller.sdf b/test/worlds/joint_controller.sdf index fce422dc84..4685383d19 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"> true @@ -111,7 +111,7 @@ + name="gz::sim::systems::JointController"> j1 5.0 @@ -189,7 +189,7 @@ + name="gz::sim::systems::JointController"> j1 true 0.2 diff --git a/test/worlds/joint_controller_invalid.sdf b/test/worlds/joint_controller_invalid.sdf index 45a8494ca4..e7cc38f8a8 100644 --- a/test/worlds/joint_controller_invalid.sdf +++ b/test/worlds/joint_controller_invalid.sdf @@ -9,7 +9,7 @@ + name="gz::sim::systems::JointController"> invalid diff --git a/test/worlds/joint_position_controller.sdf b/test/worlds/joint_position_controller.sdf index 9a15596021..4a517c516c 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"> @@ -112,7 +112,7 @@ + name="gz::sim::systems::JointPositionController"> j1 1 0.1 diff --git a/test/worlds/joint_position_controller_velocity.sdf b/test/worlds/joint_position_controller_velocity.sdf index 8d382ad10b..6719773477 100644 --- a/test/worlds/joint_position_controller_velocity.sdf +++ b/test/worlds/joint_position_controller_velocity.sdf @@ -6,11 +6,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -111,7 +111,7 @@ + name="gz::sim::systems::JointPositionController"> j1 true 1000 diff --git a/test/worlds/joint_sensor.sdf b/test/worlds/joint_sensor.sdf index c74fd6cf6c..c9d0fa5d6a 100644 --- a/test/worlds/joint_sensor.sdf +++ b/test/worlds/joint_sensor.sdf @@ -6,11 +6,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/joint_trajectory_controller.sdf b/test/worlds/joint_trajectory_controller.sdf index 25e6e1547e..b186e69565 100644 --- a/test/worlds/joint_trajectory_controller.sdf +++ b/test/worlds/joint_trajectory_controller.sdf @@ -7,13 +7,13 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> 0.4 0.4 0.4 @@ -180,7 +180,7 @@ + name="gz::sim::systems::JointTrajectoryController"> RR_position_control_joint2 25 @@ -343,7 +343,7 @@ + name="gz::sim::systems::JointTrajectoryController"> test_custom_topic/velocity_control 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/lift_drag_nested_model.sdf b/test/worlds/lift_drag_nested_model.sdf index 0c8f54df84..18a0588122 100644 --- a/test/worlds/lift_drag_nested_model.sdf +++ b/test/worlds/lift_drag_nested_model.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::Physics"> @@ -113,7 +113,7 @@ + name="gz::sim::systems::LiftDrag"> 0.1 4.000 20.0 @@ -131,7 +131,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 8150fcad1e..e5f77cd90b 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"> true diff --git a/test/worlds/lights_render.sdf b/test/worlds/lights_render.sdf index 6abff89c28..2b639b5ffd 100644 --- a/test/worlds/lights_render.sdf +++ b/test/worlds/lights_render.sdf @@ -7,15 +7,15 @@ + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::Sensors"> ogre diff --git a/test/worlds/log_playback.sdf b/test/worlds/log_playback.sdf index 2218dd7848..18134937ca 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'> 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 c0e2761c55..8c0aec957e 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 d142e54607..195cdc4a3c 100644 --- a/test/worlds/magnetometer.sdf +++ b/test/worlds/magnetometer.sdf @@ -8,15 +8,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Magnetometer"> + name="gz::sim::systems::SceneBroadcaster"> 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/model_nested_include.sdf b/test/worlds/model_nested_include.sdf index f007fbc4f9..6cbee807e6 100644 --- a/test/worlds/model_nested_include.sdf +++ b/test/worlds/model_nested_include.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/model_photo_shoot_random_joints.sdf b/test/worlds/model_photo_shoot_random_joints.sdf index dd22d60677..f843a61a06 100644 --- a/test/worlds/model_photo_shoot_random_joints.sdf +++ b/test/worlds/model_photo_shoot_random_joints.sdf @@ -1,6 +1,6 @@ @@ -104,11 +104,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/navsat.sdf b/test/worlds/navsat.sdf index 46d984a18e..9f8e021a68 100644 --- a/test/worlds/navsat.sdf +++ b/test/worlds/navsat.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::NavSat"> diff --git a/test/worlds/nested_model.sdf b/test/worlds/nested_model.sdf index 68ab84077e..47b17a8085 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"> false false false diff --git a/test/worlds/nested_model_canonical_link.sdf b/test/worlds/nested_model_canonical_link.sdf index df4344d1cd..294bcba7b5 100644 --- a/test/worlds/nested_model_canonical_link.sdf +++ b/test/worlds/nested_model_canonical_link.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/non_rendering_sensors.sdf b/test/worlds/non_rendering_sensors.sdf index 096a971815..fffaeff9b9 100644 --- a/test/worlds/non_rendering_sensors.sdf +++ b/test/worlds/non_rendering_sensors.sdf @@ -6,12 +6,12 @@ + name="gz::sim::systems::Sensors"> ogre2 + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/nondefault_canonical.sdf b/test/worlds/nondefault_canonical.sdf index 5ad31d435f..4826a336f8 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/odometry_noise.sdf b/test/worlds/odometry_noise.sdf index e5d158f5a5..9e03676791 100644 --- a/test/worlds/odometry_noise.sdf +++ b/test/worlds/odometry_noise.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::Physics"> @@ -221,7 +221,7 @@ + name="gz::sim::systems::OdometryPublisher"> 1 diff --git a/test/worlds/odometry_offset.sdf b/test/worlds/odometry_offset.sdf index ec5468ff63..941847a235 100644 --- a/test/worlds/odometry_offset.sdf +++ b/test/worlds/odometry_offset.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::Physics"> @@ -221,7 +221,7 @@ + name="gz::sim::systems::OdometryPublisher"> 1 -1 0 1.5708 0 0 diff --git a/test/worlds/odometry_publisher.sdf b/test/worlds/odometry_publisher.sdf index ccda8141bd..8b82195b24 100644 --- a/test/worlds/odometry_publisher.sdf +++ b/test/worlds/odometry_publisher.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::Physics"> @@ -221,7 +221,7 @@ + name="gz::sim::systems::OdometryPublisher"> diff --git a/test/worlds/odometry_publisher_3d.sdf b/test/worlds/odometry_publisher_3d.sdf index dbb29326c3..24dfbad1f1 100644 --- a/test/worlds/odometry_publisher_3d.sdf +++ b/test/worlds/odometry_publisher_3d.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::Physics"> @@ -262,7 +262,7 @@ + name="gz::sim::systems::MulticopterMotorModel"> X3 rotor_0_joint rotor_0 @@ -282,7 +282,7 @@ + name="gz::sim::systems::MulticopterMotorModel"> X3 rotor_1_joint rotor_1 @@ -302,7 +302,7 @@ + name="gz::sim::systems::MulticopterMotorModel"> X3 rotor_2_joint rotor_2 @@ -322,7 +322,7 @@ + name="gz::sim::systems::MulticopterMotorModel"> X3 rotor_3_joint rotor_3 @@ -342,7 +342,7 @@ + name="gz::sim::systems::MulticopterVelocityControl"> X3 gazebo/command/twist enable @@ -381,7 +381,7 @@ + name="gz::sim::systems::OdometryPublisher"> 3 diff --git a/test/worlds/odometry_publisher_custom.sdf b/test/worlds/odometry_publisher_custom.sdf index 8adab5b1c4..c74cde3160 100644 --- a/test/worlds/odometry_publisher_custom.sdf +++ b/test/worlds/odometry_publisher_custom.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::Physics"> @@ -221,7 +221,7 @@ + name="gz::sim::systems::OdometryPublisher"> 50 /model/bar/odom odomCustom diff --git a/test/worlds/office.sdf b/test/worlds/office.sdf index 27b0adba41..70687016aa 100644 --- a/test/worlds/office.sdf +++ b/test/worlds/office.sdf @@ -5,9 +5,9 @@ 0.01 0 - + - + 1 1 1 @@ -27,7 +27,7 @@ -0.5 0.1 -0.9 - + building_L1 model://building_L1 diff --git a/test/worlds/only_canonical_link_moves.sdf b/test/worlds/only_canonical_link_moves.sdf index 5649e3facc..2c9313ce3f 100644 --- a/test/worlds/only_canonical_link_moves.sdf +++ b/test/worlds/only_canonical_link_moves.sdf @@ -7,11 +7,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> 0 0 10 0 0 0 diff --git a/test/worlds/optical_tactile_plugin.sdf b/test/worlds/optical_tactile_plugin.sdf index 253a94b3ed..65779715f5 100644 --- a/test/worlds/optical_tactile_plugin.sdf +++ b/test/worlds/optical_tactile_plugin.sdf @@ -8,15 +8,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Contact"> + name="gz::sim::systems::Sensors"> @@ -80,7 +80,7 @@ false + name="gz::sim::systems::OpticalTactilePlugin"> false optical_tactile_sensor false diff --git a/test/worlds/particle_emitter.sdf b/test/worlds/particle_emitter.sdf index e086e8b8b5..bf3a7149de 100644 --- a/test/worlds/particle_emitter.sdf +++ b/test/worlds/particle_emitter.sdf @@ -9,7 +9,7 @@ + name="gz::sim::systems::ParticleEmitter"> 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/physics_options.sdf b/test/worlds/physics_options.sdf index 0351a2495e..9f185102f1 100644 --- a/test/worlds/physics_options.sdf +++ b/test/worlds/physics_options.sdf @@ -12,7 +12,7 @@ + name="gz::sim::systems::Physics"> diff --git a/test/worlds/plugins.sdf b/test/worlds/plugins.sdf index d4668e294d..91800ed7d8 100644 --- a/test/worlds/plugins.sdf +++ b/test/worlds/plugins.sdf @@ -7,28 +7,28 @@ + name="gz::sim::TestWorldSystem"> 0.123 + name="gz::sim::TestModelSystem"> 987 + name="gz::sim::TestSensorSystem"> 456 + name="gz::sim::TestVisualSystem"> 890 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/reset.sdf b/test/worlds/reset.sdf index 10c6c63426..b346ea8f37 100644 --- a/test/worlds/reset.sdf +++ b/test/worlds/reset.sdf @@ -3,15 +3,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::UserCommands"> 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 345a170632..3dbfdac4fe 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 abdfc56dda..3506efd7fe 100644 --- a/test/worlds/rgbd_camera_sensor.sdf +++ b/test/worlds/rgbd_camera_sensor.sdf @@ -7,16 +7,16 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre2 + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/save_world.sdf b/test/worlds/save_world.sdf index 055dd32d4e..5c80864416 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"> 0 0 -9.8 5.5645e-6 22.8758e-6 -42.3884e-6 diff --git a/test/worlds/sea_storm_effects.sdf b/test/worlds/sea_storm_effects.sdf index f5f9e3f14a..efbc6eff33 100644 --- a/test/worlds/sea_storm_effects.sdf +++ b/test/worlds/sea_storm_effects.sdf @@ -9,16 +9,16 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::WindEffects"> 0 0.2 diff --git a/test/worlds/sensor.sdf b/test/worlds/sensor.sdf index fe6568e3f7..428c86d2fc 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/sensors_system_battery.sdf b/test/worlds/sensors_system_battery.sdf index 3c747c60ea..59ced7ef2e 100644 --- a/test/worlds/sensors_system_battery.sdf +++ b/test/worlds/sensors_system_battery.sdf @@ -7,15 +7,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Sensors"> ogre2 true @@ -96,7 +96,7 @@ + name="gz::sim::systems::LinearBatteryPlugin"> linear_battery 12.592 12.694 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/shapes_scene_broadcaster_only.sdf b/test/worlds/shapes_scene_broadcaster_only.sdf index dff73115c5..19fd713783 100644 --- a/test/worlds/shapes_scene_broadcaster_only.sdf +++ b/test/worlds/shapes_scene_broadcaster_only.sdf @@ -8,7 +8,7 @@ + name="gz::sim::systems::SceneBroadcaster"> 1000 diff --git a/test/worlds/spherical_coordinates.sdf b/test/worlds/spherical_coordinates.sdf index ca0796c74b..cc2fc123fe 100644 --- a/test/worlds/spherical_coordinates.sdf +++ b/test/worlds/spherical_coordinates.sdf @@ -7,12 +7,12 @@ + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::Physics"> 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 56a2544de4..fe6fa71bf7 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"> 600.0 @@ -154,7 +154,7 @@ + name="gz::sim::systems::Thermal"> 400.0 @@ -203,7 +203,7 @@ + name="gz::sim::systems::Thermal"> ../media/duck.png 400.0 @@ -247,7 +247,7 @@ + name="gz::sim::systems::Thermal"> ../media/duck.png 500.0 @@ -294,7 +294,7 @@ + name="gz::sim::systems::Thermal"> ../media/duck.png 400.0 @@ -346,7 +346,7 @@ thermal_camera_8bit/image + name="gz::sim::systems::ThermalSensor"> 253.15 673.15 3.0 diff --git a/test/worlds/thermal_invalid.sdf b/test/worlds/thermal_invalid.sdf index 960c072b0f..3fb08b3036 100644 --- a/test/worlds/thermal_invalid.sdf +++ b/test/worlds/thermal_invalid.sdf @@ -12,16 +12,16 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre2 + name="gz::sim::systems::SceneBroadcaster"> @@ -61,7 +61,7 @@ + name="gz::sim::systems::Thermal"> 600.0 @@ -95,7 +95,7 @@ + name="gz::sim::systems::Thermal"> 800.0 @@ -127,7 +127,7 @@ + name="gz::sim::systems::Thermal"> -10.0 @@ -171,7 +171,7 @@ thermal_camera_invalid/image + name="gz::sim::systems::ThermalSensor"> 999 -590 0.0 diff --git a/test/worlds/thruster_ang_vel_cmd.sdf b/test/worlds/thruster_ang_vel_cmd.sdf index 28185e1ec5..c026c82b3c 100644 --- a/test/worlds/thruster_ang_vel_cmd.sdf +++ b/test/worlds/thruster_ang_vel_cmd.sdf @@ -12,11 +12,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -96,7 +96,7 @@ + name="gz::sim::systems::Thruster"> custom propeller_joint 0.005 diff --git a/test/worlds/thruster_ccw_ang_vel_cmd.sdf b/test/worlds/thruster_ccw_ang_vel_cmd.sdf index 9e1651ca3a..8f2c725b91 100644 --- a/test/worlds/thruster_ccw_ang_vel_cmd.sdf +++ b/test/worlds/thruster_ccw_ang_vel_cmd.sdf @@ -12,11 +12,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -96,7 +96,7 @@ + name="gz::sim::systems::Thruster"> custom propeller_joint diff --git a/test/worlds/thruster_ccw_force_cmd.sdf b/test/worlds/thruster_ccw_force_cmd.sdf index 84a975d5ab..339928bb24 100644 --- a/test/worlds/thruster_ccw_force_cmd.sdf +++ b/test/worlds/thruster_ccw_force_cmd.sdf @@ -12,11 +12,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -96,7 +96,7 @@ + name="gz::sim::systems::Thruster"> custom propeller_joint diff --git a/test/worlds/thruster_pid.sdf b/test/worlds/thruster_pid.sdf index 540c73170b..61ca0b509f 100644 --- a/test/worlds/thruster_pid.sdf +++ b/test/worlds/thruster_pid.sdf @@ -12,11 +12,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -99,7 +99,7 @@ + name="gz::sim::systems::Thruster"> propeller_joint 0.004 1000 diff --git a/test/worlds/thruster_vel_cmd.sdf b/test/worlds/thruster_vel_cmd.sdf index 1850eac8f4..494d1fd428 100644 --- a/test/worlds/thruster_vel_cmd.sdf +++ b/test/worlds/thruster_vel_cmd.sdf @@ -12,11 +12,11 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> @@ -96,7 +96,7 @@ + name="gz::sim::systems::Thruster"> custom propeller_joint 0.005 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 86c82ec066..9748995574 100644 --- a/test/worlds/triball_drift.sdf +++ b/test/worlds/triball_drift.sdf @@ -8,15 +8,15 @@ 1 0 -9.8 + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -845,7 +845,7 @@ + name="gz::sim::systems::WheelSlip"> 0.25 1 diff --git a/test/worlds/triggered_publisher.sdf b/test/worlds/triggered_publisher.sdf index 7c9f21c568..5ec575e6cb 100644 --- a/test/worlds/triggered_publisher.sdf +++ b/test/worlds/triggered_publisher.sdf @@ -5,57 +5,57 @@ 0 - - - + + + - - - + + + data: true - - - + + + data: false - + data: true - - + + data: true - + - - + + data: 0 - + - - + + data: 0 - + - - + + data: -5 @@ -72,27 +72,27 @@ data: -1 - + - - + + 1.0 2.0 - + - - + + 1.0 2.0 - + - - + + { key: "frame_id" @@ -100,10 +100,10 @@ } - + - - + + { data { @@ -117,53 +117,53 @@ } - + - - + + data: 0, data: 1 - + - - + + data: 0.5 - + - - + + 0.5 - + - - + + "value1" - + - - - + + + 1000 - - + + data: 0, data: 1 - + - - + + diff --git a/test/worlds/trisphere_cycle_wheel_slip.sdf b/test/worlds/trisphere_cycle_wheel_slip.sdf index bfab17d87c..d1dded994b 100644 --- a/test/worlds/trisphere_cycle_wheel_slip.sdf +++ b/test/worlds/trisphere_cycle_wheel_slip.sdf @@ -9,15 +9,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -379,7 +379,7 @@ + name="gz::sim::systems::WheelSlip"> 0.15 0 @@ -721,7 +721,7 @@ + name="gz::sim::systems::WheelSlip"> 1 1 diff --git a/test/worlds/velocity_control.sdf b/test/worlds/velocity_control.sdf index 06192f3207..31c966d61b 100644 --- a/test/worlds/velocity_control.sdf +++ b/test/worlds/velocity_control.sdf @@ -1,12 +1,12 @@ @@ -18,15 +18,15 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::UserCommands"> + name="gz::sim::systems::SceneBroadcaster"> @@ -240,7 +240,7 @@ + name="gz::sim::systems::VelocityControl"> caster @@ -416,7 +416,7 @@ + name="gz::sim::systems::VelocityControl"> 0.3 0 0 0 0 -0.1 diff --git a/test/worlds/wide_angle_camera_sensor.sdf b/test/worlds/wide_angle_camera_sensor.sdf index 4e02add3c5..86edb28f26 100644 --- a/test/worlds/wide_angle_camera_sensor.sdf +++ b/test/worlds/wide_angle_camera_sensor.sdf @@ -7,16 +7,16 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::Sensors"> ogre + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/wind_effects.sdf b/test/worlds/wind_effects.sdf index fa2b9c691f..d191f7b4e2 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.md.in b/tutorials.md.in index 74988a1c5c..c4cd60ff55 100644 --- a/tutorials.md.in +++ b/tutorials.md.in @@ -10,7 +10,7 @@ Ignition @IGN_DESIGNATION_CAP@ library and how to use the library effectively. * \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 Ignition Rendering on the server and client. +* \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 Ignition looks for files. @@ -23,7 +23,7 @@ Ignition @IGN_DESIGNATION_CAP@ library and how to use the library effectively. * \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 Ignition Fuel app. +* \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. @@ -43,12 +43,12 @@ Ignition @IGN_DESIGNATION_CAP@ library and how to use the library effectively. **Migration from Gazebo classic** -* \subpage migrationplugins "Plugins": Walk through the differences between writing plugins for Gazebo classic and Ignition Gazebo -* \subpage migrationsdf "SDF": Migrating SDF files from Gazebo classic to Ignition Gazebo -* \subpage migrationworldapi "World API": Guide on what World C++ functions to call in Ignition Gazebo when migrating from Gazebo classic -* \subpage migrationmodelapi "Model API": Guide on what Model C++ functions to call in Ignition Gazebo when migrating from Gazebo classic -* \subpage migrationlinkapi "Link API": Guide on what Link C++ functions to call in Ignition Gazebo when migrating from Gazebo classic -* \subpage ardupilot "Case Study": Migrating the ArduPilot ModelPlugin from Gazebo classic to Ignition Gazebo. +* \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 +* \subpage migrationworldapi "World API": Guide on what World C++ functions to call in Gazebo Sim when migrating from Gazebo classic +* \subpage migrationmodelapi "Model API": Guide on what Model C++ functions to call in Gazebo Sim when migrating from Gazebo classic +* \subpage migrationlinkapi "Link API": Guide on what Link C++ functions to call in Gazebo Sim when migrating from Gazebo classic +* \subpage ardupilot "Case Study": Migrating the ArduPilot ModelPlugin from Gazebo classic to Gazebo. ## License diff --git a/tutorials/battery.md b/tutorials/battery.md index 4b235125c3..2eff476ca8 100644 --- a/tutorials/battery.md +++ b/tutorials/battery.md @@ -19,7 +19,7 @@ model: ... + name="gz::sim::systems::LinearBatteryPlugin"> linear_battery 4.2 @@ -53,8 +53,8 @@ Next, you can find a description of the SDF parameters used: * ``: Power load on battery (W). -* ``: As reported [here](https://github.com/ignitionrobotics/ign-gazebo/issues/225), -there are some issues affecting batteries in Ignition Blueprint and Citadel. +* ``: As reported [here](https://github.com/gazebosim/gz-sim/issues/225), +there are some issues affecting batteries in Gazebo Blueprint and Citadel. This parameter fixes the issues. Feel free to omit the parameter if you have legacy code and want to preserve the old behavior. @@ -102,12 +102,12 @@ it will take a longer time to recharge. battery will also be available via topics. The regular Ignition services will still be available. -By default, two Ignition Transport services are available for managing charging: +By default, two Gazebo 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/blender_sdf_exporter.md b/tutorials/blender_sdf_exporter.md index 0d991d3987..bfe60fdaaa 100644 --- a/tutorials/blender_sdf_exporter.md +++ b/tutorials/blender_sdf_exporter.md @@ -12,7 +12,7 @@ mesh/materials/lights feature set. As such feel free to customize the script as ## Using the Blender SDF Exporter -1. Download the blender script in [sdf_exporter.py](https://github.com/ignitionrobotics/ign-gazebo/tree/ign-gazebo5/examples/scripts/blender/sdf_exporter.py). +1. Download the blender script in [sdf_exporter.py](https://github.com/gazebosim/gz-sim/tree/ign-gazebo5/examples/scripts/blender/sdf_exporter.py). 2. Open the script under Blender's Scripting tab and run it. diff --git a/tutorials/collada_world_exporter.md b/tutorials/collada_world_exporter.md index d193b9e91b..7f9a872e29 100644 --- a/tutorials/collada_world_exporter.md +++ b/tutorials/collada_world_exporter.md @@ -11,7 +11,7 @@ loader. ``` + name="gz::sim::systems::ColladaWorldExporter"> ``` @@ -22,4 +22,4 @@ ign gazebo -v 4 -s -r --iterations 1 WORLD_FILE_NAME 3. A subdirectory, named after the world, has been created in the current working directory. Within this subdirectory is the mesh and materials for the world. -Refer to the [collada_world_exporter.sdf](https://github.com/ignitionrobotics/ign-gazebo/blob/main/examples/worlds/collada_world_exporter.sdf) example. +Refer to the [collada_world_exporter.sdf](https://github.com/gazebosim/gz-sim/blob/main/examples/worlds/collada_world_exporter.sdf) example. diff --git a/tutorials/create_system_plugins.md b/tutorials/create_system_plugins.md index 1a9eeecf07..98f4c8fbe3 100644 --- a/tutorials/create_system_plugins.md +++ b/tutorials/create_system_plugins.md @@ -1,6 +1,6 @@ \page createsystemplugins Create System Plugins -In Ignition Gazebo, all systems are loaded as plugins at runtime. Each system +In Gazebo, all systems are loaded as plugins at runtime. Each system is associated with an entity in simulation. Systems can be attached to the following entity types: @@ -25,19 +25,19 @@ there are currently three additional available interfaces: with the event manager, as well as modifying entities and components. 2. 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/detachable_joints.md b/tutorials/detachable_joints.md index 70a2456b8d..38f2d0d5a3 100644 --- a/tutorials/detachable_joints.md +++ b/tutorials/detachable_joints.md @@ -8,7 +8,7 @@ kinematic topology has to be a tree, i.e., kinematic loops are not currently supported. This affects the choice of the parent link, and therefore, the parent model, which is the model that contains the `DetachableJoint` system. -For example, [detachable_joint.sdf](https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo2/examples/worlds/detachable_joint.sdf) +For example, [detachable_joint.sdf](https://github.com/gazebosim/gz-sim/blob/ign-gazebo2/examples/worlds/detachable_joint.sdf) demonstrates a four wheel vehicle that holds three objects that are later detached from the vehicle. As seen in this example, the parent model is the vehicle. The kinematic topology is the following. diff --git a/tutorials/distributed_simulation.md b/tutorials/distributed_simulation.md index 5395d72fd1..8f3220fcde 100644 --- a/tutorials/distributed_simulation.md +++ b/tutorials/distributed_simulation.md @@ -106,7 +106,7 @@ keeps all performers loaded, but performs no physics simulation. Stepping happens in 2 stages: the primary update and the secondaries update, according to the diagram below: - + 1. The primary publishes a `SimulationStep` message on the `/step` topic, containing: diff --git a/tutorials/entity_creation.md b/tutorials/entity_creation.md index 2078d08c15..0c951d347d 100644 --- a/tutorials/entity_creation.md +++ b/tutorials/entity_creation.md @@ -1,16 +1,16 @@ \page entity_creation Entity creation -This tutorial gives an introduction to Ignition Gazebo's service `/world//create`. +This tutorial gives an introduction to Gazebo Sim's service `/world//create`. This service allows creating entities in the scene such us spheres, lights, etc. -Ignition Gazebo creates many services depending on the plugins that are specified in the SDF. +Gazebo creates many services depending on the plugins that are specified in the SDF. In this case we need to load the `UserCommands` plugin, which will offer the `create` service. You can include the `UserCommands` system plugin including these lines in your SDF: ```xml + name="gz::sim::systems::UserCommands"> ``` @@ -58,16 +58,16 @@ ign service --list # Factory message To create new entities in the world we need to use the -[ignition::msgs::EntityFactory](https://ignitionrobotics.org/api/msgs/6.0/classignition_1_1msgs_1_1EntityFactory__V.html) +[gz::msgs::EntityFactory](https://gazebosim.org/api/msgs/6.0/classignition_1_1msgs_1_1EntityFactory__V.html) message to send a request to the create service. This message allows us to create entities from strings, files, -[Models](https://ignitionrobotics.org/api/msgs/6.0/classignition_1_1msgs_1_1Model.html), -[Lights](https://ignitionrobotics.org/api/msgs/6.0/classignition_1_1msgs_1_1Light.html) or even clone models. +[Models](https://gazebosim.org/api/msgs/6.0/classignition_1_1msgs_1_1Model.html), +[Lights](https://gazebosim.org/api/msgs/6.0/classignition_1_1msgs_1_1Light.html) or even clone models. This tutorial introduces how to create entities from SDF strings and light messages. ## Insert an entity based on a string -We will open an empty Ignition Gazebo world, let's start creating a sphere in the world. +We will open an empty Gazebo world, let's start creating a sphere in the world. In the next snippet you can see how to create models based on strings. \snippet examples/standalone/entity_creation/entity_creation.cc create sphere @@ -91,8 +91,8 @@ There is an option to create a new entity every time that the message is sent by To insert a light in the world we have two options: - - Fill the string inside the `ignition::msgs::EntityFactory` message like in the section above. - - Fill the field `light` inside the `ignition::msgs::EntityFactory` message. + - Fill the string inside the `gz::msgs::EntityFactory` message like in the section above. + - Fill the field `light` inside the `gz::msgs::EntityFactory` message. In the following snippet you can see how the light's field is filled. @@ -103,7 +103,7 @@ Or we can create an SDF string: \snippet examples/standalone/entity_creation/entity_creation.cc create light str Please check the API to know which fields are available in the -[Light message](https://ignitionrobotics.org/api/msgs/6.2/classignition_1_1msgs_1_1Light.html). +[Light message](https://gazebosim.org/api/msgs/6.2/classignition_1_1msgs_1_1Light.html). There are three types of lights: Point, Directional and Spot. Finally we should call the same service `/world//create`: diff --git a/tutorials/erb_template.md b/tutorials/erb_template.md index 1814d024dc..7dd406361e 100644 --- a/tutorials/erb_template.md +++ b/tutorials/erb_template.md @@ -17,7 +17,7 @@ Some of them are listed below and demonstrated in this [example ERB file](https: ## Set up Ruby Firstly, Ruby needs to be installed. -If you have gone through [Ignition's installation guide](https://ignitionrobotics.org/docs/latest/install), it's most likely you already have Ruby installed. +If you have gone through [Gazebo Sim's installation guide](https://gazebosim.org/docs/latest/install), it's most likely you already have Ruby installed. To check if Ruby is installed, use ```{.sh} ruby --version @@ -102,7 +102,7 @@ Each box model also has a different name and pose to ensure they show up as indi %> ``` -[Here](https://github.com/ignitionrobotics/ign-gazebo/blob/main/examples/worlds/shapes_population.sdf.erb) is a complete shapes simulation world example. +[Here](https://github.com/gazebosim/gz-sim/blob/main/examples/worlds/shapes_population.sdf.erb) is a complete shapes simulation world example. Instead of simple shapes, you can also use a nested loop to generate 100 actors spaced out evenly in a simulation world. @@ -160,7 +160,7 @@ erb my_first_erb.erb > my_first_erb.sdf To test if the ERB template works, run the SDF file with the `ign gazebo` command ```{.sh} -# run with Ignition Gazebo +# run with Gazebo ign gazebo my_first_erb.sdf ``` diff --git a/tutorials/gui_config.md b/tutorials/gui_config.md index d7cecc59f4..3e1cf18fe2 100644 --- a/tutorials/gui_config.md +++ b/tutorials/gui_config.md @@ -1,9 +1,9 @@ \page gui_config GUI Configuration -Ignition Gazebo's graphical user interface is powered by -[Ignition GUI](https://ignitionrobotics.org/libs/gui). Therefore, Gazebo's +Gazebo Sim's graphical user interface is powered by +[Gazebo GUI](https://gazebosim.org/libs/gui). Therefore, Gazebo Sim's GUI layout can be defined in -[Ignition GUI configuration files](https://ignitionrobotics.org/api/gui/2.1/config.html). +[Gazebo GUI configuration files](https://gazebosim.org/api/gui/2.1/config.html). These are XML files that describe what plugins to be loaded and with what settings. @@ -13,8 +13,8 @@ There are a few places where the GUI configuration can come from: 1. A file passed to the `--gui-config` command line argument 2. A `` element inside an SDF file -3. The default configuration file at `$HOME/.ignition/gazebo/<#>/gui.config` \*, - where `<#>` is Gazebo's major version. +3. The default configuration file at `$HOME/.gz/sim/<#>/gui.config` \*, + where `<#>` is Gazebo Sim's major version. Each of the items above takes precedence over the ones below it. For example, if a user chooses a `--gui-config`, the SDF's `` element is ignored. And @@ -22,13 +22,13 @@ the default configuration file is only loaded if no configuration is passed through the command line or the SDF file. > \* For log-playback, the default file is -> `$HOME/.ignition/gazebo/<#>/playback_gui.config` +> `$HOME/.gz/sim/<#>/playback_gui.config` ## Try it out ### Default configuration -Let's try this in practice. First, let's open Ignition Gazebo without passing +Let's try this in practice. First, let's open Gazebo without passing any arguments: `ign gazebo` @@ -40,9 +40,9 @@ You should see an empty world with several plugins loaded by default, such as th By default, you're loading this file: -`$HOME/.ignition/gazebo/<#>/gui.config` +`$HOME/.gz/sim/<#>/gui.config` -That file is created the first time you load Ignition Gazebo. Once it is +That file is created the first time you load Gazebo. Once it is created, Ignition will never write to it again unless you delete it. This means that you can customize it with your preferences and they will be applied every time Ignition is started! @@ -51,7 +51,7 @@ Let's try customizing it: 1. Open this file with your favorite editor: - `$HOME/.ignition/gazebo/<#>/gui.config` + `$HOME/.gz/sim/<#>/gui.config` 2. Change `material_theme` from `Light` to `Dark` @@ -68,7 +68,7 @@ provided by Ignition (when you update to a newer version for example). In that case, just delete that file, and the next time Gazebo is started a new file will be created with default values: -`rm $HOME/.ignition/gazebo/<#>/gui.config` +`rm $HOME/.gz/sim/<#>/gui.config` ### SDF @@ -81,7 +81,7 @@ favorite editor and save this file as `fuel_preview.sdf`: + name="gz::sim::systems::SceneBroadcaster"> @@ -169,7 +169,7 @@ hand, we'll create it from the UI. 3. Gazebo should open with your custom layout. **Tip**: From the top-left menu, you can choose "Save client configuration" to -save directly to `$HOME/.ignition/gazebo/<#>/gui.config`. +save directly to `$HOME/.gz/sim/<#>/gui.config`. @image html files/gui_config/cmd_line.png diff --git a/tutorials/headless_rendering.md b/tutorials/headless_rendering.md index 124efa8df0..8db2030f7f 100644 --- a/tutorials/headless_rendering.md +++ b/tutorials/headless_rendering.md @@ -8,7 +8,7 @@ X server requirement on linux systems. This issue can be resolved through installation and proper configuration of X, but the steps can be complex and error prone. -An easier solution is through the use of [EGL](https://www.khronos.org/egl), which allows for the the creation of rendering surfaces without an X server. Ignition Gazebo has added support for EGL via the `--headless-rendering` command line option. Use of EGL is only available with OGRE2. +An easier solution is through the use of [EGL](https://www.khronos.org/egl), which allows for the the creation of rendering surfaces without an X server. Gazebo has added support for EGL via the `--headless-rendering` command line option. Use of EGL is only available with OGRE2. Example usage: @@ -16,7 +16,7 @@ Example usage: ign gazebo -v 4 -s --headless-rendering sensors_demo.sdf ``` -If you are using Ignition Gazebo as a library, then you can configure the +If you are using Gazebo as a library, then you can configure the server to use headless rendering through the `ServerConfig::SetHeadlessRendering(bool)` function. Make sure your SDF world uses OGRE2. @@ -63,7 +63,7 @@ here](https://www.ogre3d.org/2021/02/06/ogre-2-2-5-cerberus-released-and-egl-hea ``` sudo reboot ``` -11. [Install Gazebo](https://ignitionrobotics.org/docs/latest/install). +11. [Install Gazebo](https://gazebosim.org/docs/latest/install). 12. Run a Gazebo world that uses OGRE2 with camera sensors using headless rendering. This will enable EGL. ``` ign gazebo -v 4 -s -r --headless-rendering sensors_demo.sdf diff --git a/tutorials/install.md b/tutorials/install.md index 96de384802..3b5854c50f 100644 --- a/tutorials/install.md +++ b/tutorials/install.md @@ -2,9 +2,9 @@ # Install -These instructions are for installing only Ignition Gazebo. If you're interested +These instructions are for installing only Gazebo. If you're interested in using all the Ignition libraries, not only Igniton Gazebo, check out this -[Ignition installation](https://ignitionrobotics.org/docs/latest/install). +[Ignition installation](https://gazebosim.org/docs/latest/install). We recommend following the binary install instructions to get up and running as quickly and painlessly as possible. @@ -25,7 +25,7 @@ available through a package management utility such as [Apt](https://wiki.debian This approach eliminates the need to download and compile source code, and dependencies are handled for you. The downside of a binary install is that you won't be able to modify the code. See [Source Install](#source-install) for information on -installing Ignition Gazebo from source. +installing Gazebo from source. 1. Configure package repositories. ``` @@ -34,7 +34,7 @@ installing Ignition Gazebo from source. sudo apt-get update ``` -2. Install Ignition Gazebo +2. Install Gazebo ``` sudo apt-get install libignition-gazebo<#>-dev ``` @@ -47,7 +47,7 @@ installing Ignition Gazebo from source. brew tap osrf/simulation ``` -2. Install Ignition Gazebo: +2. Install Gazebo: ``` brew install ignition-gazebo<#> ``` @@ -73,7 +73,7 @@ feature which hasn't been released yet. 3. Clone repository ``` - git clone https://github.com/ignitionrobotics/ign-gazebo -b ign-gazebo<#> + git clone https://github.com/gazebosim/gz-sim -b ign-gazebo<#> ``` 4. Install package dependencies (including other Ignition libraries): @@ -95,7 +95,7 @@ feature which hasn't been released yet. 1. Clone the repository ``` - git clone https://github.com/ignitionrobotics/ign-gazebo -b ign-gazebo<#> + git clone https://github.com/gazebosim/gz-sim -b ign-gazebo<#> ``` 2. Install dependencies @@ -119,7 +119,7 @@ feature which hasn't been released yet. # Documentation -API documentation and tutorials can be accessed at [https://ignitionrobotics.org/libs/gazebo](https://ignitionrobotics.org/libs/gazebo) +API documentation and tutorials can be accessed at [https://gazebosim.org/libs/gazebo](https://gazebosim.org/libs/gazebo) You can also generate the documentation from a clone of this repository by following these steps. @@ -130,7 +130,7 @@ You can also generate the documentation from a clone of this repository by follo 2. Clone the repository ``` - git clone https://github.com/ignitionrobotics/ign-gazebo + git clone https://github.com/gazebosim/gz-sim ``` 3. Configure and build the documentation. diff --git a/tutorials/levels.md b/tutorials/levels.md index c2f62b8667..55e61ae018 100644 --- a/tutorials/levels.md +++ b/tutorials/levels.md @@ -1,6 +1,6 @@ \page levels Levels -This tutorial gives an introduction to Ignition Gazebo's levels feature. +This tutorial gives an introduction to Gazebo Sim's levels feature. This feature allows loading and unloading objects in simulation according to their proximity to the robot, which improves performance in simulations with large environments. @@ -39,11 +39,11 @@ Gazebo ships with an example world that demos the levels feature. Try it as foll 2. Open a new terminal and publish the following commands for the vehicles to drive forward: - `ign topic -t "/model/vehicle_blue/cmd_vel" -m ignition.msgs.Twist -p "linear: {x: 4.0}"` + `ign topic -t "/model/vehicle_blue/cmd_vel" -m gz.msgs.Twist -p "linear: {x: 4.0}"` and - `ign topic -t "/model/vehicle_red/cmd_vel" -m ignition.msgs.Twist -p "linear: {x: 2.0}"` + `ign topic -t "/model/vehicle_red/cmd_vel" -m gz.msgs.Twist -p "linear: {x: 2.0}"` 3. Press play on Gazebo. You'll see that the tunnels will be loaded as the vehicles move forward. @@ -77,7 +77,7 @@ being added and removed. Take a look at the 2D example below. This example focuses on a single performer, but the same logic can be extended to multiple performers. - + * The **green area** represents the area of the world which this simulation is expected to take place in. @@ -115,23 +115,23 @@ Let's take a look at how levels are loaded / unloaded as the performer moves: * `M1` and `M3`, because they belong to the level. * `M6`, because it is global. - + 2. The performer moves south towards `L3` and enters its buffer zone, triggering a load of that level's models, `M4` and `M5`. Note that at this moment, both `L1` and `L3` are loaded. - + 3. The performer moves further south, exiting `L1` and entering `L3`. However, `L1` is still loaded, since `R1` is still within its buffer zone. - + 4. Eventually `R1` moves beyond `L1`'s buffer, triggering an unload of `L1`. The main effect is unloading `M1`. - + ## SDF elements @@ -140,12 +140,12 @@ Two new SDF elements are introduced for distributed simulation: * `` * `` -The concepts of levels and performers are specific to Ignition Gazebo, thus, +The concepts of levels and performers are specific to 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. ### @@ -215,7 +215,7 @@ Example snippet: ### Runtime performers -Performers can be specified at runtime using an Ignition Transport service. +Performers can be specified at runtime using a Gazebo Transport service. This functionality can be used when a performer is not known at load time. For example, you may need to start simulation with an empty world and spawn models (performers) into simulation at a later time. @@ -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 @@ -240,7 +240,7 @@ Here you will see the two vehicles, which are regular models that do not trigger 2. In another terminal call the add performer service for the blue vehicle. ``` -ign service -s /world/levels/level/set_performer --reqtype ignition.msgs.StringMsg --reptype ignition.msgs.Boolean --timeout 2000 --req 'data: "vehicle_blue"' +ign service -s /world/levels/level/set_performer --reqtype gz.msgs.StringMsg --reptype gz.msgs.Boolean --timeout 2000 --req 'data: "vehicle_blue"' ``` ### Example @@ -248,7 +248,7 @@ ign service -s /world/levels/level/set_performer --reqtype ignition.msgs.StringM The following is a world file that could be an instance of the world shown in the figure - + ```xml @@ -298,7 +298,7 @@ the figure - + R1 diff --git a/tutorials/light_config.md b/tutorials/light_config.md index 8a87170faf..d3f2d432bd 100644 --- a/tutorials/light_config.md +++ b/tutorials/light_config.md @@ -1,12 +1,12 @@ \page light_config Light config -This tutorial gives an introduction to Ignition Gazebo's service `/world//light_config`. +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 To modify lights inside the scene we need to use the service `/world//light_config` and -fill the message [`ignition::msgs::Light`](https://ignitionrobotics.org/api/msgs/6.0/classignition_1_1msgs_1_1Light.html). +fill the message [`gz::msgs::Light`](https://gazebosim.org/api/msgs/6.0/classignition_1_1msgs_1_1Light.html). In particular this example modifies the point light that we introduced with the function `createLight()`. \snippet examples/standalone/light_control/light_control.cc create light diff --git a/tutorials/log.md b/tutorials/log.md index 09423fa8a7..eff2dd01a5 100644 --- a/tutorials/log.md +++ b/tutorials/log.md @@ -8,7 +8,7 @@ Ignition records two types of information to files: * Always recorded * Simulation state * Entity poses, insertion and deletion - * Logged to an [Ignition Transport `state.tlog` file](https://ignitionrobotics.org/api/transport/7.0/logging.html) + * Logged to an [Gazebo Transport `state.tlog` file](https://gazebosim.org/api/transport/7.0/logging.html) * Recording must be enabled from the command line or the C++ API * Can be played back using the command line or the C++ API @@ -17,7 +17,7 @@ Ignition records two types of information to files: ### From command line Run the example world with `--record` flag. This records data to a default -path, i.e. `~/.ignition/gazebo/log/`: +path, i.e. `~/.gz/sim/log/`: `ign gazebo -v 4 -r --record pose_publisher.sdf` @@ -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://ignitionrobotics.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"> ... @@ -77,9 +77,9 @@ start during a Gazebo run. The final record path will depend on a few options: * If state recording is not enabled, only the console log is recorded to - `~/.ignition/gazebo/log/`. + `~/.gz/sim/log/`. * If only `--record`, all files are recorded to - `~/.ignition/gazebo/log/`. + `~/.gz/sim/log/`. * If `--record-path` is specified: * If the path doesn't exist, logs are recorded there. * If the path exists: diff --git a/tutorials/logical_audio_sensor.md b/tutorials/logical_audio_sensor.md index 0a1e776e47..08a54b691b 100644 --- a/tutorials/logical_audio_sensor.md +++ b/tutorials/logical_audio_sensor.md @@ -1,6 +1,6 @@ \page logicalaudiosensor Logical Audio Sensor -This tutorial will explain how to use the `LogicalAudioSensor` system plugin in Ignition Gazebo. +This tutorial will explain how to use the `LogicalAudioSensor` system plugin in Gazebo. The logical audio sensor plugin allows for the usage of logical audio sources and microphones in a simulation environment. At the end of each simulation step, microphones check if audio was detected by any of the sources in the world. @@ -8,13 +8,13 @@ The logical audio plugin does not play actual audio to a device like speakers, b ## Setup -Let's take a look at [logical_audio_sensor_plugin.sdf](https://github.com/ignitionrobotics/ign-gazebo/blob/460d2b1cfbf0addf05a1e61c05e1f7a675a83785/examples/worlds/logical_audio_sensor_plugin.sdf), which defines a simulation world with 4 models (in this case, boxes) that have an audio object attached to them. +Let's take a look at [logical_audio_sensor_plugin.sdf](https://github.com/gazebosim/gz-sim/blob/460d2b1cfbf0addf05a1e61c05e1f7a675a83785/examples/worlds/logical_audio_sensor_plugin.sdf), which defines a simulation world with 4 models (in this case, boxes) that have an audio object attached to them. This world attaches logical audio sources to the `red_box` and `blue_box` models, and attaches logical microphones to the `green_box` and `yellow_box` models. Let's take a look at the SDF relevant to the source for `red_box` to understand how to define a logical audio source in SDF: ```xml - + 1 .5 0 0 0 0 0 @@ -30,7 +30,7 @@ Let's take a look at the SDF relevant to the source for `red_box` to understand ``` As we can see, we use a `` tag to define an audio source. -An explanation of all of the tags can be found in the [plugin documentation](https://github.com/ignitionrobotics/ign-gazebo/blob/314477419d2aa946f384204dc99b17d9fcd963b3/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh#L35-L130), but there are a few important things to point out: +An explanation of all of the tags can be found in the [plugin documentation](https://github.com/gazebosim/gz-sim/blob/314477419d2aa946f384204dc99b17d9fcd963b3/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh#L35-L130), but there are a few important things to point out: * `` is used to identify this source when operating on it via services (services will be discussed later). Since a model can have multiple sources and microphones attached to it, each source attached to a particular model must have a unique ID. This means that no other sources attached to `red_box` can have an ID of 1, but sources attached to other models can have an ID of 1 (assuming that other models don't already have a source with an ID of 1 attached to it). @@ -45,7 +45,7 @@ This means that this source will play for an infinite amount of simulation time, Let's now take a look at the SDF relevant to the microphone for `green_box` to understand how to define a logical microphone in SDF: ```xml - + 1 0 .5 0 0 0 0 @@ -55,7 +55,7 @@ Let's now take a look at the SDF relevant to the microphone for `green_box` to u ``` The same rules regarding `` and `` for a logical audio source also apply to a logical microphone. -You can also take a look at the [microphone documentation](https://github.com/ignitionrobotics/ign-gazebo/blob/314477419d2aa946f384204dc99b17d9fcd963b3/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh#L35-L130) for a detailed explanation of the tags embedded in the `` tag. +You can also take a look at the [microphone documentation](https://github.com/gazebosim/gz-sim/blob/314477419d2aa946f384204dc99b17d9fcd963b3/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh#L35-L130) for a detailed explanation of the tags embedded in the `` tag. ## Testing Source and Microphone Behavior @@ -158,7 +158,7 @@ Let's start the source attached to `blue_box`. This can be done by running the following command, which calls the "play" service for the source attached to `blue_box`: ``` -ign service -s /model/blue_box/sensor/source_1/play --reqtype ignition.msgs.Empty --reptype ignition.msgs.Boolean --timeout 1000 --req 'unused: false' +ign service -s /model/blue_box/sensor/source_1/play --reqtype gz.msgs.Empty --reptype gz.msgs.Boolean --timeout 1000 --req 'unused: false' ``` Now, if you look back at the terminal that is displaying the output of `green_box`'s microphone detections, we can see that this microphone is detecting audio from `blue_box`'s source (we see `blue_box` as a part of the `key` field): @@ -187,7 +187,7 @@ Move `blue_box` back towards its original position, until you see detection mess Now, go ahead and stop `blue_box`'s source by running the following command: ``` -ign service -s /model/blue_box/sensor/source_1/stop --reqtype ignition.msgs.Empty --reptype ignition.msgs.Boolean --timeout 1000 --req 'unused: false' +ign service -s /model/blue_box/sensor/source_1/stop --reqtype gz.msgs.Empty --reptype gz.msgs.Boolean --timeout 1000 --req 'unused: false' ``` Now, if you look at the output for either microphone topic, you'll notice that no new messages are being published, which makes sense since no audio sources are currently playing. diff --git a/tutorials/mesh_to_fuel.md b/tutorials/mesh_to_fuel.md index b3667a1353..8d98381985 100644 --- a/tutorials/mesh_to_fuel.md +++ b/tutorials/mesh_to_fuel.md @@ -1,17 +1,17 @@ \page meshtofuel Importing a Mesh to Fuel -This tutorial will explain how to import a mesh to the [Ignition Fuel](https://app.ignitionrobotics.org) web application. -Adding models and/or worlds to Fuel will make your content readily available to the open source robotics simulation community, and easier to use with the Ignition GUI. +This tutorial will explain how to import a mesh to the [Gazebo Fuel](https://app.gazebosim.org) web application. +Adding models and/or worlds to Fuel will make your content readily available to the open source robotics simulation community, and easier to use with the Gazebo GUI. ## Prerequisites To import meshes to Fuel, you need to have a user account. -Go to [app.ignitionrobotics.org](https://app.ignitionrobotics.org) and click Login in the top right corner of the screen, then click Sign Up. +Go to [app.gazebosim.org](https://app.gazebosim.org) and click Login in the top right corner of the screen, then click Sign Up. Once you verify your email address, your account will be ready. You'll need a mesh ready before trying to import to Fuel. There are several ways to acquire a mesh. -To save time, we'll use this [Electrical Box model](https://app.ignitionrobotics.org/openrobotics/fuel/models/Electrical%20Box) that you can download from Fuel. +To save time, we'll use this [Electrical Box model](https://app.gazebosim.org/openrobotics/fuel/models/Electrical%20Box) that you can download from Fuel. ## Model Directory Structure @@ -126,17 +126,17 @@ Click the `Add folders` button, or drag and drop the `Electrical Box` folder you All the files in your model description will be listed there. Press `Upload`, and the "Fuel Model Info" page for your model will open. -![Electrical Box Test](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/mesh_to_fuel/model_info2.png) +![Electrical Box Test](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/mesh_to_fuel/model_info2.png) You can always delete a model by clicking the "Edit model" button and then selecting "Delete model" at the bottom of the page -![Delete model](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/mesh_to_fuel/delete2.png) +![Delete model](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/mesh_to_fuel/delete2.png) ## Include the Model in a World With your mesh successfully uploaded to Fuel, you can now easily include it in a world SDF file. -Copy [this example world code](https://github.com/ignitionrobotics/ign-gazebo/raw/main/examples/worlds/import_mesh.sdf) into a text editor and save it as `import_mesh.sdf`. +Copy [this example world code](https://github.com/gazebosim/gz-sim/raw/main/examples/worlds/import_mesh.sdf) into a text editor and save it as `import_mesh.sdf`. This is a simple world SDF file, which you can learn more about on the [SDF website](http://sdformat.org/). Scroll all the way to the bottom of the file until you see the `include` tag section following the `` comment line. @@ -144,7 +144,7 @@ Scroll all the way to the bottom of the file until you see the `include` tag sec ```xml @@ -182,4 +182,4 @@ To launch the world and see your mesh, run Ignition from inside the directory wh ign gazebo import_mesh.sdf ``` -![Launch sample world with mesh](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/mesh_to_fuel/launch_world2.png) +![Launch sample world with mesh](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/mesh_to_fuel/launch_world2.png) diff --git a/tutorials/migrating_ardupilot_plugin.md b/tutorials/migrating_ardupilot_plugin.md index 9048d9743e..b88f871e17 100644 --- a/tutorials/migrating_ardupilot_plugin.md +++ b/tutorials/migrating_ardupilot_plugin.md @@ -1,9 +1,9 @@ \page ardupilot -# Case study: migrating the ArduPilot ModelPlugin from Gazebo classic to Ignition Gazebo +# Case study: migrating the ArduPilot ModelPlugin from Gazebo classic to Gazebo A variety of changes are required when migrating a plugin from Gazebo classic -to Ignition Gazebo. In this tutorial we offer as a case +to Gazebo. In this tutorial we offer as a case study the migration of one particular `ModelPlugin`, [ardupilot_gazebo](https://github.com/khancyr/ardupilot_gazebo). We hope that this example provides useful tips to others who are migrating their existing @@ -22,7 +22,7 @@ documentation](https://ardupilot.org/dev/docs/using-gazebo-simulator-with-sitl.h As context to understand what we're migrating, here's a system diagram for how the ArduPilot Gazebo plugin works is used: - + *UAV icon credit: By Julian Herzog, CC BY 4.0, https://commons.wikimedia.org/w/index.php?curid=60965475* @@ -69,7 +69,7 @@ library](http://sdformat.org/) is used by both classic and Ignition. But in plac ```cpp // NEW -#include +#include #include ``` @@ -78,17 +78,17 @@ library](http://sdformat.org/) is used by both classic and Ignition. But in plac In the old code, the plugin class `ArduPilotPlugin` is declared in the `gazebo` namespace: ```cpp // OLD -namespace gazebo +namespace sim { ``` -In the new code we declare the class in the `ignition::gazebo::systems` namespace: +In the new code we declare the class in the `gz::sim::systems` namespace: ```cpp // NEW -namespace ignition +namespace gz { -namespace gazebo +namespace sim { namespace systems { @@ -108,11 +108,11 @@ the symbol visibility macro): ```cpp // NEW -class IGNITION_GAZEBO_VISIBLE ArduPilotPlugin: - public ignition::gazebo::System, - public ignition::gazebo::ISystemConfigure, - public ignition::gazebo::ISystemPostUpdate, - public ignition::gazebo::ISystemPreUpdate +class GZ_GAZEBO_VISIBLE ArduPilotPlugin: + public gz::sim::System, + public gz::sim::ISystemConfigure, + public gz::sim::ISystemPostUpdate, + public gz::sim::ISystemPreUpdate ``` With this declaration we're indicating that our plugin will supply implementation of the `Configure()`, `PreUpdate()`, and `PostUpdate()` methods. @@ -130,10 +130,10 @@ In the new code, we use `Configure()` for the same purpose (if a different signa ```cpp // NEW -void Configure(const ignition::gazebo::Entity &_entity, +void Configure(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); ``` Similarly, the old code provides `OnUpdate()`, which is called once per time step while simulation is running: @@ -149,11 +149,11 @@ In the new code, this method is replaced by two methods, `PreUpdate()` and ```cpp // NEW -void PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm); +void PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm); -void PostUpdate(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); +void PostUpdate(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm); ``` As the names suggest, the former is called before each time step, while the @@ -179,9 +179,9 @@ become: ```cpp // NEW void ApplyMotorForces(const double _dt, - ignition::gazebo::EntityComponentManager &_ecm); + gz::sim::EntityComponentManager &_ecm); void SendState(double _simTime, - const ignition::gazebo::EntityComponentManager &_ecm); + const gz::sim::EntityComponentManager &_ecm); bool InitArduPilotSockets(const std::shared_ptr &_sdf); ``` @@ -194,7 +194,7 @@ The old code includes these Gazebo-related headers: ```cpp // OLD #include -#include +#include #include #include #include @@ -209,23 +209,23 @@ ECS pattern used by Ignition) that we're using: ```cpp // NEW -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include ``` To better understand the ECS pattern as it is used in Ignition, it's helpful to learn about the EntityComponentManager (ECM), which is responsible for managing the ECS graph. A great resource to understand the logic under the hood of the ECM is the `SdfEntityCreator` class -([header](https://github.com/ignitionrobotics/ign-gazebo/blob/main/include/ignition/gazebo/SdfEntityCreator.hh), -[source](https://github.com/ignitionrobotics/ign-gazebo/blob/main/src/SdfEntityCreator.cc)). +([header](https://github.com/gazebosim/gz-sim/blob/main/include/ignition/gazebo/SdfEntityCreator.hh), +[source](https://github.com/gazebosim/gz-sim/blob/main/src/SdfEntityCreator.cc)). This class is responsible for mapping the content of an SDF file to the entities and components that form the graph handled by the ECM. For example, if you wonder which components can be accessed by default from the plugin, this @@ -235,18 +235,18 @@ Next we include the parts of `ign-gazebo` itself that we're using: ```cpp // NEW -#include -#include +#include +#include ``` We need a few things from `ign-math`: ```cpp // NEW -#include -#include -#include -#include +#include +#include +#include +#include ``` To use the `IGNITION_ADD_PLUGIN()` and `IGNITION_ADD_PLUGIN_ALIAS()` macros, we @@ -254,14 +254,14 @@ need a header from `ign-plugin`: ```cpp // NEW -#include +#include ``` Because we'll be subscribing to data published by a sensor, we need a header from `ign-transport`: ```cpp // NEW -#include +#include ``` And we keep the SDFormat header: @@ -280,11 +280,11 @@ Now let's get into the class member declarations. The `PID` class has moved from common::PID pid; ``` -to `ignition::math`: +to `gz::math`: ```cpp // NEW -ignition::math::PID pid; +gz::math::PID pid; ``` In the old code we store a `physics::JointPtr` for each propeller joint we're controlling: @@ -294,11 +294,11 @@ In the old code we store a `physics::JointPtr` for each propeller joint we're co physics::JointPtr joint; ``` -In the new code we store an `ignition::gazebo::Entity` instead: +In the new code we store an `gz::sim::Entity` instead: ```cpp // NEW -ignition::gazebo::Entity joint; +gz::sim::Entity joint; ``` In the old code we store an `event::ConnectionPtr` to manage periodic calls to the `OnUpdate()` method: @@ -323,16 +323,16 @@ the model, and the entity underyling one of the links in the model: ```cpp // NEW -ignition::gazebo::Entity entity{ignition::gazebo::kNullEntity}; -ignition::gazebo::Model model{ignition::gazebo::kNullEntity}; -ignition::gazebo::Entity modelLink{ignition::gazebo::kNullEntity}; +gz::sim::Entity entity{gz::sim::kNullEntity}; +gz::sim::Model model{gz::sim::kNullEntity}; +gz::sim::Entity modelLink{gz::sim::kNullEntity}; ``` The old code uses a custom time class: ```cpp // OLD -gazebo::common::Time lastControllerUpdateTime; +sim::common::Time lastControllerUpdateTime; ``` while the new code uses `std::chrono`: @@ -362,8 +362,8 @@ and so on: // NEW std::string imuName; bool imuInitialized; -ignition::transport::Node node; -ignition::msgs::IMU imuMsg; +gz::transport::Node node; +gz::msgs::IMU imuMsg; bool imuMsgValid; std::mutex imuMsgMutex; ``` @@ -374,7 +374,7 @@ message in a mutex-controlled fashion: ```cpp // NEW -void imuCb(const ignition::msgs::IMU &_msg) +void imuCb(const gz::msgs::IMU &_msg) { std::lock_guard lock(this->imuMsgMutex); imuMsg = _msg; @@ -398,10 +398,10 @@ with their Ignition equivalents: ```cpp // NEW -igndbg << ... ; -ignlog << ... ; -ignwarn << ... ; -ignerr << ... ; +gzdbg << ... ; +gzlog << ... ; +gzwarn << ... ; +gzerr << ... ; ``` ### Plugin interface: Configure() @@ -421,7 +421,7 @@ In the new code, we store the entity, model, and name a bit differently: ```cpp // NEW this->dataPtr->entity = _entity; -this->dataPtr->model = ignition::gazebo::Model(_entity); +this->dataPtr->model = gz::sim::Model(_entity); this->dataPtr->modelName = this->dataPtr->model.Name(_ecm); ``` @@ -437,11 +437,11 @@ ensure that the components exist: // NEW if(!_ecm.EntityHasComponentType(this->dataPtr->modelLink, components::WorldPose::typeId)) { - _ecm.CreateComponent(this->dataPtr->modelLink, ignition::gazebo::components::WorldPose()); + _ecm.CreateComponent(this->dataPtr->modelLink, gz::sim::components::WorldPose()); } if(!_ecm.EntityHasComponentType(this->dataPtr->modelLink, components::WorldLinearVelocity::typeId)) { - _ecm.CreateComponent(this->dataPtr->modelLink, ignition::gazebo::components::WorldLinearVelocity()); + _ecm.CreateComponent(this->dataPtr->modelLink, gz::sim::components::WorldLinearVelocity()); } ``` @@ -505,7 +505,7 @@ The old code does the following each time step in its `OnUpdate()` method: ```cpp // OLD -const gazebo::common::Time curTime = +const sim::common::Time curTime = this->dataPtr->model->GetWorld()->SimTime(); if (curTime > this->dataPtr->lastControllerUpdateTime) @@ -560,7 +560,7 @@ this->dataPtr->lastControllerUpdateTime = _info.simTime; Note the differences in both methods with regard to time-handling: (i) the current simulation time is passed in as part of an -`ignition::gazebo::UpdateInfo` object; and (ii) we operate on time values using +`gz::sim::UpdateInfo` object; and (ii) we operate on time values using `std::chrono`. #### One-time initialization in PreUpdate(): subscribing to sensor data @@ -588,13 +588,13 @@ if(!this->dataPtr->imuInitialized) if(imuTopicName.empty()) { - ignerr << "[" << this->dataPtr->modelName << "] " + gzerr << "[" << this->dataPtr->modelName << "] " << "imu_sensor [" << this->dataPtr->imuName << "] not found, abort ArduPilot plugin." << "\n"; return; } - this->dataPtr->node.Subscribe(imuTopicName, &ignition::gazebo::systems::ArduPilotPluginPrivate::imuCb, this->dataPtr.get()); + this->dataPtr->node.Subscribe(imuTopicName, &gz::sim::systems::ArduPilotPluginPrivate::imuCb, this->dataPtr.get()); } ``` @@ -619,11 +619,11 @@ exist): ```cpp // NEW -const double vel = _ecm.ComponentData( +const double vel = _ecm.ComponentData( this->dataPtr->controls[i].joint); // ...do some feedback control math to compute force from vel... _ecm.SetComponentData(this->dataPtr->controls[i].joint, - ignition::gazebo::components::JointForceCmd({force})); + gz::sim::components::JointForceCmd({force})); ``` A similar pattern is used for the case of setting a velocity on a joint; @@ -642,13 +642,13 @@ and copying the result into the packet that we're going to send to ArduPilot: ```cpp // OLD -const ignition::math::Vector3d linearAccel = +const gz::math::Vector3d linearAccel = this->dataPtr->imuSensor->LinearAcceleration(); pkt.imuLinearAccelerationXYZ[0] = linearAccel.X(); pkt.imuLinearAccelerationXYZ[1] = linearAccel.Y(); pkt.imuLinearAccelerationXYZ[2] = linearAccel.Z(); -const ignition::math::Vector3d angularVel = +const gz::math::Vector3d angularVel = this->dataPtr->imuSensor->AngularVelocity(); pkt.imuAngularVelocityRPY[0] = angularVel.X(); pkt.imuAngularVelocityRPY[1] = angularVel.Y(); @@ -664,7 +664,7 @@ message: ```cpp // NEW -ignition::msgs::IMU imuMsg; +gz::msgs::IMU imuMsg; { std::lock_guard lock(this->dataPtr->imuMsgMutex); if(!this->dataPtr->imuMsgValid) @@ -689,11 +689,11 @@ object: ```cpp // OLD -const ignition::math::Pose3d gazeboXYZToModelXForwardZDown = +const gz::math::Pose3d gazeboXYZToModelXForwardZDown = this->modelXYZToAirplaneXForwardZDown + this->dataPtr->model->WorldPose(); -const ignition::math::Vector3d velGazeboWorldFrame = +const gz::math::Vector3d velGazeboWorldFrame = this->dataPtr->model->GetLink()->WorldLinearVel(); ``` @@ -702,15 +702,15 @@ components attached to the entity representing one of the UAV model's links: ```cpp // NEW -const ignition::gazebo::components::WorldPose* pComp = - _ecm.Component(this->dataPtr->modelLink); -const ignition::math::Pose3d gazeboXYZToModelXForwardZDown = +const gz::sim::components::WorldPose* pComp = + _ecm.Component(this->dataPtr->modelLink); +const gz::math::Pose3d gazeboXYZToModelXForwardZDown = this->modelXYZToAirplaneXForwardZDown + pComp->Data(); -const ignition::gazebo::components::WorldLinearVelocity* vComp = - _ecm.Component(this->dataPtr->modelLink); -const ignition::math::Vector3d velGazeboWorldFrame = vComp->Data(); +const gz::sim::components::WorldLinearVelocity* vComp = + _ecm.Component(this->dataPtr->modelLink); +const gz::math::Vector3d velGazeboWorldFrame = vComp->Data(); ``` ### Registering the plugin @@ -726,12 +726,12 @@ In the new code we instead use two macros: `IGNITION_ADD_PLUGIN()` and `IGNITION ```cpp // NEW -IGNITION_ADD_PLUGIN(ignition::gazebo::systems::ArduPilotPlugin, - ignition::gazebo::System, - ignition::gazebo::systems::ArduPilotPlugin::ISystemConfigure, - ignition::gazebo::systems::ArduPilotPlugin::ISystemPostUpdate, - ignition::gazebo::systems::ArduPilotPlugin::ISystemPreUpdate) -IGNITION_ADD_PLUGIN_ALIAS(ignition::gazebo::systems::ArduPilotPlugin,"ArduPilotPlugin") +IGNITION_ADD_PLUGIN(gz::sim::systems::ArduPilotPlugin, + gz::sim::System, + gz::sim::systems::ArduPilotPlugin::ISystemConfigure, + gz::sim::systems::ArduPilotPlugin::ISystemPostUpdate, + gz::sim::systems::ArduPilotPlugin::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS(gz::sim::systems::ArduPilotPlugin,"ArduPilotPlugin") ``` ## Build recipe: `CMakeLists.txt` @@ -831,7 +831,7 @@ In the new model, we do this instead: ```xml rotor_0 @@ -846,25 +846,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 5d290a0f03..60222077e9 100644 --- a/tutorials/migration_link_api.md +++ b/tutorials/migration_link_api.md @@ -2,23 +2,23 @@ # Migration from Gazebo-classic: Link API -When migrating plugins from Gazebo-classic to Ignition Gazebo, developers will +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::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 yet, feel free to -[ticket an issue](https://github.com/ignitionrobotics/ign-gazebo/issues/). +[ticket an issue](https://github.com/gazebosim/gz-sim/issues/). ## Link API -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 @@ -32,16 +32,16 @@ can be divided in these categories: * **Others**: Functions that don't fit any of the categories above * Example: [Link::PlaceOnEntity](http://osrf-distributions.s3.amazonaws.com/gazebo/api/11.0.0/classgazebo_1_1physics_1_1Entity.html#a9ecbfeb56940cacd75f55bed6aa9fcb4) -You'll find the Ignition APIs below on the following headers: +You'll find the Gazebo APIs below on the following headers: -* [ignition/gazebo/Link.hh](https://ignitionrobotics.org/api/gazebo/3.3/Link_8hh.html) -* [ignition/gazebo/Util.hh](https://ignitionrobotics.org/api/gazebo/3.3/Util_8hh.html) -* [ignition/gazebo/SdfEntityCreator.hh](https://ignitionrobotics.org/api/gazebo/3.3/SdfEntityCreator_8hh.html) -* [ignition/gazebo/EntityComponentManager.hh](https://ignitionrobotics.org/api/gazebo/3.3/classignition_1_1gazebo_1_1EntityComponentManager.html) +* [ignition/gazebo/Link.hh](https://gazebosim.org/api/gazebo/3.3/Link_8hh.html) +* [ignition/gazebo/Util.hh](https://gazebosim.org/api/gazebo/3.3/Util_8hh.html) +* [ignition/gazebo/SdfEntityCreator.hh](https://gazebosim.org/api/gazebo/3.3/SdfEntityCreator_8hh.html) +* [ignition/gazebo/EntityComponentManager.hh](https://gazebosim.org/api/gazebo/3.3/classignition_1_1gazebo_1_1EntityComponentManager.html) It's worth remembering that most of this functionality can be performed using the -[EntityComponentManager](https://ignitionrobotics.org/api/gazebo/3.3/classignition_1_1gazebo_1_1EntityComponentManager.html) +[EntityComponentManager](https://gazebosim.org/api/gazebo/3.3/classignition_1_1gazebo_1_1EntityComponentManager.html) directly. The functions presented here exist for convenience and readability. ### 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` -WorldAngularAccel | `ignition::gazebo::Link::WorldAngularAcceleration` +WindMode | `gz::sim::Link::WindMode` +WorldAngularAccel | `gz::sim::Link::WorldAngularAcceleration` 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 e3a4a5337e..d0adb96869 100644 --- a/tutorials/migration_model_api.md +++ b/tutorials/migration_model_api.md @@ -2,23 +2,23 @@ # Migration from Gazebo-classic: Model API -When migrating plugins from Gazebo-classic to Ignition Gazebo, developers will +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::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 yet, feel free to -[ticket an issue](https://github.com/ignitionrobotics/ign-gazebo/issues/). +[ticket an issue](https://github.com/gazebosim/gz-sim/issues/). ## Model API -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 @@ -32,16 +32,16 @@ can be divided in these categories: * **Others**: Functions that don't fit any of the categories above * Example: [Model::PlaceOnEntity](http://osrf-distributions.s3.amazonaws.com/gazebo/api/11.0.0/classgazebo_1_1physics_1_1Entity.html#a9ecbfeb56940cacd75f55bed6aa9fcb4) -You'll find the Ignition APIs below on the following headers: +You'll find the Gazebo APIs below on the following headers: -* [ignition/gazebo/Model.hh](https://ignitionrobotics.org/api/gazebo/3.3/Model_8hh.html) -* [ignition/gazebo/Util.hh](https://ignitionrobotics.org/api/gazebo/3.3/Util_8hh.html) -* [ignition/gazebo/SdfEntityCreator.hh](https://ignitionrobotics.org/api/gazebo/3.3/SdfEntityCreator_8hh.html) -* [ignition/gazebo/EntityComponentManager.hh](https://ignitionrobotics.org/api/gazebo/3.3/classignition_1_1gazebo_1_1EntityComponentManager.html) +* [ignition/gazebo/Model.hh](https://gazebosim.org/api/gazebo/3.3/Model_8hh.html) +* [ignition/gazebo/Util.hh](https://gazebosim.org/api/gazebo/3.3/Util_8hh.html) +* [ignition/gazebo/SdfEntityCreator.hh](https://gazebosim.org/api/gazebo/3.3/SdfEntityCreator_8hh.html) +* [ignition/gazebo/EntityComponentManager.hh](https://gazebosim.org/api/gazebo/3.3/classignition_1_1gazebo_1_1EntityComponentManager.html) It's worth remembering that most of this functionality can be performed using the -[EntityComponentManager](https://ignitionrobotics.org/api/gazebo/3.3/classignition_1_1gazebo_1_1EntityComponentManager.html) +[EntityComponentManager](https://gazebosim.org/api/gazebo/3.3/classignition_1_1gazebo_1_1EntityComponentManager.html) directly. The functions presented here exist for convenience and readability. ### 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..222d6cc3d2 100644 --- a/tutorials/migration_plugins.md +++ b/tutorials/migration_plugins.md @@ -5,18 +5,18 @@ Gazebo Classic supports [6 different C++ plugin types](http://gazebosim.org/tutorials?tut=plugins_hello_world&cat=write_plugin), each providing access to different parts of the API, like physics, rendering, -sensors, GUI, etc. Due to Ignition Gazebo's architecture based on an +sensors, GUI, etc. Due to Gazebo Sim's architecture based on an [ECS](https://en.wikipedia.org/wiki/Entity_component_system) , plugin interfaces are somewhat different, but more varied and in many cases much -more powerful. Some plugins in Ignition are systems within Ignition Gazebo, +more powerful. Some plugins in Ignition are systems within Gazebo, while others are specific plugin types from other Ignition libraries. -\note Plugin types other than systems may be added to Ignition Gazebo in the future. +\note Plugin types other than systems may be added to Gazebo in the future. For example, plugins which get and set properties of simulation entities would be -Ignition Gazebo systems. On the other hand, there are now plugin interfaces which didn't +Gazebo systems. On the other hand, there are now plugin interfaces which didn't exist in Gazebo Classic, such as integrating a new physics or rendering engine, and these can -be also used in projects outside of Ignition Gazebo. +be also used in projects outside of Gazebo. Take a look at the comparison below: @@ -30,7 +30,7 @@ Visual | Get/set properties of the visual and its children | Gazebo system | Get Sensor | Get/set sensor properties and readings | Gazebo system | Get/set components. World / Model | Access physics-engine-specific features | Physics plugin | Loaded by ign-physics Visual | Access rendering-engine-specific features | Rendering plugin | Loaded by ign-rendering -Sensor | Connect to callbacks | Standalone program | Subscribe to Ignition Transport messages. +Sensor | Connect to callbacks | Standalone program | Subscribe to Gazebo Transport messages. All | Connect to simulation events | Gazebo system | Use `PreUpdate`, `Update` and `PostUpdate` callbacks for the update loop, and the event manager for other events. GUI | Add an overlay UI | GUI plugin | Support for overlays and docked widgets GUI / System | Change the default UI | GUI plugin / SDF | All GUI elements can be removed or configured through SDF @@ -97,16 +97,16 @@ class MyPlugin : public ModelPlugin GZ_REGISTER_MODEL_PLUGIN(MyPlugin) ``` -On Ignition Gazebo, that would be implemented as follows: +On 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,14 +230,14 @@ 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: +In summary, the key differences between Gazebo Classic and Gazebo are: * Plugins must inherit from the `ISystemConfigure` class to be able to override the `Configure` callback that gives access to many things, such as the SDF @@ -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 30d3978bff..1d166577ac 100644 --- a/tutorials/migration_sdf.md +++ b/tutorials/migration_sdf.md @@ -2,7 +2,7 @@ # Migration from Gazebo classic: SDF -Both Gazebo classic and Ignition Gazebo support [SDF](http://sdformat.org/) +Both Gazebo classic and Gazebo support [SDF](http://sdformat.org/) files to describe the simulation to be loaded. An SDF file defines the world environment, the robot's characteristics and what plugins to load. @@ -30,10 +30,10 @@ nested models. These are some of the SDF tags that take URIs: Here are the recommended ways to use URIs from most recommended to least: -### Ignition Fuel URL +### Gazebo Fuel URL It's possible to use URLs of resources on -[Ignition Fuel](https://app.ignitionrobotics.org) within any of the tags +[Gazebo Fuel](https://app.gazebosim.org) within any of the tags above and both simulators will be able to load it. For example, this world can be loaded into both simulators: @@ -145,7 +145,7 @@ Each simulator uses a different environment variable: * Gazebo classic: * `GAZEBO_MODEL_PATH` for models * `GAZEBO_RESOURCE_PATH` for worlds and some rendering resources -* Ignition Gazebo: +* Gazebo: * `IGN_GAZEBO_RESOURCE_PATH` for worlds, models and other resources For example, if you have the file structure above, you can set the environment @@ -185,7 +185,7 @@ different directories. ## Plugins Plugins are binary files compiled to use with a specific simulator. Plugins -for Gazebo classic and Ignition Gazebo aren't usually compatible, so plugins +for Gazebo classic and Gazebo aren't usually compatible, so plugins will need to be specified for each simulator separately. It's important to note that for both simulators, plugins compiled against @@ -198,7 +198,7 @@ sure you're loading the correct plugins. Both simulators are installed with several built-in plugins. [Gazebo classic's plugins](https://github.com/osrf/gazebo/tree/gazebo11/plugins) and -[Ignition Gazebo's plugins](https://github.com/ignitionrobotics/ign-gazebo/tree/main/src/systems) +[Gazebo Sim's plugins](https://github.com/gazebosim/gz-sim/tree/main/src/systems) have different file names. For example, to use Gazebo classic's differential drive plugin, the user can refer to it as follows: @@ -215,7 +215,7 @@ On Ignition, that would be: ``` + name="gz::sim::systems::DiffDrive"> ... @@ -235,8 +235,8 @@ where that plugin is located. The variables are different for each simulator: * Gazebo classic: * `GAZEBO_PLUGIN_PATH` for all plugin types. -* Ignition Gazebo: - * `IGN_GAZEBO_SYSTEM_PLUGIN_PATH` for Ignition Gazebo systems (world, model, +* Gazebo: + * `IGN_GAZEBO_SYSTEM_PLUGIN_PATH` for Gazebo systems (world, model, sensor and visual plugins). * `IGN_GUI_PLUGIN_PATH` for GUI plugins. @@ -257,10 +257,10 @@ and [xacro](http://wiki.ros.org/xacro) to generate SDF files with the correct pl ### Default plugins -Ignition Gazebo is more modular than Gazebo classic, so most features are optional. +Gazebo is more modular than Gazebo classic, so most features are optional. For example, by default, Ignition will load all the system plugins defined on -the `~/.ignition/gazebo/<#>/server.config` file and all GUI plugins defined on the -`~/.ignition/gazebo/<#>/gui.config` file. But the user can always remove plugins from +the `~/.gz/sim/<#>/server.config` file and all GUI plugins defined on the +`~/.gz/sim/<#>/gui.config` file. But the user can always remove plugins from those files, or choose different ones by adding `` tags to the SDF file. (For more details, see the [Server configuration tutorial](server_config.html) and the [GUI configuration tutorial](gui_config.html)). @@ -322,8 +322,8 @@ couple alternatives. If using mesh files, the texture can be embedded into it. The advantage is that this works for both simulators. Some examples: -* [OBJ + MTL](https://app.ignitionrobotics.org/OpenRobotics/fuel/models/DeskChair) -* [COLLADA](https://app.ignitionrobotics.org/OpenRobotics/fuel/models/Lamp%20Post) +* [OBJ + MTL](https://app.gazebosim.org/OpenRobotics/fuel/models/DeskChair) +* [COLLADA](https://app.gazebosim.org/OpenRobotics/fuel/models/Lamp%20Post) For primitive shapes or even meshes, you can pass the texture as the albedo map. If you want the model to be compatible with both Classic and Ignition, you can specify both diff --git a/tutorials/migration_world_api.md b/tutorials/migration_world_api.md index f4fdc3b974..e2f2571cd3 100644 --- a/tutorials/migration_world_api.md +++ b/tutorials/migration_world_api.md @@ -2,23 +2,23 @@ # Migration from Gazebo-classic: World API -When migrating plugins from Gazebo-classic to Ignition Gazebo, developers will +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::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 yet, feel free to -[ticket an issue](https://github.com/ignitionrobotics/ign-gazebo/issues/). +[ticket an issue](https://github.com/gazebosim/gz-sim/issues/). ## World API -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 @@ -32,15 +32,15 @@ can be divided in these categories: * **Others**: Functions that don't fit any of the categories above * Example: [World::UniqueModelName](http://osrf-distributions.s3.amazonaws.com/gazebo/api/11.0.0/classgazebo_1_1physics_1_1World.html#a05934164af0cf95eb5a4be70e726846d) -You'll find the Ignition APIs below on the following headers: +You'll find the Gazebo APIs below on the following headers: -* [ignition/gazebo/World.hh](https://ignitionrobotics.org/api/gazebo/3.3/World_8hh.html) -* [ignition/gazebo/Util.hh](https://ignitionrobotics.org/api/gazebo/3.3/Util_8hh.html) -* [ignition/gazebo/SdfEntityCreator.hh](https://ignitionrobotics.org/api/gazebo/3.3/SdfEntityCreator_8hh.html) +* [ignition/gazebo/World.hh](https://gazebosim.org/api/gazebo/3.3/World_8hh.html) +* [ignition/gazebo/Util.hh](https://gazebosim.org/api/gazebo/3.3/Util_8hh.html) +* [ignition/gazebo/SdfEntityCreator.hh](https://gazebosim.org/api/gazebo/3.3/SdfEntityCreator_8hh.html) It's worth remembering that most of this functionality can be performed using the -[EntityComponentManager](https://ignitionrobotics.org/api/gazebo/3.3/classignition_1_1gazebo_1_1EntityComponentManager.html) +[EntityComponentManager](https://gazebosim.org/api/gazebo/3.3/classignition_1_1gazebo_1_1EntityComponentManager.html) directly. The functions presented here exist for convenience and readability. ### 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/model_command.md b/tutorials/model_command.md index 71aba77e71..c2d5c2c06b 100644 --- a/tutorials/model_command.md +++ b/tutorials/model_command.md @@ -1,7 +1,7 @@ \page model_command Model Command ## Overview -`ign model` command allows you to get information about the models for a given running Ignition Gazebo simulation. +`ign model` command allows you to get information about the models for a given running Gazebo simulation. For each model, it is possible to get information about its - Pose: Pose of the model @@ -14,7 +14,7 @@ To try out this command we need first a running simulation. Let's load the `diff ign gazebo diff_drive.sdf -Once Ignition Gazebo is up, we can use the ign model command to get information of the simulation. +Once Gazebo is up, we can use the ign model command to get information of the simulation. Open a new terminal and enter: ign model --list diff --git a/tutorials/model_photo_shoot.md b/tutorials/model_photo_shoot.md index 7a1874e9a5..b6726e50a6 100644 --- a/tutorials/model_photo_shoot.md +++ b/tutorials/model_photo_shoot.md @@ -2,16 +2,16 @@ ## Using the model photo shot plugin -Ignition Gazebo offers a model photo taking tool that will take perspective, +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 -in Ignition Gazebo, located at `examples/worlds/model_photo_shoot.sdf`, by +in Gazebo, located at `examples/worlds/model_photo_shoot.sdf`, by running the following command: ``` ign gazebo -s -r -v 4 --iterations 50 model_photo_shoot.sdf ``` -This will start Ignition Gazebo server, load the model and the plugin, take the +This will start Gazebo server, load the model and the plugin, take the pictures and shutdown after 50 iterations. The pictures can be found at the same location where the command was issued. @@ -25,7 +25,7 @@ contains a good example of the different options and other related plugins: ``` + name="gz::sim::systems::Physics"> ``` @@ -38,7 +38,7 @@ to random positions. ``` + name="gz::sim::systems::Sensors"> ogre2 1, 1, 1 @@ -56,7 +56,7 @@ plugin will also affect the final resulting background color on the images. https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Robonaut + name="gz::sim::systems::ModelPhotoShoot"> poses.txt true diff --git a/tutorials/particle_tutorial.md b/tutorials/particle_tutorial.md index dc6ab9f28e..aed7b80616 100644 --- a/tutorials/particle_tutorial.md +++ b/tutorials/particle_tutorial.md @@ -1,22 +1,22 @@ \page particle_emitter Particle Emitter -This tutorial shows how to use the particle emitter system to add and configure particle effects like smoke and fog in simulation. It also shows the effects that particles have on different types of sensors in Ignition Gazebo. +This tutorial shows how to use the particle emitter system to add and configure particle effects like smoke and fog in simulation. It also shows the effects that particles have on different types of sensors in Gazebo. ## Particle Emitter System We will demonstrate the particle emitter system by using the [examples/worlds/particle_emitter.sdf]( -https://github.com/ignitionrobotics/ign-gazebo/blob/main/examples/worlds/particle_emitter.sdf) world. +https://github.com/gazebosim/gz-sim/blob/main/examples/worlds/particle_emitter.sdf) world. To be able to spawn particle emitters, first you will need to include the particle emitter system as a plugin to the world in your SDF. The system does not take any arguments. ```xml + name="gz::sim::systems::ParticleEmitter"> ``` -Next, we can start adding particle emitter models into the world. In our example world, we include a [Fog Generator](https://app.ignitionrobotics.org/OpenRobotics/fuel/models/Fog%20Generator) model from Ignition Fuel: +Next, we can start adding particle emitter models into the world. In our example world, we include a [Fog Generator](https://app.gazebosim.org/OpenRobotics/fuel/models/Fog%20Generator) model from Gazebo Fuel: ```xml @@ -55,7 +55,7 @@ Here is the content of the Fog Generator [model.sdf](https://fuel.ignitionroboti ``` -The SDF 1.6+ specification supports having a `` SDF element as a child of ``. The particle emitter itself has several properties that can be configured, see Ignition Rendering's [particles tutorial](https://ignitionrobotics.org/api/rendering/4.0/particles.html) for more details on these properties. In our Fog Generator model, we are using a box type particle emitter that covers a region size of 10 by 10m. By default, the particles are emitted in the `+x` direction, hence the model as a pitch rotation of -90 degrees to rotate the particle emitter so that the particles are emitted upwards in `+z`. +The SDF 1.6+ specification supports having a `` SDF element as a child of ``. The particle emitter itself has several properties that can be configured, see Gazebo Rendering's [particles tutorial](https://gazebosim.org/api/rendering/4.0/particles.html) for more details on these properties. In our Fog Generator model, we are using a box type particle emitter that covers a region size of 10 by 10m. By default, the particles are emitted in the `+x` direction, hence the model as a pitch rotation of -90 degrees to rotate the particle emitter so that the particles are emitted upwards in `+z`. Let's launch the example world to see what it looks like. @@ -67,10 +67,10 @@ You should see the fog slowly starting to appear from the ground plane in the wo @image html files/particle_emitter/fog_generator.png -Next, try changing some properties of the particle emitter while the simulation is running. You can do this by publishing messages over Ignition Transport. Try turning off the particle emitter by setting the `emitting` property to `false`. Make sure the simulation is running in order for this command to take effect. +Next, try changing some properties of the particle emitter while the simulation is running. You can do this by publishing messages over Gazebo Transport. Try turning off the particle emitter by setting the `emitting` property to `false`. Make sure the simulation is running in order for this command to take effect. ```bash -ign topic -t /model/fog_generator/link/fog_link/particle_emitter/emitter/cmd -m ignition.msgs.ParticleEmitter -p 'emitting: {data: false}' +ign topic -t /model/fog_generator/link/fog_link/particle_emitter/emitter/cmd -m gz.msgs.ParticleEmitter -p 'emitting: {data: false}' ``` Note the above command tells the particle emitter to stop emitting. It does not make all the particles disappear immediately. The particles that have already been emitted will naturally fade and disappear over the specified `lifetime`. @@ -78,13 +78,13 @@ Note the above command tells the particle emitter to stop emitting. It does not Turn particle emitter back on by setting the `emitting` property to `true`: ```bash -ign topic -t /model/fog_generator/link/fog_link/particle_emitter/emitter/cmd -m ignition.msgs.ParticleEmitter -p 'emitting: {data: true}' +ign topic -t /model/fog_generator/link/fog_link/particle_emitter/emitter/cmd -m gz.msgs.ParticleEmitter -p 'emitting: {data: true}' ``` Here is an example command for changing the `rate` property of the particle emitter. This should make the particle emitter emit more particles per second, causing it to visually appear more dense. ```bash -ign topic -t /model/fog_generator/link/fog_link/particle_emitter/emitter/cmd -m ignition.msgs.ParticleEmitter -p 'rate: {data: 100}' +ign topic -t /model/fog_generator/link/fog_link/particle_emitter/emitter/cmd -m gz.msgs.ParticleEmitter -p 'rate: {data: 100}' ``` ## Particle Effects on Sensors diff --git a/tutorials/physics.md b/tutorials/physics.md index 4ff2a32097..bd7bfd4491 100644 --- a/tutorials/physics.md +++ b/tutorials/physics.md @@ -1,22 +1,22 @@ \page physics Physics engines -Ignition Gazebo supports choosing what physics engine to use at runtime. +Gazebo supports choosing what physics engine to use at runtime. This is made possible by -[Ignition Physics](https://ignitionrobotics.org/libs/physics)' abstraction +[Gazebo Physics](https://gazebosim.org/libs/physics)' abstraction layer. -Ignition Gazebo uses the [DART](https://dartsim.github.io/) physics engine +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://ignitionrobotics.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 -Ignition Gazebo automatically looks for all physics engine plugins that are -installed with Ignition Physics. At the moment, that's only DART +Gazebo automatically looks for all physics engine plugins that are +installed with Gazebo Physics. At the moment, that's only DART (`ignition-physics-dartsim-plugin`). If you've created a custom engine plugin, you can tell Gazebo where to find it @@ -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://ignitionrobotics.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); ``` ## Engine configuration @@ -101,9 +101,9 @@ may support them. The default physics engine, DART, supports all these options. > Failed to find plugin [libCustomEngine.so]. Have you checked the > IGN_GAZEBO_PHYSICS_ENGINE_PATH environment variable? -Ignition Gazebo can't find out where `libCustomEngine.so` is located. +Gazebo can't find out where `libCustomEngine.so` is located. -If that's an engine you believe should be installed with Ignition Physics, +If that's an engine you believe should be installed with Gazebo Physics, check if the relevant plugin is installed. If that's a 3rd party engine, find where the `.so` file is installed and add @@ -118,7 +118,7 @@ permissions to access it, and that it's acually a physics engine plugin. > [/home/physics_engines/libCustomEngine.so] This means that there are plugins on that library, but none of them satisfies -the minimum requirement of features needed to run an Ignition Gazebo simulation. +the minimum requirement of features needed to run a Gazebo simulation. Be sure to implement all the necessary features. > Failed to load a valid physics engine from diff --git a/tutorials/point_cloud_to_mesh.md b/tutorials/point_cloud_to_mesh.md index cd7fff694b..91af03aec4 100644 --- a/tutorials/point_cloud_to_mesh.md +++ b/tutorials/point_cloud_to_mesh.md @@ -20,7 +20,7 @@ After installing, open CloudCompare and import your point cloud file by going to Depending on the number of points in your point cloud, this could take several minutes. Once loaded, you should see the following tunnel section: -![Opening the point cloud](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/cloudcompare2.png) +![Opening the point cloud](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/cloudcompare2.png) Many 3D scans will be composed of millions, sometimes hundreds of millions of points. Converting a scan to a 3D model with that many points would be very difficult due to the number of polygons that would be created and the long processing time necessary to compute the normals. @@ -34,13 +34,13 @@ We'll still walk through reducing points, however, to make the process quicker. To reduce the number of points in your cloud, click on the tunnel so a yellow cube outline appears around it, then go to `Edit` > `Subsample`. -![Min. space between points](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/min_space.png) +![Min. space between points](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/min_space.png) The number you will need to enter in the `min. space between points` field will vary depending on your point cloud. A value of .01 was sufficient to bring our point cloud to an easy-to-manage 1 million points. Point count is visible in the `Properties` window on the lower left side of the screen. -![Point count of subsample](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/properties.png) +![Point count of subsample](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/properties.png) How many points you reduce down to will largely depend on how long you are willing to wait for the point cloud to be converted into a mesh. The more points you start with, the longer it will take to compute the normals and create the mesh. @@ -48,7 +48,7 @@ The more points you start with, the longer it will take to compute the normals a After the operation is complete you’ll have two clouds in your scene: the original point cloud and your subsampled point cloud. Most operations in CloudCompare will create new point clouds and keep the original, so make sure that you have the new point cloud selected before running an operation. -![Selecting the new point cloud](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/secondcloud.png) +![Selecting the new point cloud](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/secondcloud.png) ### Create a Polygonal Mesh @@ -59,7 +59,7 @@ A normal is essentially the direction a polygon is facing. To do this, go to `Edit` > `Normals` > `Compute`. You'll see this dialog box: -![Choose Triangulation surface model](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/compute_normals.png) +![Choose Triangulation surface model](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/compute_normals.png) You’ll see various options in the dialog box that appears. The main thing you’ll want to consider is what `Local surface model` to use. @@ -72,7 +72,7 @@ Now we get to actually convert our point cloud to a mesh. To do this go to `Plugins` > `PoissonRecon`. You'll see this dialog box: -![Octree depth and output density selection](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/outputdensity.png) +![Octree depth and output density selection](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/outputdensity.png) The value you enter in the `Octree depth` field will determine the polygon count of the created model. You may have to run the surface reconstruction a couple times with varying values before you land on a polygon count that is suitable for your needs. @@ -93,18 +93,18 @@ Our tunnel has turned into a blob shape. This is because the mesh that CloudCompare creates will always be water tight even if it has to add polygons where there are no points. We just want our tunnels, though, so we need to remove those unnecessary polygons. -![The blob shape](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/blob2.png) +![The blob shape](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/blob2.png) This is where our scalar field comes in. In the mesh's `Properties` window go to `SF display params` and take the left handle in the graph and drag it to the right until it hits the area where the bulk of the scalar field starts. -![Adjusting scalar filed params](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/sf_display.png) +![Adjusting scalar filed params](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/sf_display.png) This will display only the polygons that were created from the point cloud and hide the polygons used to make the model watertight. The polygons are only hidden however. We still need to actually remove them. -![Display original polygons](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/hidden_polygons2.png) +![Display original polygons](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/hidden_polygons2.png) To remove the hidden polygons go to `Edit` > `Scalar fields` > `Filter By Value`. @@ -113,7 +113,7 @@ Hitting export will simply export the mesh within that range. Instead, we'll hit `Split` to create two meshes. One with the polygons inside our specified range and one containing polygons outside that range. -![Splitting the mesh](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/split.png) +![Splitting the mesh](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/split.png) ### The Completed Model @@ -121,6 +121,6 @@ By hitting `Split` we can view the model before exporting by simply going to `Fi Remember to have the correct mesh selected (`.part`) since choosing `Split` will give you two new meshes, plus you will still have your original, complete mesh. Your file format will depend on the software you want to use but `.obj` is a widely supported format that should work in most 3D applications. -![The completed mesh](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/complete2.png) +![The completed mesh](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/complete2.png) You can find more information on CloudCompare and a more in depth look at the tools we used in this tutorial on [the CloudCompare website](https://www.cloudcompare.org/) and the [CloudCompare wiki](https://www.cloudcompare.org/doc/wiki/index.php?title=Main_Page). diff --git a/tutorials/python_interfaces.md b/tutorials/python_interfaces.md index f5620e147d..e046a12e39 100644 --- a/tutorials/python_interfaces.md +++ b/tutorials/python_interfaces.md @@ -2,7 +2,7 @@ # Overview -Ignition Gazebo provides a Python API to interact with world. +Gazebo provides a Python API to interact with world. For now, we provide a `TestFixture` class that allows to load a world file, step simulation and check entities and components. @@ -45,10 +45,10 @@ while(server.is_running()): # Run the example In the -[examples/scripts/python_api](https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo7/examples/scripts/python_api) +[examples/scripts/python_api](https://github.com/gazebosim/gz-sim/blob/ign-gazebo7/examples/scripts/python_api) folder there is a Python script that shows how to make use of this API. -If you compiled Ignition Gazebo from source you should modify your `PYTHONPATH`: +If you compiled Gazebo from source you should modify your `PYTHONPATH`: ```bash export PYTHONPATH=$PYTHONPATH:/install/lib/python @@ -59,8 +59,8 @@ Now you can run the example: ```bash $ python3 examples/scripts/python_api/testFixture.py [Msg] Loading SDF world file[/home/ahcorde/ignition_fortress/src/ign-gazebo/examples/scripts/python_api/gravity.sdf]. -[Dbg] [Physics.cc:789] Loaded [ignition::physics::dartsim::Plugin] from library [/home/ahcorde/ignition_fortress/install/lib/ign-physics-5/engine-plugins/libignition-physics-dartsim-plugin.so] -[Dbg] [SimulationRunner.cc:909] Loaded system [ignition::gazebo::systems::Physics] for entity [1] +[Dbg] [Physics.cc:789] Loaded [gz::physics::dartsim::Plugin] from library [/home/ahcorde/ignition_fortress/install/lib/ign-physics-5/engine-plugins/libignition-physics-dartsim-plugin.so] +[Dbg] [SimulationRunner.cc:909] Loaded system [gz::sim::systems::Physics] for entity [1] [Msg] Loaded level [3] [Msg] Serving world controls on [/world/gravity/control], [/world/gravity/control/state] and [/world/gravity/playback/control] [Msg] Serving GUI information on [/world/gravity/gui/info] diff --git a/tutorials/rendering_plugins.md b/tutorials/rendering_plugins.md index 1a9de801a7..b50a761abe 100644 --- a/tutorials/rendering_plugins.md +++ b/tutorials/rendering_plugins.md @@ -1,36 +1,36 @@ \page rendering_plugins Rendering plugins -This tutorial will go over how to write Ignition Gazebo plugins that alter the -3D scene's visual appearance using Ignition Rendering APIs. +This tutorial will go over how to write Gazebo plugins that alter the +3D scene's visual appearance using Gazebo Rendering APIs. This is not to be confused with integrating a new rendering engine. See -[How to write your own rendering engine plugin](https://ignitionrobotics.org/api/rendering/4.2/renderingplugin.html) +[How to write your own rendering engine plugin](https://gazebosim.org/api/rendering/4.2/renderingplugin.html) for that. This tutorial will go over a couple of example plugins that are located at -https://github.com/ignitionrobotics/ign-gazebo/tree/main/examples/plugin/rendering_plugins. +https://github.com/gazebosim/gz-sim/tree/main/examples/plugin/rendering_plugins. ## Scenes 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. +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 +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 -changes done to these scenes using Ignition Rendering APIs directly, as +the `gz::sim::systems::SceneBroadcaster` plugin. Any +changes done to these scenes using Gazebo 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 each scene separately. @@ -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://ignitionrobotics.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/ignitionrobotics/ign-gazebo/tree/main/examples/plugin/gui_system_plugin). +See the [GUI system plugin example](https://github.com/gazebosim/gz-sim/tree/main/examples/plugin/gui_system_plugin). ## Getting the scene -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://ignitionrobotics.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: @@ -123,7 +123,7 @@ Here's how to do it: ## Running examples Follow the build instructions on the rendering plugins -[README](https://github.com/ignitionrobotics/ign-gazebo/blob/main/examples/plugin/rendering_plugins) +[README](https://github.com/gazebosim/gz-sim/blob/main/examples/plugin/rendering_plugins) and you'll generate both plugins: * `RenderingGuiPlugin`: GUI plugin that updates the GUI scene's ambient light with a random color at each click. diff --git a/tutorials/resources.md b/tutorials/resources.md index 430f1f4216..80a6155bba 100644 --- a/tutorials/resources.md +++ b/tutorials/resources.md @@ -2,14 +2,14 @@ Setting up and running a simulation can involve loading various kinds of resources, such as robot models and plugins, from different locations, which -can include a local filesystem and online servers. Ignition Gazebo offers +can include a local filesystem and online servers. Gazebo offers a few different mechanisms for locating required resources. ## Plugins A plugin is a shared library that adheres to a specific API and is loaded at runtime. Typically, plugins are scoped to perform a narrow set of features. -For example, the `diff_drive` plugin, provided by Ignition Gazebo, implements +For example, the `diff_drive` plugin, provided by Gazebo, implements a differential drive controller for mobile robots. Ignition relies on plugins for rendering, physics simulation, sensor data @@ -18,7 +18,7 @@ how Ignition finds and loads different types of plugins. ### System Plugins -A system plugin is used by Ignition Gazebo, and provides an entry point for +A system plugin is used by Gazebo, and provides an entry point for simulation customization and control. Refer to the \subpage createsystemplugins tutorial for information about creating your own system plugin. @@ -31,27 +31,27 @@ System plugins may be loaded through: * Attached to a **model**: `` * Attached to a **sensor**: `` * Passing the shared library and class to be loaded through - [PluginInfo](https://ignitionrobotics.org/api/gazebo/4.6/classignition_1_1gazebo_1_1ServerConfig_1_1PluginInfo.html) - (within [ServerConfig](https://ignitionrobotics.org/api/gazebo/4.6/classignition_1_1gazebo_1_1ServerConfig.html)) + [PluginInfo](https://gazebosim.org/api/gazebo/4.6/classignition_1_1gazebo_1_1ServerConfig_1_1PluginInfo.html) + (within [ServerConfig](https://gazebosim.org/api/gazebo/4.6/classignition_1_1gazebo_1_1ServerConfig.html)) when instantiating the - [Server](https://ignitionrobotics.org/api/gazebo/4.6/classignition_1_1gazebo_1_1Server.html#a084ef7616f5af42061a7aeded5651ab0). + [Server](https://gazebosim.org/api/gazebo/4.6/classignition_1_1gazebo_1_1Server.html#a084ef7616f5af42061a7aeded5651ab0). 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://ignitionrobotics.org/api/gazebo/4.6/namespaceignition_1_1gazebo_1_1systems.html) +2. `$HOME/.gz/sim/plugins` +3. [Systems that are installed with Gazebo](https://gazebosim.org/api/gazebo/4.6/namespace gz_1_1gazebo_1_1systems.html) -### Ignition GUI plugins +### Gazebo GUI plugins -Each [Ignition GUI](https://ignitionrobotics.org/libs/rendering) plugin +Each [Gazebo GUI](https://gazebosim.org/libs/rendering) plugin defines a widget. GUI plugins may be loaded through: * Tags in SDF world files, where `filename` is the shared library: * `` -* Tags in [GUI config files](https://ignitionrobotics.org/api/gui/4.2/config.html), +* Tags in [GUI config files](https://gazebosim.org/api/gui/4.2/config.html), where `filename` is the shared library: * `` * The plugin menu on the top-right of the screen. @@ -59,29 +59,29 @@ GUI plugins may be loaded through: Ignition will look for GUI plugins on the following paths, in order: 1. All paths set on the `IGN_GUI_PLUGIN_PATH` environment variable -2. [GUI plugins that are installed with Ignition Gazebo](https://github.com/ignitionrobotics/ign-gazebo/tree/main/src/gui/plugins) -3. Other paths added by calling `ignition::gui::App()->AddPluginPath` -4. `~/.ignition/gui/plugins` -5. [Plugins which are installed with Ignition GUI](https://ignitionrobotics.org/api/gui/4.2/namespaceignition_1_1gui_1_1plugins.html) +2. [GUI plugins that are installed with Gazebo](https://github.com/gazebosim/gz-sim/tree/main/src/gui/plugins) +3. Other paths added by calling `gz::gui::App()->AddPluginPath` +4. `~/.gz/gui/plugins` +5. [Plugins which are installed with Gazebo GUI](https://gazebosim.org/api/gui/4.2/namespace gz_1_1gui_1_1plugins.html) ### Physics engines -[Ignition Physics](https://ignitionrobotics.org/libs/physics) +[Gazebo Physics](https://gazebosim.org/libs/physics) uses a plugin architecture and its physics engines are built as plugins that are loaded at run time using -[Ignition Plugin](https://ignitionrobotics.org/libs/plugin). +[Gazebo Plugin](https://gazebosim.org/libs/plugin). See the [Physics engines](physics.html) tutorial for more details. ### Rendering engines -[Ignition Rendering](https://ignitionrobotics.org/libs/rendering) +[Gazebo Rendering](https://gazebosim.org/libs/rendering) uses a plugin architecture and its render engines are built as plugins that are loaded at run time using -[Ignition Plugin](https://ignitionrobotics.org/libs/plugin). +[Gazebo Plugin](https://gazebosim.org/libs/plugin). -At the moment, Ignition Rendering will only look for render engine plugin +At the moment, Gazebo Rendering will only look for render engine plugin shared libraries installed within its `/lib` directory. Likewise, the resources used by these engines are located in Ignition Rendering's `/share` directory. @@ -89,12 +89,12 @@ Rendering's `/share` directory. ### Sensors Each unique type of sensor in -[Ignition Sensors](https://ignitionrobotics.org/libs/sensors) is a plugin. When +[Gazebo Sensors](https://gazebosim.org/libs/sensors) is a plugin. When a particular sensor type is requested, the relevant plugin is loaded by -[Ignition Plugin](https://ignitionrobotics.org/libs/plugin) and a +[Gazebo Plugin](https://gazebosim.org/libs/plugin) and a sensor object is instantiated from it. -At the moment, Ignition Sensors will only look for sensor plugin +At the moment, Gazebo Sensors will only look for sensor plugin shared libraries installed within its `/lib` directory. ## Models, lights, actors @@ -109,9 +109,9 @@ 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://ignitionrobotics.org/api/gazebo/4.6/classignition_1_1gazebo_1_1SdfEntityCreator.html) + [SdfEntityCreator](https://gazebosim.org/api/gazebo/4.6/classignition_1_1gazebo_1_1SdfEntityCreator.html) or directly creating components and entities. Ignition will look for URIs (path / URL) in the following, in order: @@ -119,12 +119,12 @@ Ignition will look for URIs (path / URL) in the following, in order: 1. All paths on the `IGN_GAZEBO_RESOURCE_PATH`\* environment variable (if path is URI, scheme is stripped) 2. Current running path / absolute path -3. [Ignition Fuel](https://app.ignitionrobotics.org/fuel/models) +3. [Gazebo Fuel](https://app.gazebosim.org/fuel/models) 1. Cache (i.e. `$HOME/.ignition/fuel`) 2. Web server \* The `SDF_PATH` environment variable also works in some scenarios, but - it's not recommended when using Ignition Gazebo. + it's not recommended when using Gazebo. ## Meshes @@ -142,17 +142,17 @@ Ignition will look for URIs (path / URL) in the following, in order: is URI, scheme is stripped) \* The `IGN_FILE_PATH` environment variable also works in some scenarios, but - it's not recommended when using Ignition Gazebo. + it's not recommended when using Gazebo. ### GUI configuration -Ignition Gazebo's -[GUI configuration](https://ignitionrobotics.org/api/gui/4.2/config.html) +Gazebo Sim's +[GUI configuration](https://gazebosim.org/api/gui/4.2/config.html) can come from the following, in order: 1. The command line option `--gui-config ` 2. Plugins within SDF's `` -3. `$HOME/.ignition/gazebo/<#>/gui.config` (if that file doesn't -exist, the default `gui.config` file that is installed with Ignition Gazebo +3. `$HOME/.gz/sim/<#>/gui.config` (if that file doesn't +exist, the default `gui.config` file that is installed with Gazebo will be copied to that location) diff --git a/tutorials/server_config.md b/tutorials/server_config.md index a9a27830f1..0fa315fa12 100644 --- a/tutorials/server_config.md +++ b/tutorials/server_config.md @@ -1,6 +1,6 @@ \page server_config Server Configuration -Most functionality on Ignition Gazebo is provided by plugins, which means that +Most functionality on Gazebo is provided by plugins, which means that users can choose exactly what functionality is available to their simulations. Even running the physics engine is optional. This gives users great control and makes sure only what's crucial for a given simulation is loaded. @@ -14,8 +14,8 @@ There are a few places where the plugins can be defined: 1. `` elements inside an SDF file. 2. File path defined by the `IGN_GAZEBO_SERVER_CONFIG_PATH` environment variable. -3. The default configuration file at `$HOME/.ignition/gazebo/<#>/server.config` \*, - where `<#>` is Gazebo's major version. +3. The default configuration file at `$HOME/.gz/sim/<#>/server.config` \*, + where `<#>` is Gazebo Sim's major version. Each of the items above takes precedence over the ones below it. For example, if a the SDF file has any `` elements, then the @@ -24,13 +24,13 @@ file is only loaded if no plugins are passed through the SDF file or the environment variable. > \* For log-playback, the default file is -> `$HOME/.ignition/gazebo/<#>/playback_server.config` +> `$HOME/.gz/sim/<#>/playback_server.config` ## Try it out ### Default configuration -Let's try this in practice. First, let's open Ignition Gazebo without passing +Let's try this in practice. First, let's open Gazebo without passing any arguments: `ign gazebo` @@ -49,9 +49,9 @@ broadcaster is loaded. By default, you're loading this file: -`$HOME/.ignition/gazebo/<#>/server.config` +`$HOME/.gz/sim/<#>/server.config` -That file is created the first time you load Ignition Gazebo. Once it is +That file is created the first time you load Gazebo. Once it is created, Ignition will never write to it again unless you delete it. This means that you can customize it with your preferences and they will be applied every time Ignition is started! @@ -60,7 +60,7 @@ Let's try customizing it: 1. Open this file with your favorite editor: - `$HOME/.ignition/gazebo/<#>/server.config` + `$HOME/.gz/sim/<#>/server.config` 2. Remove the `` block for the physics system @@ -78,7 +78,7 @@ provided by Ignition (when you update to a newer version for example). In that case, just delete that file, and the next time Gazebo is started a new file will be created with default values: -`rm $HOME/.ignition/gazebo/<#>/server.config` +`rm $HOME/.gz/sim/<#>/server.config` ### SDF @@ -91,7 +91,7 @@ favorite editor and save this file as `fuel_preview.sdf`: + name="gz::sim::systems::SceneBroadcaster"> @@ -231,7 +231,7 @@ rendering-based sensors to generate data. @image html files/server_config/camera_no_env.gif Now let's create a custom configuration file in -`$HOME/.ignition/gazebo/rendering_sensors_server.config` that has the sensors +`$HOME/.gz/sim/rendering_sensors_server.config` that has the sensors system: ``` @@ -240,12 +240,12 @@ system: + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::Sensors"> ogre @@ -254,7 +254,7 @@ system: And point the environment variable to that file: -`export IGN_GAZEBO_SERVER_CONFIG_PATH=$HOME/.ignition/gazebo/rendering_sensors_server.config` +`export IGN_GAZEBO_SERVER_CONFIG_PATH=$HOME/.gz/sim/rendering_sensors_server.config` Now when we launch the simulation again, refreshing the image display will show the camera topic, and we can see the camera data. diff --git a/tutorials/spherical_coordinates.md b/tutorials/spherical_coordinates.md index c5f1f283c6..b08b3b178f 100644 --- a/tutorials/spherical_coordinates.md +++ b/tutorials/spherical_coordinates.md @@ -5,7 +5,7 @@ simulations using the [WGS84](https://en.wikipedia.org/wiki/World_Geodetic_System#1984_version) geodetic system. -Gazebo's simulation is always performed in Cartesian coordinates (good old XYZ). +Gazebo Sim's simulation is always performed in Cartesian coordinates (good old XYZ). Therefore, in order to use spherical coordinates, it's necessary to project coordinates expressed in the `WGS84` frame to Cartesian and back. @@ -27,7 +27,7 @@ ENU (East-North-Up) convention, as shown on the image below: Users can define where the origin of the ENU coordinates sits on the surface of the planet in three different ways: through the SDF file, the GUI, or through -an Ignition Transport service call. +a Gazebo Transport service call. Changing the world origin will only affect operations performed afterwards. For example, models already in the world will not be moved when the world origin's @@ -83,8 +83,8 @@ Loading the world above, try calling for example: ```.bash ign service \ -s /world/spherical_coordinates/set_spherical_coordinates \ ---reqtype ignition.msgs.SphericalCoordinates \ ---reptype ignition.msgs.Boolean \ +--reqtype gz.msgs.SphericalCoordinates \ +--reptype gz.msgs.Boolean \ --timeout 2000 \ --req "surface_model: EARTH_WGS84, latitude_deg: 35.6, longitude_deg: 140.1, elevation: 10.0" ``` @@ -98,7 +98,7 @@ to creating entities. In order to create an entity at a given spherical coordinate using the `/world//create` service, omit the `pose` field from the -`ignition::msgs::EntityFactory` message and use the `spherical_coordinates` +`gz::msgs::EntityFactory` message and use the `spherical_coordinates` field instead. For example, you can spawn a sphere into the `spherical_coordinates.sdf` world @@ -106,8 +106,8 @@ as follows: ```.bash ign service -s /world/spherical_coordinates/create \ ---reqtype ignition.msgs.EntityFactory \ ---reptype ignition.msgs.Boolean \ +--reqtype gz.msgs.EntityFactory \ +--reptype gz.msgs.Boolean \ --timeout 300 \ --req 'sdf: '\ '"'\ @@ -136,8 +136,8 @@ For example, to move the sphere created above: ```.bash ign service -s /world/spherical_coordinates/set_spherical_coordinates \ ---reqtype ignition.msgs.SphericalCoordinates \ ---reptype ignition.msgs.Boolean \ +--reqtype gz.msgs.SphericalCoordinates \ +--reptype gz.msgs.Boolean \ --timeout 300 \ --req 'entity: {name: "spawned_model", type: MODEL}, latitude_deg: 35.59990, longitude_deg: 140.09990' ``` @@ -145,6 +145,6 @@ ign service -s /world/spherical_coordinates/set_spherical_coordinates \ ## Querying entities' coordinates When writing plugins, developers can use the -`ignition::gazebo::sphericalCoordinates` helper function to query the current +`gz::sim::sphericalCoordinates` helper function to query the current coordinates for any entity that has a pose. diff --git a/tutorials/terminology.md b/tutorials/terminology.md index 3742a569fe..44690bfa25 100644 --- a/tutorials/terminology.md +++ b/tutorials/terminology.md @@ -1,6 +1,6 @@ \page terminology Terminology -This is a list of definitions used throughout Ignition Gazebo. Some of them +This is a list of definitions used throughout Gazebo. Some of them are important for downstream users, while some of them are only interesting to developers touching the source code. @@ -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) + Gazebo comes with various + [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) @@ -26,7 +26,7 @@ to developers touching the source code. * **System**: Logic that operates on all entities that have a given set of components. Systems are plugins that can be loaded at runtime. - Ignition Gazebo ships with various systems, and downstream develpers can + Gazebo ships with various systems, and downstream develpers can [create their own systems](createsystemplugins.html). * **Entity-component manager** (**ECM**): Provides functions for @@ -66,8 +66,8 @@ to developers touching the source code. * **[Event manager](classignition_1_1gazebo_1_1EventManager.html)**: Manages events that can be sent across systems and the server. Plugins can create and emit custom - [Event](https://ignitionrobotics.org/api/common/3.0/classignition_1_1common_1_1Event.html)s - and / or emit / listen to events from Ignition Gazebo. + [Event](https://gazebosim.org/api/common/3.0/classignition_1_1common_1_1Event.html)s + and / or emit / listen to events from Gazebo. * **Simulation runner**: Runs a whole world or some levels of a world, but no more than 1 world. @@ -78,6 +78,6 @@ to developers touching the source code. * It has a network manager, if simulation is distributed. * It loads up a set of systems. -* **Server**: Ignition Gazebo's entry point. It's responsible for loading an +* **Server**: Gazebo Sim's entry point. It's responsible for loading an SDF file and instantiating a simulation runner per world. diff --git a/tutorials/test_fixture.md b/tutorials/test_fixture.md index a9a4cca1c7..a371707edb 100644 --- a/tutorials/test_fixture.md +++ b/tutorials/test_fixture.md @@ -1,8 +1,8 @@ \page test_fixture Test fixture -Ignition Gazebo can be used to run scripted simulations so that it's convenient +Gazebo can be used to run scripted simulations so that it's convenient to run automated tests for robot applications. This tutorial will go over the -process of writing automated tests using Ignition Gazebo so that they can be run +process of writing automated tests using Gazebo so that they can be run using Continuous Integration (CI). ## Example setup @@ -10,7 +10,7 @@ using Continuous Integration (CI). Gazebo can be used for testing using any testing library. We provide an example of how to setup some test cases using [Google Test](https://github.com/google/googletest) in -[ign-gazebo/examples/standalone/gtest_setup](https://github.com/ignitionrobotics/ign-gazebo/tree/main/examples/standalone/gtest_setup). +[ign-gazebo/examples/standalone/gtest_setup](https://github.com/gazebosim/gz-sim/tree/main/examples/standalone/gtest_setup). The instructions on that example's `README` can be followed to compile and run those tests. Also be sure to go through the source code for comments with @@ -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 d07c74c318..10cdd23745 100644 --- a/tutorials/triggered_publisher.md +++ b/tutorials/triggered_publisher.md @@ -13,10 +13,10 @@ in response to the motion of a vehicle. The tutorial also covers how Triggered Publisher systems can be chained together by showing how the falling of the box can trigger another box to fall. The finished world SDFormat file for this tutorial can be found in -[examples/worlds/triggered_publisher.sdf](https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo2/examples/worlds/triggered_publisher.sdf) +[examples/worlds/triggered_publisher.sdf](https://github.com/gazebosim/gz-sim/blob/ign-gazebo2/examples/worlds/triggered_publisher.sdf) We will use the differential drive vehicle from -[examples/worlds/diff_drive.sdf](https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo2/examples/worlds/diff_drive.sdf), +[examples/worlds/diff_drive.sdf](https://github.com/gazebosim/gz-sim/blob/ign-gazebo2/examples/worlds/diff_drive.sdf), but modify the input topic of the `DiffDrive` system to `cmd_vel`. A snippet of the change to the `DiffDrive` system is shown below: @@ -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,16 +45,16 @@ a "start" message from the user: ```xml - - + name="gz::sim::systems::TriggeredPublisher"> + + linear: {x: 3} ``` The `` tag sets up the `TriggeredPublisher` to subscribe to the topic -`/start` with a message type of `ignition.msgs.Empty`. The `` tag +`/start` with a message type of `gz.msgs.Empty`. The `` tag specifies the topic of the output and the actual data to be published. The data is expressed in the human-readable form of Google Protobuf messages. This is the same format used by `ign topic` for publishing messages. @@ -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,11 +164,11 @@ 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 @@ -231,9 +231,9 @@ static model `trigger` by adding the following to `trigger` Similar to what we did for `box1`, we need to publish to `/box2/detach` when our desired trigger occurs. To setup our trigger, we observe that the altimeter -publishes an `ignition.msgs.Altimeter` message that contains a +publishes an `gz.msgs.Altimeter` message that contains a `vertical_position` field. Since we do not necessarily care about the values of -the other fields inside `ignition.msgs.Altimeter`, we will create a +the other fields inside `gz.msgs.Altimeter`, we will create a `TriggeredPublisher` matcher that matches a specific field. The value of the `vertical_position` field will be the altitude of the link @@ -244,11 +244,11 @@ numbers is not advised, we will set a tolerance of 0.2. ```xml - + name="gz::sim::systems::TriggeredPublisher"> + -7.5 - + ``` @@ -261,5 +261,5 @@ ign gazebo -r triggered_publisher.sdf and publish the start message ``` -ign topic -t "/start" -m ignition.msgs.Empty -p " " +ign topic -t "/start" -m gz.msgs.Empty -p " " ``` diff --git a/tutorials/underwater_vehicles.md b/tutorials/underwater_vehicles.md index 37a5fe0eba..712b0bc561 100644 --- a/tutorials/underwater_vehicles.md +++ b/tutorials/underwater_vehicles.md @@ -6,7 +6,7 @@ This capability is based on the equations described in Fossen's ["Guidance and Control of Ocean Vehicles"](https://www.wiley.com/en-sg/Guidance+and+Control+of+Ocean+Vehicles-p-9780471941132). This tutorial will guide you through the steps you need to setup simulation of an underwater vehicle. In this tutorial, we will -guide you through the setup of the [MBARI Tethys](https://app.ignitionrobotics.org/accurrent/fuel/models/MBARI%20Tethys%20LRAUV). +guide you through the setup of the [MBARI Tethys](https://app.gazebosim.org/accurrent/fuel/models/MBARI%20Tethys%20LRAUV). One can find the final sdf file for this tutorial in the `examples/worlds/auv_controls.sdf` file. @@ -15,7 +15,7 @@ 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/ignitionrobotics/ign-gazebo/ign-gazebo5/tutorials/files/underwater/MBARI%20forces.png) +![force diagram](https://raw.githubusercontent.com/gazebosim/gz-sim/ign-gazebo5/tutorials/files/underwater/MBARI%20forces.png) # Setting up the buoyancy plugin The buoyancy plugin in ignition uses the collision mesh to calculate the volume @@ -27,7 +27,7 @@ tag: ```xml + name="gz::sim::systems::Buoyancy"> 1000 ``` @@ -38,7 +38,7 @@ rpm. Under the `` or `` tag add the following: ```xml + name="gz::sim::systems::Thruster"> tethys propeller_joint 0.004422 @@ -49,7 +49,7 @@ rpm. Under the `` or `` tag add the following: Now if we were to publish to `/model/tethys/joint/propeller_joint/cmd_pos` ``` ign topic -t /model/tethys/joint/propeller_joint/cmd_pos \ - -m ignition.msgs.Double -p 'data: -31' + -m gz.msgs.Double -p 'data: -31' ``` we should see the model move. The thrusters are governed by the equation on page 246 of Fossen's book. In particular it relates force to rpm as follows: @@ -70,7 +70,7 @@ experimental tests in a water tub. ```xml +name="gz::sim::systems::Hydrodynamics"> base_link -4.876161 -126.324739 @@ -108,7 +108,7 @@ turning when we move. +name="gz::sim::systems::LiftDrag"> 1000 4.13 -1.1 @@ -126,7 +126,7 @@ name="ignition::gazebo::systems::LiftDrag"> +name="gz::sim::systems::LiftDrag"> 1000 4.13 -1.1 @@ -147,14 +147,14 @@ use the joint controller plugin. ```xml +name="gz::sim::systems::JointPositionController"> horizontal_fins_joint 0.1 +name="gz::sim::systems::JointPositionController"> vertical_fins_joint 0.1 @@ -162,7 +162,7 @@ name="ignition::gazebo::systems::JointPositionController"> We should now be able to wiggle the fins using the following command: ``` ign topic -t /model/tethys/joint/vertical_fins_joint/0/cmd_pos \ - -m ignition.msgs.Double -p 'data: -0.17' + -m gz.msgs.Double -p 'data: -0.17' ``` # Testing the system out @@ -170,12 +170,12 @@ ign topic -t /model/tethys/joint/vertical_fins_joint/0/cmd_pos \ To control the rudder of the craft run the following ``` ign topic -t /model/tethys/joint/vertical_fins_joint/0/cmd_pos \ - -m ignition.msgs.Double -p 'data: -0.17' + -m gz.msgs.Double -p 'data: -0.17' ``` To apply a thrust you may run the following command ``` ign topic -t /model/tethys/joint/propeller_joint/cmd_pos \ --m ignition.msgs.Double -p 'data: -31' +-m gz.msgs.Double -p 'data: -31' ``` The vehicle should move in a circle. @@ -185,6 +185,6 @@ When underwater, vehicles are often subject to ocean currents. The hydrodynamics plugin allows simulation of such currents. We can add a current simply by publishing the following: ``` -ign topic -t /ocean_current -m ignition.msgs.Vector3d -p 'x: 1, y:0, z:0' +ign topic -t /ocean_current -m gz.msgs.Vector3d -p 'x: 1, y:0, z:0' ``` You should observe your vehicle slowly drift to the side. diff --git a/tutorials/video_recorder.md b/tutorials/video_recorder.md index c786dba6d0..d40618611e 100644 --- a/tutorials/video_recorder.md +++ b/tutorials/video_recorder.md @@ -2,12 +2,12 @@ ## Using the video recorder plugin -Ignition Gazebo offers a video recorder tool for recording videos from the 3D +Gazebo offers a video recorder tool for recording videos from the 3D scene. The recorder tool is available as a GUI plugin. To open this plugin, -first launch Ignition Gazebo and select the ellipsis menu on top right +first launch Gazebo and select the ellipsis menu on top right (3 dots menu), and scroll down to find the `Video Recorder` option. Click on the plugin to open the Video Recorder tool. Alternatively, launch the demo world in -Ignition Gazebo that already has this plugin included in the GUI. +Gazebo that already has this plugin included in the GUI. ``` ign gazebo -v 4 video_record_dbl_pendulum.sdf @@ -35,14 +35,14 @@ window prior to recording. A few video recorder parameters can be specified using GUI configurations, see the [GUI Configuration](gui_config.html) tutorial for more information. -If you launched Ignition Gazebo with the +If you launched Gazebo with the `video_record_dbl_pendulum.sdf` demo world, the GUI configurations are embedded in the world SDF file so you will need to download a copy of the -[sdf file](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/examples/worlds/video_record_dbl_pendulum.sdf). +[sdf file](https://raw.githubusercontent.com/gazebosim/gz-sim/main/examples/worlds/video_record_dbl_pendulum.sdf). and modify the GUI configuration in that file. On the other hand, if you -launched Ignition Gazebo with a world file that does not have GUI +launched Gazebo with a world file that does not have GUI configurations, you will need to specify the settings in -`$HOME/.ignition/gazebo/<#>/gui.config`. +`$HOME/.gz/sim/<#>/gui.config`. Recall that videos are recorded from the 3D scene, we will to set the video configurations in the 3D scene plugin. Here is an example of the @@ -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 ``` @@ -108,7 +108,7 @@ generated video. The default bitrate is 2Mbps. ## Hardware-accelerated encoding -Since Ignition Common 3.10.2, there is support for utilizing the power of GPUs +Since Gazebo Common 3.10.2, there is support for utilizing the power of GPUs to speed up the video encoding process. See the -[Hardware-accelerated Video Encoding tutorial](https://ignitionrobotics.org/api/common/3.10/hw-encoding.html) +[Hardware-accelerated Video Encoding tutorial](https://gazebosim.org/api/common/3.10/hw-encoding.html) for more details.
Documentation:" "" - "" - "https://ignitionrobotics.org/libs/gazebo" + "https://gazebosim.org/libs/gazebo" "" "
" - "" - "https://ignitionrobotics.org/docs/" + "https://gazebosim.org/docs/" "" "