diff --git a/.github/ci/packages.apt b/.github/ci/packages.apt index 3d556cb0..469eba9b 100644 --- a/.github/ci/packages.apt +++ b/.github/ci/packages.apt @@ -1,9 +1,9 @@ -libignition-cmake3-dev -libignition-common5-dev -libignition-math7-dev -libignition-msgs9-dev -libignition-rendering7-dev -libignition-tools2-dev -libignition-transport12-dev +libgz-cmake3-dev +libgz-common5-dev +libgz-math7-dev +libgz-msgs9-dev +libgz-rendering7-dev +libgz-tools2-dev +libgz-transport12-dev libsdformat13-dev xvfb diff --git a/.github/disabled_workflows/macos.yml b/.github/disabled_workflows/macos.yml index d7e1e68f..963b6336 100644 --- a/.github/disabled_workflows/macos.yml +++ b/.github/disabled_workflows/macos.yml @@ -6,7 +6,7 @@ jobs: build: env: - PACKAGE: ignition-sensors7 + PACKAGE: gz-sensors7 runs-on: macos-latest steps: - uses: actions/checkout@v2 diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index ba1eed61..bd14ed68 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -11,7 +11,7 @@ jobs: uses: actions/checkout@v2 - name: Compile and test id: ci - uses: ignition-tooling/action-ignition-ci@focal + uses: gazebo-tooling/action-gz-ci@focal with: codecov-enabled: true cppcheck-enabled: true @@ -24,4 +24,4 @@ jobs: uses: actions/checkout@v2 - name: Compile and test id: ci - uses: ignition-tooling/action-ignition-ci@jammy + uses: gazebo-tooling/action-gz-ci@jammy diff --git a/.github/workflows/pr-collection-labeler.yml b/.github/workflows/pr-collection-labeler.yml index 7d7b4e17..38c4fc13 100644 --- a/.github/workflows/pr-collection-labeler.yml +++ b/.github/workflows/pr-collection-labeler.yml @@ -8,6 +8,6 @@ jobs: steps: - name: Add collection labels if: github.event.action == 'opened' - uses: ignition-tooling/pr-collection-labeler@v1 + uses: gazebo-tooling/pr-collection-labeler@v1 with: github-token: ${{ secrets.GITHUB_TOKEN }} diff --git a/CMakeLists.txt b/CMakeLists.txt index cc1983d3..1ca48694 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -16,9 +16,7 @@ find_package(gz-cmake3 REQUIRED) set(CMAKE_CXX_STANDARD 17) set(CMAKE_CXX_STANDARD_REQUIRED ON) -gz_configure_project( - REPLACE_IGNITION_INCLUDE_PATH gz/sensors - VERSION_SUFFIX pre1) +gz_configure_project(VERSION_SUFFIX pre1) #============================================================================ # Set project-specific options @@ -41,7 +39,7 @@ message(STATUS "\n\n-- ====== Finding Dependencies ======") #-------------------------------------- # Find Protobuf set(REQ_PROTOBUF_VER 3) -gz_find_package(IgnProtobuf +gz_find_package(GzProtobuf VERSION ${REQ_PROTOBUF_VER} REQUIRED PRETTY Protobuf) diff --git a/Migration.md b/Migration.md index 56c85e56..57d1937f 100644 --- a/Migration.md +++ b/Migration.md @@ -89,7 +89,7 @@ release will remove the deprecated code. ### Additions -1. The core ignition-sensors library no longer depends on ign-rendering. All +1. The core gz-sensors library no longer depends on gz-rendering. All rendering sensors and noise models are now part of the `rendering` component 1. New sensors: thermal camera diff --git a/README.md b/README.md index c8daa62c..8e23137c 100644 --- a/README.md +++ b/README.md @@ -65,7 +65,7 @@ Refer to the following table for information about important directories and fil ``` ├── examples Example programs. -├── include/ignition/sensors Header files that will be installed. +├── include/gz/sensors Header files that will be installed. ├── src Source files and unit tests. ├── test │   ├── integration Integration tests. diff --git a/api.md.in b/api.md.in index 218f6857..bb345ae1 100644 --- a/api.md.in +++ b/api.md.in @@ -1,6 +1,6 @@ -## Gazebo @IGN_DESIGNATION_CAP@ +## Gazebo @GZ_DESIGNATION_CAP@ -Gazebo @IGN_DESIGNATION_CAP@ is a component in Gazebo, a set of libraries +Gazebo @GZ_DESIGNATION_CAP@ is a component in Gazebo, a set of libraries designed to rapidly develop robot and simulation applications. ## License diff --git a/configure.bat b/configure.bat deleted file mode 100644 index cd99e189..00000000 --- a/configure.bat +++ /dev/null @@ -1,5 +0,0 @@ -@set build_type=Release -@if not "%1"=="" set build_type=%1 -@echo Configuring for build type %build_type% - -cmake -G "NMake Makefiles" -DCMAKE_INSTALL_PREFIX="install\%build_type%" -DCMAKE_BUILD_TYPE="%build_type%" -DENABLE_TESTS_COMPILATION:BOOL=True .. diff --git a/doc/CMakeLists.txt b/doc/CMakeLists.txt index f4316917..5e036492 100644 --- a/doc/CMakeLists.txt +++ b/doc/CMakeLists.txt @@ -1,6 +1,6 @@ find_package(Doxygen) -set(IGNITION_DOXYGEN_TAGFILES +set(GZ_DOXYGEN_TAGFILES "\"${GZ-MATH_DOXYGEN_TAGFILE} = ${GZ-MATH_API_URL}\" \ \"${GZ-MSGS_DOXYGEN_TAGFILE} = ${GZ-MSGS_API_URL}\" \ \"${GZ-TRANSPORT_DOXYGEN_TAGFILE} = ${GZ-TRANSPORT_API_URL}\" \ @@ -8,10 +8,10 @@ set(IGNITION_DOXYGEN_TAGFILES ) if (DOXYGEN_FOUND) - configure_file(${IGNITION_CMAKE_DOXYGEN_DIR}/api.in + configure_file(${GZ_CMAKE_DOXYGEN_DIR}/api.in ${CMAKE_BINARY_DIR}/api.dox @ONLY) - configure_file(${IGNITION_CMAKE_DOXYGEN_DIR}/tutorials.in + configure_file(${GZ_CMAKE_DOXYGEN_DIR}/tutorials.in ${CMAKE_BINARY_DIR}/tutorials.dox @ONLY) add_custom_target(doc ALL diff --git a/examples/imu_noise/README.md b/examples/imu_noise/README.md index ffb5781a..c3736d2f 100644 --- a/examples/imu_noise/README.md +++ b/examples/imu_noise/README.md @@ -4,7 +4,7 @@ This example creates a sequence of samples for an accelerometer and gyroscope ba on the https://www.analog.com/media/en/technical-documentation/data-sheets/adis16448.pdf, a commonly-used MEMS IMU. The sequence of samples can then be evaluated with Allan Variance to determine that -the noise generation in ign-sensors is working as expected. +the noise generation in gz-sensors is working as expected. To evaluate noise, first build and run. diff --git a/examples/loop_sensor/README.md b/examples/loop_sensor/README.md index 8ea50a7a..be189b9c 100644 --- a/examples/loop_sensor/README.md +++ b/examples/loop_sensor/README.md @@ -38,7 +38,7 @@ On another terminal, check that the altimeter and odometer are generating data on a topic: ``` -ign topic -l +gz topic -l ``` You should see: @@ -51,7 +51,7 @@ You should see: Then listen to the altimeter data: ``` -ign topic -e -t /altimeter +gz topic -e -t /altimeter ``` You'll see data like: @@ -79,7 +79,7 @@ vertical_velocity: 10.596832320931542 Then listen to the custom sensor: ``` -ign topic -e -t /odometer +gz topic -e -t /odometer ``` You'll see data like: diff --git a/examples/save_image/main.cc b/examples/save_image/main.cc index e405bfad..9c4b7bf9 100644 --- a/examples/save_image/main.cc +++ b/examples/save_image/main.cc @@ -25,7 +25,7 @@ #include #include -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) @@ -58,7 +58,7 @@ void BuildScene(gz::rendering::ScenePtr _scene); int main() { - // Setup ign-rendering with a scene + // Setup gz-rendering with a scene #ifdef WITH_OGRE auto engine = gz::rendering::engine("ogre"); #else @@ -82,7 +82,7 @@ int main() // Create SDF describing a camera sensor const std::string name = "ExampleCamera"; - const std::string topic = "/ignition/sensors/examples/save_image"; + const std::string topic = "/gz/sensors/examples/save_image"; const double hz = 30; const std::size_t width = 480; const std::size_t height = 320; @@ -133,7 +133,7 @@ int main() return 0; } -// Copy/paste from an gz-rendering example +// Copy/paste from a gz-rendering example void BuildScene(gz::rendering::ScenePtr _scene) { // initialize _scene diff --git a/include/CMakeLists.txt b/include/CMakeLists.txt index 4b2bdd7b..992a1312 100644 --- a/include/CMakeLists.txt +++ b/include/CMakeLists.txt @@ -1,2 +1,2 @@ add_subdirectory(gz) -install(DIRECTORY ignition DESTINATION ${IGN_INCLUDE_INSTALL_DIR_FULL}) +install(DIRECTORY ignition DESTINATION ${GZ_INCLUDE_INSTALL_DIR_FULL}) diff --git a/include/gz/sensors/AltimeterSensor.hh b/include/gz/sensors/AltimeterSensor.hh index a930f0c1..f1abf2a1 100644 --- a/include/gz/sensors/AltimeterSensor.hh +++ b/include/gz/sensors/AltimeterSensor.hh @@ -41,7 +41,7 @@ namespace gz /// \brief Altimeter Sensor Class /// /// An altimeter sensor that reports vertical position and velocity - /// readings over ign transport + /// readings over gz transport class GZ_SENSORS_ALTIMETER_VISIBLE AltimeterSensor : public Sensor { /// \brief constructor diff --git a/include/gz/sensors/CameraSensor.hh b/include/gz/sensors/CameraSensor.hh index 1d43ddcb..930bfa79 100644 --- a/include/gz/sensors/CameraSensor.hh +++ b/include/gz/sensors/CameraSensor.hh @@ -35,7 +35,7 @@ #pragma warning(pop) #endif -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) @@ -65,7 +65,7 @@ namespace gz /// /// This class creates images from a Gazebo Rendering scene. The scene /// must be created in advance and given to Manager::Init(). - /// It offers both an ignition-transport interface and a direct C++ API + /// It offers both a gz-transport interface and a direct C++ API /// to access the image data. The API works by setting a callback to be /// called with image data. class GZ_SENSORS_CAMERA_VISIBLE CameraSensor : public RenderingSensor diff --git a/include/gz/sensors/DepthCameraSensor.hh b/include/gz/sensors/DepthCameraSensor.hh index 1217fb5b..a5a91370 100644 --- a/include/gz/sensors/DepthCameraSensor.hh +++ b/include/gz/sensors/DepthCameraSensor.hh @@ -36,7 +36,7 @@ #pragma warning(pop) #endif -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) @@ -65,7 +65,7 @@ namespace gz /// /// This class creates depth image from a Gazebo Rendering scene. /// The scene must be created in advance and given to Manager::Init(). - /// It offers both an ignition-transport interface and a direct C++ API + /// It offers both a gz-transport interface and a direct C++ API /// to access the image data. The API works by setting a callback to be /// called with image data. class GZ_SENSORS_DEPTH_CAMERA_VISIBLE DepthCameraSensor diff --git a/include/gz/sensors/GpuLidarSensor.hh b/include/gz/sensors/GpuLidarSensor.hh index 85705cd5..6438221d 100644 --- a/include/gz/sensors/GpuLidarSensor.hh +++ b/include/gz/sensors/GpuLidarSensor.hh @@ -24,7 +24,7 @@ #include -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) @@ -55,7 +55,7 @@ namespace gz /// from the origin of the center to points on the visual geometry in the /// scene. /// - /// It offers both an ignition-transport interface and a direct C++ API + /// It offers both a gz-transport interface and a direct C++ API /// to access the image data. The API works by setting a callback to be /// called with image data. class GZ_SENSORS_GPU_LIDAR_VISIBLE GpuLidarSensor : public Lidar diff --git a/include/gz/sensors/ImageBrownDistortionModel.hh b/include/gz/sensors/ImageBrownDistortionModel.hh index ee4441f0..af70082e 100644 --- a/include/gz/sensors/ImageBrownDistortionModel.hh +++ b/include/gz/sensors/ImageBrownDistortionModel.hh @@ -20,7 +20,7 @@ #include -// TODO(WilliamLewww): Remove these pragmas once ign-rendering is disabling the +// TODO(WilliamLewww): Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) diff --git a/include/gz/sensors/ImageGaussianNoiseModel.hh b/include/gz/sensors/ImageGaussianNoiseModel.hh index ed71390c..d9b7e6a4 100644 --- a/include/gz/sensors/ImageGaussianNoiseModel.hh +++ b/include/gz/sensors/ImageGaussianNoiseModel.hh @@ -20,7 +20,7 @@ #include -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) diff --git a/include/gz/sensors/Lidar.hh b/include/gz/sensors/Lidar.hh index 5acc2b9a..988533e6 100644 --- a/include/gz/sensors/Lidar.hh +++ b/include/gz/sensors/Lidar.hh @@ -43,7 +43,7 @@ namespace gz /// from the origin of the center to points on the visual geometry in the /// scene. /// - /// It offers both an ignition-transport interface and a direct C++ API + /// It offers both a gz-transport interface and a direct C++ API /// to access the image data. The API works by setting a callback to be /// called with image data. class GZ_SENSORS_LIDAR_VISIBLE Lidar : public RenderingSensor diff --git a/include/gz/sensors/RenderingEvents.hh b/include/gz/sensors/RenderingEvents.hh index 424b0fc1..e204ca4f 100644 --- a/include/gz/sensors/RenderingEvents.hh +++ b/include/gz/sensors/RenderingEvents.hh @@ -21,7 +21,7 @@ #include #include -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) diff --git a/include/gz/sensors/RenderingSensor.hh b/include/gz/sensors/RenderingSensor.hh index 0f236701..7443ff8c 100644 --- a/include/gz/sensors/RenderingSensor.hh +++ b/include/gz/sensors/RenderingSensor.hh @@ -21,7 +21,7 @@ #include -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) diff --git a/include/gz/sensors/RgbdCameraSensor.hh b/include/gz/sensors/RgbdCameraSensor.hh index 28de04f8..f3fc58cc 100644 --- a/include/gz/sensors/RgbdCameraSensor.hh +++ b/include/gz/sensors/RgbdCameraSensor.hh @@ -45,7 +45,7 @@ namespace gz /// * Depth image (same as DepthCamera) /// * (future / todo) Color point cloud /// The scene must be created in advance and given to Manager::Init(). - /// It offers both an ignition-transport interface and a direct C++ API + /// It offers both a gz-transport interface and a direct C++ API /// to access the image data. The API works by setting a callback to be /// called with image data. class GZ_SENSORS_RGBD_CAMERA_VISIBLE RgbdCameraSensor diff --git a/include/gz/sensors/SegmentationCameraSensor.hh b/include/gz/sensors/SegmentationCameraSensor.hh index 0c52f5a9..59303474 100644 --- a/include/gz/sensors/SegmentationCameraSensor.hh +++ b/include/gz/sensors/SegmentationCameraSensor.hh @@ -47,7 +47,7 @@ namespace gz /// /// This class creates segmentation images from a Gazebo Rendering scene. /// The scene must be created in advance and given to Manager::Init(). - /// It offers both an ignition-transport interface and a direct C++ API + /// It offers both a gz-transport interface and a direct C++ API /// to access the image data. The API works by setting a callback to be /// called with image data. class GZ_SENSORS_SEGMENTATION_CAMERA_VISIBLE diff --git a/include/gz/sensors/Sensor.hh b/include/gz/sensors/Sensor.hh index be357ba4..146ebf61 100644 --- a/include/gz/sensors/Sensor.hh +++ b/include/gz/sensors/Sensor.hh @@ -187,7 +187,7 @@ namespace gz /// information for this sensor. public: sdf::ElementPtr SDF() const; - /// \brief Add a sequence number to an gz::msgs::Header. This + /// \brief Add a sequence number to a gz::msgs::Header. This /// function can be called by a sensor that wants to add a sequence /// number to a sensor message in order to have improved /// accountability for generated sensor data. diff --git a/include/gz/sensors/SensorFactory.hh b/include/gz/sensors/SensorFactory.hh index b7d8175c..b6c3b202 100644 --- a/include/gz/sensors/SensorFactory.hh +++ b/include/gz/sensors/SensorFactory.hh @@ -171,7 +171,7 @@ namespace gz /// /// This creates sensors by looking at the given SDF Sensor DOM /// object. - /// Sensors created with this API offer an ignition-transport interface. + /// Sensors created with this API offer a gz-transport interface. /// If you need a direct C++ interface to the data, you must get the /// sensor pointer and cast to the correct type. /// diff --git a/include/gz/sensors/ThermalCameraSensor.hh b/include/gz/sensors/ThermalCameraSensor.hh index f8d7a719..e0d6bbe6 100644 --- a/include/gz/sensors/ThermalCameraSensor.hh +++ b/include/gz/sensors/ThermalCameraSensor.hh @@ -36,7 +36,7 @@ #pragma warning(pop) #endif -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) @@ -65,7 +65,7 @@ namespace gz /// /// This class creates thermal image from a Gazebo Rendering scene. /// The scene must be created in advance and given to Manager::Init(). - /// It offers both an ignition-transport interface and a direct C++ API + /// It offers both a gz-transport interface and a direct C++ API /// to access the image data. The API works by setting a callback to be /// called with image data. class GZ_SENSORS_THERMAL_CAMERA_VISIBLE ThermalCameraSensor diff --git a/include/gz/sensors/WideAngleCameraSensor.hh b/include/gz/sensors/WideAngleCameraSensor.hh index d975fe09..a9b80c7b 100644 --- a/include/gz/sensors/WideAngleCameraSensor.hh +++ b/include/gz/sensors/WideAngleCameraSensor.hh @@ -36,7 +36,7 @@ #pragma warning(pop) #endif -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) @@ -65,7 +65,7 @@ namespace gz /// /// This class creates wide angle camera image from a Gazebo Rendering /// scene. The scene must be created in advance and given to Manager::Init() - /// It offers both an ignition-transport interface and a direct C++ API + /// It offers both a gz-transport interface and a direct C++ API /// to access the image data. The API works by setting a callback to be /// called with image data. class GZ_SENSORS_WIDE_ANGLE_CAMERA_VISIBLE WideAngleCameraSensor diff --git a/include/gz/sensors/sensors.hh.in b/include/gz/sensors/sensors.hh.in index 61b338de..ac83b06b 100644 --- a/include/gz/sensors/sensors.hh.in +++ b/include/gz/sensors/sensors.hh.in @@ -1,3 +1,3 @@ // Automatically generated #include -${ign_headers} +${gz_headers} diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 776bdfc0..904dd46c 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -28,7 +28,7 @@ set (gtest_sources ) if (MSVC) - # TODO(louise) Remove this once warnings are suppressed in ign-rendering + # TODO(louise) Remove this once warnings are suppressed in gz-rendering set_source_files_properties( ${rendering_sources} SegmentationCameraSensor.cc diff --git a/src/ImageBrownDistortionModel.cc b/src/ImageBrownDistortionModel.cc index bc21e1a2..4fd9e1fd 100644 --- a/src/ImageBrownDistortionModel.cc +++ b/src/ImageBrownDistortionModel.cc @@ -22,7 +22,7 @@ #include -// TODO(WilliamLewww): Remove these pragmas once ign-rendering is disabling the +// TODO(WilliamLewww): Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) diff --git a/src/ImageGaussianNoiseModel.cc b/src/ImageGaussianNoiseModel.cc index 8d06a51c..45f60ae8 100644 --- a/src/ImageGaussianNoiseModel.cc +++ b/src/ImageGaussianNoiseModel.cc @@ -22,7 +22,7 @@ #include -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) diff --git a/src/ImuSensor_TEST.cc b/src/ImuSensor_TEST.cc index 4fb233af..21e3476a 100644 --- a/src/ImuSensor_TEST.cc +++ b/src/ImuSensor_TEST.cc @@ -199,7 +199,7 @@ TEST(ImuSensor_TEST, CreateImuSensor) gz::sensors::Manager mgr; const std::string name = "TestImu"; - const std::string topic = "/ignition/sensors/test/imu"; + const std::string topic = "/gz/sensors/test/imu"; const double update_rate = 100; const auto accelNoise = accelerometerParameters(update_rate, 0.0); const auto gyroNoise = gyroscopeParameters(update_rate, 0.0); @@ -226,7 +226,7 @@ TEST(ImuSensor_TEST, ComputeNoise) { const std::string name = "TestImu_Truth"; - const std::string topic = "/ignition/sensors/test/imu_truth"; + const std::string topic = "/gz/sensors/test/imu_truth"; const double update_rate = 100; const auto accelNoise = noNoiseParameters(update_rate, 0.0); const auto gyroNoise = noNoiseParameters(update_rate, 0.0); @@ -239,7 +239,7 @@ TEST(ImuSensor_TEST, ComputeNoise) { const std::string name = "TestImu_Truth"; - const std::string topic = "/ignition/sensors/test/imu_truth"; + const std::string topic = "/gz/sensors/test/imu_truth"; const double update_rate = 100; auto accelNoise = accelerometerParameters(update_rate, 0.0); auto gyroNoise = gyroscopeParameters(update_rate, 0.0); @@ -322,7 +322,7 @@ TEST(ImuSensor_TEST, Orientation) { const std::string name = "TestImu_Truth"; - const std::string topic = "/ignition/sensors/test/imu_truth"; + const std::string topic = "/gz/sensors/test/imu_truth"; const double updateRate = 100; const auto accelNoise = noNoiseParameters(updateRate, 0.0); const auto gyroNoise = noNoiseParameters(updateRate, 0.0); diff --git a/src/Lidar_TEST.cc b/src/Lidar_TEST.cc index 0154ae78..47e7a747 100644 --- a/src/Lidar_TEST.cc +++ b/src/Lidar_TEST.cc @@ -116,7 +116,7 @@ TEST(Lidar_TEST, CreateLaser) // Create SDF describing a camera sensor const std::string name = "TestLidar"; - const std::string topic = "/ignition/sensors/test/lidar"; + const std::string topic = "/gz/sensors/test/lidar"; const double update_rate = 30; const double horz_samples = 640; const double horz_resolution = 1; diff --git a/src/Manager.cc b/src/Manager.cc index b83a0003..2c39df69 100644 --- a/src/Manager.cc +++ b/src/Manager.cc @@ -96,8 +96,8 @@ gz::sensors::SensorId Manager::AddSensor( ///////////////////////////////////////////////// gz::sensors::SensorId Manager::CreateSensor(const sdf::Sensor &) { - gzwarn << "Trying to create sensor without providing sensor type. Ignition" - << " Sensor doesn't support sensor registration anymore. Use the" + gzwarn << "Trying to create sensor without providing sensor type. Gazebo" + << " Sensors doesn't support sensor registration anymore. Use the" << " templated `CreateSensor` function instead." << std::endl; return NO_SENSOR; } @@ -105,8 +105,8 @@ gz::sensors::SensorId Manager::CreateSensor(const sdf::Sensor &) ///////////////////////////////////////////////// gz::sensors::SensorId Manager::CreateSensor(sdf::ElementPtr) { - gzwarn << "Trying to create sensor without providing sensor type. Ignition" - << " Sensor doesn't support sensor registration anymore. Use the" + gzwarn << "Trying to create sensor without providing sensor type. Gazebo" + << " Sensors doesn't support sensor registration anymore. Use the" << " templated `CreateSensor` function instead." << std::endl; return NO_SENSOR; } diff --git a/src/RenderingSensor.cc b/src/RenderingSensor.cc index 8366e66f..21e450ab 100644 --- a/src/RenderingSensor.cc +++ b/src/RenderingSensor.cc @@ -17,7 +17,7 @@ #include -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) diff --git a/src/RgbdCameraSensor.cc b/src/RgbdCameraSensor.cc index 959a07f4..c73cf74f 100644 --- a/src/RgbdCameraSensor.cc +++ b/src/RgbdCameraSensor.cc @@ -30,7 +30,7 @@ #include #include -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) diff --git a/src/Sensor.cc b/src/Sensor.cc index e30258f8..3449d290 100644 --- a/src/Sensor.cc +++ b/src/Sensor.cc @@ -129,7 +129,7 @@ bool SensorPrivate::PopulateFromSDF(const sdf::Sensor &_sdf) // then the update_rate will be obeyed. Gazebo seems to use it as if // true means enable the sensor at startup. - // \todo(nkoenig) what to do with ? ign-sensor data is meant to + // \todo(nkoenig) what to do with ? gz-sensor data is meant to // create // sensor data. Whether or not that data should be visualized seems to // be outside the scope of this library diff --git a/src/SensorFactory.cc b/src/SensorFactory.cc index ab7893bd..4012baf6 100644 --- a/src/SensorFactory.cc +++ b/src/SensorFactory.cc @@ -47,8 +47,8 @@ SensorFactory::~SensorFactory() ///////////////////////////////////////////////// std::unique_ptr SensorFactory::CreateSensor(const sdf::Sensor &) { - gzwarn << "Trying to create sensor without providing sensor type. Ignition" - << " Sensor doesn't support sensor registration anymore. Use the" + gzwarn << "Trying to create sensor without providing sensor type. Gazebo" + << " Sensors doesn't support sensor registration anymore. Use the" << " templated `CreateSensor` function instead." << std::endl; return nullptr; } @@ -56,8 +56,8 @@ std::unique_ptr SensorFactory::CreateSensor(const sdf::Sensor &) ///////////////////////////////////////////////// std::unique_ptr SensorFactory::CreateSensor(sdf::ElementPtr) { - gzwarn << "Trying to create sensor without providing sensor type. Ignition" - << " Sensor doesn't support sensor registration anymore. Use the" + gzwarn << "Trying to create sensor without providing sensor type. Gazebo" + << " Sensors doesn't support sensor registration anymore. Use the" << " templated `CreateSensor` function instead." << std::endl; return nullptr; } diff --git a/src/ThermalCameraSensor.cc b/src/ThermalCameraSensor.cc index 398ebfc2..73f505f5 100644 --- a/src/ThermalCameraSensor.cc +++ b/src/ThermalCameraSensor.cc @@ -461,7 +461,7 @@ bool ThermalCameraSensor::Update( std::lock_guard lock(this->dataPtr->mutex); - // \todo(anyone) once ign-rendering supports an image event with unsigned char + // \todo(anyone) once gz-rendering supports an image event with unsigned char // data type, we can remove this check that copies uint16_t data to char array if (this->dataPtr->thermalCamera->ImageFormat() == rendering::PF_L8) { diff --git a/test/integration/air_pressure.cc b/test/integration/air_pressure.cc index 84880f6c..f7ce3c5e 100644 --- a/test/integration/air_pressure.cc +++ b/test/integration/air_pressure.cc @@ -114,8 +114,8 @@ TEST_F(AirPressureSensorTest, CreateAirPressure) { // Create SDF describing an air_pressure sensor const std::string name = "TestAirPressure"; - const std::string topic = "/ignition/sensors/test/air_pressure"; - const std::string topicNoise = "/ignition/sensors/test/air_pressure_noise"; + const std::string topic = "/gz/sensors/test/air_pressure"; + const std::string topicNoise = "/gz/sensors/test/air_pressure_noise"; const double updateRate = 30; const bool alwaysOn = 1; const bool visualize = 1; @@ -154,8 +154,8 @@ TEST_F(AirPressureSensorTest, SensorReadings) { // Create SDF describing an air_pressure sensor const std::string name = "TestAirPressure"; - const std::string topic = "/ignition/sensors/test/air_pressure"; - const std::string topicNoise = "/ignition/sensors/test/air_pressure_noise"; + const std::string topic = "/gz/sensors/test/air_pressure"; + const std::string topicNoise = "/gz/sensors/test/air_pressure_noise"; const double updateRate = 30; const bool alwaysOn = 1; const bool visualize = 1; diff --git a/test/integration/all_symbols_have_version.bash.in b/test/integration/all_symbols_have_version.bash.in index f9507255..0809555f 100644 --- a/test/integration/all_symbols_have_version.bash.in +++ b/test/integration/all_symbols_have_version.bash.in @@ -2,10 +2,10 @@ LIBPATH=$1 VERSIONED_NS=v@PROJECT_VERSION_MAJOR@ -IGN_PROJECT=@IGN_DESIGNATION@ +GZ_PROJECT=@GZ_DESIGNATION@ # Sanity check - there should be at least one symbol -NUM_SYMBOLS=$(nm $LIBPATH | grep -e "gz.*$IGN_PROJECT" | wc -l) +NUM_SYMBOLS=$(nm $LIBPATH | grep -e "gz.*$GZ_PROJECT" | wc -l) if [ $NUM_SYMBOLS -eq 0 ] then @@ -14,7 +14,7 @@ then fi # There must be no unversioned symbols -UNVERSIONED_SYMBOLS=$(nm $LIBPATH | grep -e "gz.*$IGN_PROJECT" | grep -e "$VERSIONED_NS" -v) +UNVERSIONED_SYMBOLS=$(nm $LIBPATH | grep -e "gz.*$GZ_PROJECT" | grep -e "$VERSIONED_NS" -v) UNVERSIONED_SYMBOL_CHARS=$(printf "$UNVERSIONED_SYMBOLS" | wc -m) if [ $UNVERSIONED_SYMBOL_CHARS -ne 0 ] diff --git a/test/integration/altimeter.cc b/test/integration/altimeter.cc index e15ff346..f1bed94b 100644 --- a/test/integration/altimeter.cc +++ b/test/integration/altimeter.cc @@ -121,8 +121,8 @@ TEST_F(AltimeterSensorTest, CreateAltimeter) { // Create SDF describing an altimeter sensor const std::string name = "TestAltimeter"; - const std::string topic = "/ignition/sensors/test/altimeter"; - const std::string topicNoise = "/ignition/sensors/test/altimeter_noise"; + const std::string topic = "/gz/sensors/test/altimeter"; + const std::string topicNoise = "/gz/sensors/test/altimeter_noise"; const double updateRate = 30; const bool alwaysOn = 1; const bool visualize = 1; @@ -160,8 +160,8 @@ TEST_F(AltimeterSensorTest, SensorReadings) { // Create SDF describing an altimeter sensor const std::string name = "TestAltimeter"; - const std::string topic = "/ignition/sensors/test/altimeter"; - const std::string topicNoise = "/ignition/sensors/test/altimeter_noise"; + const std::string topic = "/gz/sensors/test/altimeter"; + const std::string topicNoise = "/gz/sensors/test/altimeter_noise"; const double updateRate = 30; const bool alwaysOn = 1; const bool visualize = 1; diff --git a/test/integration/camera.cc b/test/integration/camera.cc index e671b4ca..fdc6c92c 100644 --- a/test/integration/camera.cc +++ b/test/integration/camera.cc @@ -22,7 +22,7 @@ #include #include -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) @@ -102,7 +102,7 @@ void CameraSensorTest::ImagesWithBuiltinSDF(const std::string &_renderEngine) ASSERT_TRUE(linkPtr->HasElement("sensor")); auto sensorPtr = linkPtr->GetElement("sensor"); - // Setup ign-rendering with an empty scene + // Setup gz-rendering with an empty scene auto *engine = gz::rendering::engine(_renderEngine); if (!engine) { @@ -196,7 +196,7 @@ void CameraSensorTest::ImageFormatLInt8LInt16(const std::string &_renderEngine) auto sensorPtrCamera8Bit = linkPtr->GetElement("sensor"); auto sensorPtrCamera16Bit = linkPtr->GetElement("sensor")->GetNextElement(); - // Setup ign-rendering with an empty scene + // Setup gz-rendering with an empty scene auto *engine = gz::rendering::engine(_renderEngine); if (!engine) { diff --git a/test/integration/depth_camera.cc b/test/integration/depth_camera.cc index 1e204655..bbe97d95 100644 --- a/test/integration/depth_camera.cc +++ b/test/integration/depth_camera.cc @@ -33,7 +33,7 @@ #include #include -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) @@ -191,7 +191,7 @@ void DepthCameraSensorTest::ImagesWithBuiltinSDF( return; } - // Setup ign-rendering with an empty scene + // Setup gz-rendering with an empty scene auto *engine = gz::rendering::engine(_renderEngine); if (!engine) { diff --git a/test/integration/distortion_camera.cc b/test/integration/distortion_camera.cc index b09a004a..55a2c4c8 100644 --- a/test/integration/distortion_camera.cc +++ b/test/integration/distortion_camera.cc @@ -22,7 +22,7 @@ #include #include -// TODO(WilliamLewww): Remove these pragmas once ign-rendering is disabling the +// TODO(WilliamLewww): Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) @@ -85,7 +85,7 @@ void DistortionCameraSensorTest::ImagesWithBuiltinSDF( return; } - // Setup ign-rendering with an empty scene + // Setup gz-rendering with an empty scene auto *engine = gz::rendering::engine(_renderEngine); if (!engine) { diff --git a/test/integration/force_torque.cc b/test/integration/force_torque.cc index 06eeca00..3750ffdd 100644 --- a/test/integration/force_torque.cc +++ b/test/integration/force_torque.cc @@ -139,7 +139,7 @@ TEST_F(ForceTorqueSensorTest, CreateForceTorqueSensor) { // Create SDF describing a force torque sensor const std::string name = "TestForceTorqueSensor"; - const std::string topic = "/ignition/sensors/test/force_torque"; + const std::string topic = "/gz/sensors/test/force_torque"; const double updateRate = 30; const bool alwaysOn = 1; @@ -176,7 +176,7 @@ TEST_P(ForceTorqueSensorTest, SensorReadings) // Create SDF describing a a force torque sensor const std::string name = "TestForceTorqueSensor"; - const std::string topic = "/ignition/sensors/test/force_torque"; + const std::string topic = "/gz/sensors/test/force_torque"; const double updateRate = 30; const bool alwaysOn = 1; const bool visualize = 1; diff --git a/test/integration/gpu_lidar_sensor.cc b/test/integration/gpu_lidar_sensor.cc index be1feddc..fe51dbf9 100644 --- a/test/integration/gpu_lidar_sensor.cc +++ b/test/integration/gpu_lidar_sensor.cc @@ -36,7 +36,7 @@ #endif #include -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) @@ -171,7 +171,7 @@ void GpuLidarSensorTest::CreateGpuLidar(const std::string &_renderEngine) // Create SDF describing a camera sensor const std::string name = "TestGpuLidar"; const std::string parent = "parent_link"; - const std::string topic = "/ignition/sensors/test/lidar"; + const std::string topic = "/gz/sensors/test/lidar"; const double updateRate = 30; const unsigned int horzSamples = 640; const double horzResolution = 1; @@ -195,7 +195,7 @@ void GpuLidarSensorTest::CreateGpuLidar(const std::string &_renderEngine) vertSamples, vertResolution, vertMinAngle, vertMaxAngle, rangeResolution, rangeMin, rangeMax, alwaysOn, visualize); - // Setup ign-rendering with an empty scene + // Setup gz-rendering with an empty scene auto *engine = gz::rendering::engine(_renderEngine); if (!engine) { @@ -289,7 +289,7 @@ void GpuLidarSensorTest::DetectBox(const std::string &_renderEngine) // Create SDF describing a camera sensor const std::string name = "TestGpuLidar"; const std::string parent = "parent_link"; - const std::string topic = "/ignition/sensors/test/lidar"; + const std::string topic = "/gz/sensors/test/lidar"; const double updateRate = 30; const int horzSamples = 320; const double horzResolution = 1; @@ -434,8 +434,8 @@ void GpuLidarSensorTest::TestThreeBoxes(const std::string &_renderEngine) // Create SDF describing a gpu lidar sensors sensor const std::string name1 = "TestGpuLidar1"; const std::string name2 = "TestGpuLidar2"; - const std::string topic1 = "/ignition/sensors/test/lidar1"; - const std::string topic2 = "/ignition/sensors/test/lidar2"; + const std::string topic1 = "/gz/sensors/test/lidar1"; + const std::string topic2 = "/gz/sensors/test/lidar2"; const double updateRate = 30; const int horzSamples = 320; const double horzResolution = 1; @@ -538,7 +538,7 @@ void GpuLidarSensorTest::TestThreeBoxes(const std::string &_renderEngine) double expectedRangeAtMidPointBox2 = abs(box02Pose.Pos().Y()) - unitBoxSize/2; // Sensor 1 should see box01 and box02 - // ign-rendering uses lower resolution textures for lidars with low sample + // gz-rendering uses lower resolution textures for lidars with low sample // count after: https://github.com/gazebosim/gz-rendering/pull/296 // Side effect is the loss of precision in the depth buffer data so we relax // tolerance for this check in order for test to pass. @@ -584,7 +584,7 @@ void GpuLidarSensorTest::VerticalLidar(const std::string &_renderEngine) { // Create SDF describing a camera sensor const std::string name = "TestGpuLidar"; - const std::string topic = "/ignition/sensors/test/lidar"; + const std::string topic = "/gz/sensors/test/lidar"; const double updateRate = 30; const unsigned int horzSamples = 640; const double horzResolution = 1; @@ -706,8 +706,8 @@ void GpuLidarSensorTest::ManualUpdate(const std::string &_renderEngine) // Create SDF describing a gpu lidar sensors sensor const std::string name1 = "TestGpuLidar1"; const std::string name2 = "TestGpuLidar2"; - const std::string topic1 = "/ignition/sensors/test/lidar1"; - const std::string topic2 = "/ignition/sensors/test/lidar2"; + const std::string topic1 = "/gz/sensors/test/lidar1"; + const std::string topic2 = "/gz/sensors/test/lidar2"; const double updateRate = 30; const int horzSamples = 320; const double horzResolution = 1; diff --git a/test/integration/imu.cc b/test/integration/imu.cc index 75664e04..d26fc40b 100644 --- a/test/integration/imu.cc +++ b/test/integration/imu.cc @@ -72,7 +72,7 @@ TEST_F(ImuSensorTest, CreateImu) { // Create SDF describing an imu sensor const std::string name = "TestImu"; - const std::string topic = "/ignition/sensors/test/imu"; + const std::string topic = "/gz/sensors/test/imu"; const double updateRate = 30; const bool alwaysOn = 1; const bool visualize = 1; @@ -99,7 +99,7 @@ TEST_F(ImuSensorTest, SensorReadings) { // Create SDF describing an imu sensor const std::string name = "TestImu"; - const std::string topic = "/ignition/sensors/test/imu"; + const std::string topic = "/gz/sensors/test/imu"; const double updateRate = 30; const bool alwaysOn = 1; const bool visualize = 1; diff --git a/test/integration/logical_camera.cc b/test/integration/logical_camera.cc index 1597317a..744fd24f 100644 --- a/test/integration/logical_camera.cc +++ b/test/integration/logical_camera.cc @@ -101,7 +101,7 @@ TEST_F(LogicalCameraSensorTest, CreateLogicalCamera) { // Create SDF describing a logical camera sensor const std::string name = "TestLogicalCamera"; - const std::string topic = "/ignition/sensors/test/logical_camera"; + const std::string topic = "/gz/sensors/test/logical_camera"; const double updateRate = 30; const double near = 0.55; const double far = 5; @@ -138,7 +138,7 @@ TEST_F(LogicalCameraSensorTest, DetectBox) { // Create SDF describing a logical camera sensor const std::string name = "TestLogicalCamera"; - const std::string topic = "/ignition/sensors/test/logical_camera"; + const std::string topic = "/gz/sensors/test/logical_camera"; const double updateRate = 30; const double near = 0.55; const double far = 5; diff --git a/test/integration/magnetometer.cc b/test/integration/magnetometer.cc index 2e282d26..5f8a6577 100644 --- a/test/integration/magnetometer.cc +++ b/test/integration/magnetometer.cc @@ -127,8 +127,8 @@ TEST_F(MagnetometerSensorTest, CreateMagnetometer) { // Create SDF describing an magnetometer sensor const std::string name = "TestMagnetometer"; - const std::string topic = "/ignition/sensors/test/magnetometer"; - const std::string noiseTopic = "/ignition/sensors/test/magnetometer_noise"; + const std::string topic = "/gz/sensors/test/magnetometer"; + const std::string noiseTopic = "/gz/sensors/test/magnetometer_noise"; const double updateRate = 30; const bool alwaysOn = 1; const bool visualize = 1; @@ -166,8 +166,8 @@ TEST_F(MagnetometerSensorTest, SensorReadings) { // Create SDF describing an magnetometer sensor const std::string name = "TestMagnetometer"; - const std::string topic = "/ignition/sensors/test/magnetometer"; - const std::string noiseTopic = "/ignition/sensors/test/magnetometer_noise"; + const std::string topic = "/gz/sensors/test/magnetometer"; + const std::string noiseTopic = "/gz/sensors/test/magnetometer_noise"; const double updateRate = 30; const bool alwaysOn = 1; const bool visualize = 1; diff --git a/test/integration/navsat.cc b/test/integration/navsat.cc index 274d0622..7d79d273 100644 --- a/test/integration/navsat.cc +++ b/test/integration/navsat.cc @@ -143,8 +143,8 @@ TEST_F(NavSatSensorTest, CreateNavSat) { // Create SDF describing a navsat sensor const std::string name = "TestNavSat"; - const std::string topic = "/ignition/sensors/test/navsat"; - const std::string topicNoise = "/ignition/sensors/test/navsat_noise"; + const std::string topic = "/gz/sensors/test/navsat"; + const std::string topicNoise = "/gz/sensors/test/navsat_noise"; const double updateRate = 30; const bool alwaysOn = 1; const bool visualize = 1; @@ -180,8 +180,8 @@ TEST_F(NavSatSensorTest, SensorReadings) { // Create SDF describing a navsat sensor const std::string name{"TestNavSat"}; - const std::string topic{"/ignition/sensors/test/navsat"}; - const std::string topicNoise{"/ignition/sensors/test/navsat_noise"}; + const std::string topic{"/gz/sensors/test/navsat"}; + const std::string topicNoise{"/gz/sensors/test/navsat_noise"}; const double updateRate{30.0}; const bool alwaysOn{true}; const bool visualize{true}; diff --git a/test/integration/rgbd_camera.cc b/test/integration/rgbd_camera.cc index 9e8684ca..dea56ba4 100644 --- a/test/integration/rgbd_camera.cc +++ b/test/integration/rgbd_camera.cc @@ -33,7 +33,7 @@ #include #include -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) @@ -210,7 +210,7 @@ void RgbdCameraSensorTest::ImagesWithBuiltinSDF( return; } - // Setup ign-rendering with an empty scene + // Setup gz-rendering with an empty scene auto *engine = gz::rendering::engine(_renderEngine); if (!engine) { diff --git a/test/integration/segmentation_camera.cc b/test/integration/segmentation_camera.cc index 56bc117e..428f3cc4 100644 --- a/test/integration/segmentation_camera.cc +++ b/test/integration/segmentation_camera.cc @@ -202,7 +202,7 @@ void SegmentationCameraSensorTest::ImagesWithBuiltinSDF( << "' doesn't support segmentation cameras" << std::endl; return; } - // Setup ign-rendering with an empty scene + // Setup gz-rendering with an empty scene auto *engine = gz::rendering::engine(_renderEngine); if (!engine) { diff --git a/test/integration/thermal_camera.cc b/test/integration/thermal_camera.cc index dba25ba1..a9800da6 100644 --- a/test/integration/thermal_camera.cc +++ b/test/integration/thermal_camera.cc @@ -33,7 +33,7 @@ #include #include -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) @@ -143,7 +143,7 @@ void ThermalCameraSensorTest::ImagesWithBuiltinSDF( return; } - // Setup ign-rendering with an empty scene + // Setup gz-rendering with an empty scene auto *engine = gz::rendering::engine(_renderEngine); if (!engine) { @@ -257,7 +257,7 @@ void ThermalCameraSensorTest::ImagesWithBuiltinSDF( ambientTempRange); EXPECT_FLOAT_EQ(g_thermalBuffer[right], g_thermalBuffer[left]); - // temp range of visual is hardcoded in ign-rendering shaders + // temp range of visual is hardcoded in gz-rendering shaders float boxTempRange = 3.0; EXPECT_NEAR(boxTemp, g_thermalBuffer[mid] * linearResolution, boxTempRange); @@ -405,7 +405,7 @@ void ThermalCameraSensorTest::Images8BitWithBuiltinSDF( return; } - // Setup ign-rendering with an empty scene + // Setup gz-rendering with an empty scene auto *engine = gz::rendering::engine(_renderEngine); if (!engine) { diff --git a/test/integration/triggered_camera.cc b/test/integration/triggered_camera.cc index c6974597..6274eff5 100644 --- a/test/integration/triggered_camera.cc +++ b/test/integration/triggered_camera.cc @@ -22,7 +22,7 @@ #include #include -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) @@ -78,7 +78,7 @@ void TriggeredCameraTest::ImagesWithBuiltinSDF(const std::string &_renderEngine) ASSERT_TRUE(linkPtr->HasElement("sensor")); auto sensorPtr = linkPtr->GetElement("sensor"); - // Setup ign-rendering with an empty scene + // Setup gz-rendering with an empty scene auto *engine = gz::rendering::engine(_renderEngine); if (!engine) { diff --git a/test/integration/wide_angle_camera.cc b/test/integration/wide_angle_camera.cc index 9e62e29c..ece39f60 100644 --- a/test/integration/wide_angle_camera.cc +++ b/test/integration/wide_angle_camera.cc @@ -22,7 +22,7 @@ #include #include -// TODO(louise) Remove these pragmas once ign-rendering is disabling the +// TODO(louise) Remove these pragmas once gz-rendering is disabling the // warnings #ifdef _WIN32 #pragma warning(push) @@ -114,7 +114,7 @@ void WideAngleCameraSensorTest::ImagesWithBuiltinSDF( ASSERT_TRUE(linkPtr->HasElement("sensor")); auto sensorPtr = linkPtr->GetElement("sensor"); - // Setup ign-rendering with an empty scene + // Setup gz-rendering with an empty scene auto *engine = gz::rendering::engine(_renderEngine); if (!engine) { diff --git a/tutorials.md.in b/tutorials.md.in index fc40cc53..9be0a030 100644 --- a/tutorials.md.in +++ b/tutorials.md.in @@ -1,8 +1,8 @@ \page tutorials Tutorials -Welcome to the Gazebo @IGN_DESIGNATION_CAP@ tutorials. These tutorials +Welcome to the Gazebo @GZ_DESIGNATION_CAP@ tutorials. These tutorials will guide you through the process of understanding the capabilities of the -Gazebo @IGN_DESIGNATION_CAP@ library and how to use the library effectively. +Gazebo @GZ_DESIGNATION_CAP@ library and how to use the library effectively. **The tutorials** diff --git a/tutorials/install.md b/tutorials/install.md index dc3f72e8..b78642ff 100644 --- a/tutorials/install.md +++ b/tutorials/install.md @@ -20,7 +20,7 @@ sudo apt-get update ```{.sh} # Change <#> to a version number, like 3 or 4 -sudo apt install libignition-sensors<#>-dev +sudo apt install libgz-sensors<#>-dev ``` ### macOS @@ -33,7 +33,7 @@ On macOS, add OSRF packages: Install Gazebo Sensors: ``` - brew install ignition-sensors<#> + brew install gz-sensors<#> ``` Be sure to replace `<#>` with a number value, such as 5 or 6, depending on @@ -130,7 +130,7 @@ conda activate gz-ws Install Gazebo dependencies, replacing `<#>` with the desired versions: ``` -conda install libignition-cmake<#> libignition-common<#> libignition-math<#> libignition-transport<#> libignition-msgs<#> --channel conda-forge +conda install libgz-cmake<#> libgz-common<#> libgz-math<#> libgz-transport<#> libgz-msgs<#> --channel conda-forge ``` Before [gz-rendering](https://github.com/gazebosim/gz-rendering) becomes available on conda-forge, follow its tutorial to build it from source. diff --git a/tutorials/segmentation_camera.md b/tutorials/segmentation_camera.md index 08f47d67..9c7f8699 100644 --- a/tutorials/segmentation_camera.md +++ b/tutorials/segmentation_camera.md @@ -374,7 +374,7 @@ You will see 4 windows: `image`, `labels_map`, `colored_map`, and `colored_image For panoptic/instance segmentation, to parse the `labels_map`, click on any pixel on the `labels_map` window to see the `label` and `instance count` of that pixel. -## Processing the segmentation sensor via ign-transport +## Processing the segmentation sensor via gz-transport It's possible to process the segmentation data in real time via `gz-transport`. You will need to which topics to subscribe to in order to receive this information. diff --git a/tutorials/thermal_camera.md b/tutorials/thermal_camera.md index 443d6fe7..03709317 100644 --- a/tutorials/thermal_camera.md +++ b/tutorials/thermal_camera.md @@ -282,7 +282,7 @@ In the example above, the thermal cameras publish an [image message](https://git We can observe the contents of a single message from the 16-bit camera by running the following command: ``` -ign topic -e -n 1 -t /thermal_camera +gz topic -e -n 1 -t /thermal_camera ``` Here are some important things to observe from the message output: