Skip to content

Commit

Permalink
ign -> gz Upstream Macro Migration : gz-sensors (#232)
Browse files Browse the repository at this point in the history
  • Loading branch information
methylDragon authored Jun 18, 2022
1 parent eb58297 commit b28c237
Show file tree
Hide file tree
Showing 61 changed files with 186 additions and 172 deletions.
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,9 @@ set (DRI_TESTS TRUE CACHE BOOL "True to enable DRI tests")
option(ENABLE_PROFILER "Enable Gazebo Profiler" FALSE)

if(ENABLE_PROFILER)
add_definitions("-DIGN_PROFILER_ENABLE=1")
add_definitions("-DGZ_PROFILER_ENABLE=1")
else()
add_definitions("-DIGN_PROFILER_ENABLE=0")
add_definitions("-DGZ_PROFILER_ENABLE=0")
endif()

#============================================================================
Expand Down
2 changes: 1 addition & 1 deletion Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -371,7 +371,7 @@

### Gazebo Sensors 2.5.0

1. Add `IGN_PROFILER_ENABLE` cmake option for enabling the ign-common profiler.
1. Add `GZ_PROFILER_ENABLE` cmake option for enabling the ign-common profiler.
* [BitBucket pull request 82](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-sensors/pull-requests/82)

1. Deduplicate `frame_ids` from sensor message headers
Expand Down
5 changes: 4 additions & 1 deletion Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,10 @@ release will remove the deprecated code.
1. The `ignition` namespace is deprecated and will be removed in future versions. Use `gz` instead.

1. Header files under `ignition/...` are deprecated and will be removed in future versions.
Use `gz/...` instead.
Use `gz/...` instead.

1. The `ignition:type` SDF attribute is deprecated and will be removed.
Please use `gz:type` instead.

1. **CameraSensor**: the default anti-aliasing value has changed from `2` to `4`.

Expand Down
6 changes: 3 additions & 3 deletions examples/imu_noise/main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -34,13 +34,13 @@ static constexpr double kNumSamples = 6 * 3600 * kSampleFrequency;
// These values come from the Rotors default values:
// https://github.com/ethz-asl/rotors_simulator/blob/513bb92da0c1a0c968bdc679dffc8fe7d77de918/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_imu_plugin.h#L40
static constexpr double kDefaultAdisGyroscopeNoiseDensity =
2.0 * 35.0 / 3600.0 / 180.0 * IGN_PI;
2.0 * 35.0 / 3600.0 / 180.0 * GZ_PI;
static constexpr double kDefaultAdisGyroscopeRandomWalk =
2.0 * 4.0 / 3600.0 / 180.0 * IGN_PI;
2.0 * 4.0 / 3600.0 / 180.0 * GZ_PI;
static constexpr double kDefaultAdisGyroscopeBiasCorrelationTime =
1.0e+3;
static constexpr double kDefaultAdisGyroscopeTurnOnBiasSigma =
0.5 / 180.0 * IGN_PI;
0.5 / 180.0 * GZ_PI;
static constexpr double kDefaultAdisAccelerometerNoiseDensity =
2.0 * 2.0e-3;
static constexpr double kDefaultAdisAccelerometerRandomWalk =
Expand Down
2 changes: 1 addition & 1 deletion examples/loop_sensor/sensors.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
</vertical_velocity>
</altimeter>
</sensor>
<sensor name="custom_odometer" type="custom" ignition:type="odometer">
<sensor name="custom_odometer" type="custom" gz:type="odometer">
<always_on>1</always_on>
<update_rate>30</update_rate>
<topic>odometer</topic>
Expand Down
4 changes: 2 additions & 2 deletions examples/save_image/main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ int main()
const double hz = 30;
const std::size_t width = 480;
const std::size_t height = 320;
const std::size_t hfov = IGN_DTOR(60);
const std::size_t hfov = GZ_DTOR(60);
const double near = 0.1;
const double far = 100;
const auto format = sdf::PixelFormatType::RGB_INT8;
Expand Down Expand Up @@ -202,7 +202,7 @@ void BuildScene(gz::rendering::ScenePtr _scene)
box->AddGeometry(_scene->CreateBox());
box->SetOrigin(0.0, 0.5, 0.0);
box->SetLocalPosition(3, 0, 0);
box->SetLocalRotation(IGN_PI / 4, 0, IGN_PI / 3);
box->SetLocalRotation(GZ_PI / 4, 0, GZ_PI / 3);
box->SetLocalScale(1, 2.5, 1);
box->SetMaterial(blue);
root->AddChild(box);
Expand Down
4 changes: 2 additions & 2 deletions include/gz/sensors/AirPressureSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -85,11 +85,11 @@ namespace gz
/// \todo(iche033) Make this function virtual on Garden
public: bool HasConnections() const;

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<AirPressureSensorPrivate> dataPtr;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
4 changes: 2 additions & 2 deletions include/gz/sensors/AltimeterSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -102,11 +102,11 @@ namespace gz
/// \todo(iche033) Make this function virtual on Garden
public: bool HasConnections() const;

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<AltimeterSensorPrivate> dataPtr;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
2 changes: 1 addition & 1 deletion include/gz/sensors/BrownDistortionModel.hh
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ namespace gz
public: virtual void Print(std::ostream &_out) const override;

/// \brief Private data pointer.
IGN_UTILS_IMPL_PTR(dataPtr)
GZ_UTILS_IMPL_PTR(dataPtr)
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/gz/sensors/CameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ namespace gz

/// \brief Camera Sensor Class
///
/// This class creates images from an ignition rendering scene. The scene
/// 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
/// to access the image data. The API works by setting a callback to be
Expand Down Expand Up @@ -175,11 +175,11 @@ namespace gz
/// \param[in] _scene Pointer to the new scene.
private: void OnSceneChange(gz::rendering::ScenePtr /*_scene*/);

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<CameraSensorPrivate> dataPtr;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/gz/sensors/DepthCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ namespace gz

/// \brief Depth camera sensor class.
///
/// This class creates depth image from an ignition rendering scene.
/// 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
/// to access the image data. The API works by setting a callback to be
Expand Down Expand Up @@ -171,11 +171,11 @@ namespace gz
private: void OnSceneChange(gz::rendering::ScenePtr /*_scene*/)
{ }

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<DepthCameraSensorPrivate> dataPtr;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
2 changes: 1 addition & 1 deletion include/gz/sensors/Distortion.hh
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ namespace gz
public: virtual void Print(std::ostream &_out) const;

/// \brief Private data pointer
IGN_UTILS_IMPL_PTR(dataPtr)
GZ_UTILS_IMPL_PTR(dataPtr)
};
}
}
Expand Down
4 changes: 2 additions & 2 deletions include/gz/sensors/ForceTorqueSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -120,11 +120,11 @@ namespace gz
/// \todo(iche033) Make this function virtual on Garden
public: bool HasConnections() const;

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<ForceTorqueSensorPrivate> dataPtr;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
4 changes: 2 additions & 2 deletions include/gz/sensors/GpuLidarSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -139,11 +139,11 @@ namespace gz
unsigned int _heighti, unsigned int _channels,
const std::string &_format);

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<GpuLidarSensorPrivate> dataPtr;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
4 changes: 2 additions & 2 deletions include/gz/sensors/ImuSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -171,11 +171,11 @@ namespace gz
/// \todo(iche033) Make this function virtual on Garden
public: bool HasConnections() const;

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<ImuSensorPrivate> dataPtr;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
8 changes: 4 additions & 4 deletions include/gz/sensors/Lidar.hh
Original file line number Diff line number Diff line change
Expand Up @@ -245,10 +245,10 @@ namespace gz
/// \return Visibility mask
public: uint32_t VisibilityMask() const;

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Just a mutex for thread safety
public: mutable std::mutex lidarMutex;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING

/// \brief Raw buffer of laser data.
public: float *laserBuffer = nullptr;
Expand All @@ -268,11 +268,11 @@ namespace gz
unsigned int _heighti, unsigned int _channels,
const std::string &/*_format*/)> _subscriber);

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<LidarPrivate> dataPtr;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
4 changes: 2 additions & 2 deletions include/gz/sensors/LogicalCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -118,11 +118,11 @@ namespace gz
/// \return List of detected models.
public: msgs::LogicalCameraImage Image() const;

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<LogicalCameraSensorPrivate> dataPtr;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
4 changes: 2 additions & 2 deletions include/gz/sensors/MagnetometerSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -98,11 +98,11 @@ namespace gz
/// \todo(iche033) Make this function virtual on Garden
public: bool HasConnections() const;

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<MagnetometerSensorPrivate> dataPtr;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
4 changes: 2 additions & 2 deletions include/gz/sensors/Manager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -139,10 +139,10 @@ namespace gz
/// \brief Adds colon delimited paths sensor plugins may be
public: void GZ_DEPRECATED(6) AddPluginPaths(const std::string &_path);

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief private data pointer
private: std::unique_ptr<ManagerPrivate> dataPtr;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
4 changes: 2 additions & 2 deletions include/gz/sensors/NavSatSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -120,11 +120,11 @@ namespace gz
public: void SetPosition(const math::Angle &_latitude,
const math::Angle &_longitude, double _altitude = 0.0);

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<NavSatPrivate> dataPtr;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
4 changes: 2 additions & 2 deletions include/gz/sensors/RenderingEvents.hh
Original file line number Diff line number Diff line change
Expand Up @@ -55,12 +55,12 @@ namespace gz
std::function<void(const gz::rendering::ScenePtr &)>
_callback);

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Event that is used to trigger callbacks when the scene
/// is changed
public: static gz::common::EventT<
void(const gz::rendering::ScenePtr &)> sceneEvent;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/gz/sensors/RenderingSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ namespace gz
/// \brief a rendering sensor class
///
/// This class is a base for all rendering sensor classes. It provides
/// interface to ignition rendering objects
/// interface to Gazebo Rendering objects
class GZ_SENSORS_RENDERING_VISIBLE RenderingSensor
: public Sensor
{
Expand Down Expand Up @@ -86,11 +86,11 @@ namespace gz
/// \param[in] _sensor Sensor to add.
protected: void AddSensor(rendering::SensorPtr _sensor);

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \internal
/// \brief Data pointer for private data
private: std::unique_ptr<RenderingSensorPrivate> dataPtr;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
8 changes: 4 additions & 4 deletions include/gz/sensors/RgbdCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,8 @@ namespace gz

/// \brief RGBD camera sensor class.
///
/// This class creates a few types of sensor data from an ignition
/// rendering scene:
/// This class creates a few types of sensor data from a Gazebo
/// Rendering scene:
/// * RGB image (same as CameraSensor)
/// * Depth image (same as DepthCamera)
/// * (future / todo) Color point cloud
Expand Down Expand Up @@ -99,11 +99,11 @@ namespace gz
/// \return True on success.
private: bool CreateCameras();

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<RgbdCameraSensorPrivate> dataPtr;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/gz/sensors/SegmentationCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ namespace gz

/// \brief Segmentation camera sensor class.
///
/// This class creates segmentation images from an ignition rendering scene.
/// 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
/// to access the image data. The API works by setting a callback to be
Expand Down Expand Up @@ -126,11 +126,11 @@ namespace gz
/// \return True on success.
private: bool CreateCamera();

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<SegmentationCameraSensorPrivate> dataPtr;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
4 changes: 2 additions & 2 deletions include/gz/sensors/Sensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -227,11 +227,11 @@ namespace gz
/// \sa IsActive
public: void SetActive(bool _active);

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \internal
/// \brief Data pointer for private data
private: std::unique_ptr<SensorPrivate> dataPtr;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
Loading

0 comments on commit b28c237

Please sign in to comment.