Skip to content

Commit

Permalink
Remove deprecations (#365)
Browse files Browse the repository at this point in the history
Remove functions that were deprecated in gz-sensors7. Also remove ignition headers.

---------

Signed-off-by: Addisu Z. Taddese <[email protected]>
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
Co-authored-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
azeey and ahcorde committed Jul 25, 2023
1 parent 51ac448 commit a516493
Show file tree
Hide file tree
Showing 58 changed files with 11 additions and 1,190 deletions.
1 change: 0 additions & 1 deletion include/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,2 +1 @@
add_subdirectory(gz)
install(DIRECTORY ignition DESTINATION ${GZ_INCLUDE_INSTALL_DIR_FULL})
48 changes: 0 additions & 48 deletions include/gz/sensors/Manager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -89,51 +89,6 @@ namespace gz
return result;
}

/// \brief Create a sensor from SDF without a known sensor type.
///
/// This creates sensors by looking at the given sdf element.
/// Sensors created with this API offer an 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.
///
/// A `<sensor>` tag may have multiple `<plugin>` tags. A SensorId will
/// be returned for each plugin that is described in SDF.
/// If there are no `<plugin>` tags then one of the plugins shipped with
/// this library will be loaded. For example, a `<sensor>` tag with
/// `<camera>` but no `<plugin>` will load a CameraSensor from
/// gz-sensors-camera.
/// \sa Sensor()
/// \param[in] _sdf pointer to the sdf element
/// \return A sensor id that refers to the created sensor. NO_SENSOR
/// is returned on erro.
/// \deprecated Sensor registration is deprecated, so it's necessary to
/// provide the specific sensor type to create it. Use the templated
/// `CreateSensor` function.
public: gz::sensors::SensorId GZ_DEPRECATED(6) CreateSensor(
sdf::ElementPtr _sdf);

/// \brief Create a sensor from SDF without a known sensor type.
///
/// This creates sensors by looking at the given sdf element.
/// Sensors created with this API offer an 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.
///
/// A `<sensor>` tag may have multiple `<plugin>` tags. A SensorId will
/// be returned for each plugin that is described in SDF.
/// If there are no `<plugin>` tags then one of the plugins shipped with
/// this library will be loaded. For example, a `<sensor>` tag with
/// `<camera>` but no `<plugin>` will load a CameraSensor from
/// gz-sensors-camera.
/// \sa Sensor()
/// \param[in] _sdf SDF sensor DOM object
/// \return A sensor id that refers to the created sensor. NO_SENSOR
/// is returned on erro.
/// \deprecated Sensor registration is deprecated, so it's necessary to
/// provide the specific sensor type to create it. Use the templated
/// `CreateSensor` function.
public: gz::sensors::SensorId GZ_DEPRECATED(6) CreateSensor(
const sdf::Sensor &_sdf);

/// \brief Add a sensor for this manager to manage.
/// \sa Sensor()
Expand All @@ -160,9 +115,6 @@ namespace gz
public: void RunOnce(const std::chrono::steady_clock::duration &_time,
bool _force = false);

/// \brief Adds colon delimited paths sensor plugins may be
public: void GZ_DEPRECATED(6) AddPluginPaths(const std::string &_path);

GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief private data pointer
private: std::unique_ptr<ManagerPrivate> dataPtr;
Expand Down
64 changes: 0 additions & 64 deletions include/gz/sensors/SensorFactory.hh
Original file line number Diff line number Diff line change
Expand Up @@ -39,30 +39,6 @@ namespace gz
// forward declaration
class SensorFactoryPrivate;

/// \brief Base sensor plugin interface
/// \deprecated Sensor plugins are deprecated. Instantiate sensor objects
/// instead.
class GZ_SENSORS_VISIBLE SensorPlugin
{
/// \brief Instantiate new sensor
/// \return New sensor
public: virtual Sensor GZ_DEPRECATED(6) * New() = 0;
};

/// \brief Templated class for instantiating sensors of the specified type
/// \tparam Type of sensor being instantiated.
/// \deprecated Sensor plugins are deprecated. Instantiate sensor objects
/// instead.
template<class SensorType>
class SensorTypePlugin : public SensorPlugin
{
// Documentation inherited
public: SensorType GZ_DEPRECATED(6) * New() override
{
return new SensorType();
};
};

/// \brief A factory class for creating sensors
/// This class instantiates sensor objects based on the sensor type and
/// makes sure they're initialized correctly.
Expand Down Expand Up @@ -162,46 +138,6 @@ namespace gz
return sensor;
}

/// \brief Create a sensor from SDF without a known sensor type.
///
/// This creates sensors by looking at the given sdf element.
/// Sensors created with this API offer an 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.
///
/// \sa Sensor()
/// \param[in] _sdf pointer to the sdf element
/// \return Null, as the function is deprecated.
/// \deprecated Sensor registration is deprecated, so it's necessary to
/// provide the specific sensor type to create it. Use the templated
/// `CreateSensor` function.
public: std::unique_ptr<Sensor> GZ_DEPRECATED(6) CreateSensor(
sdf::ElementPtr _sdf);

/// \brief Create a sensor from an SDF Sensor DOM object without a known
/// sensor type.
///
/// This creates sensors by looking at the given SDF Sensor DOM
/// object.
/// 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.
///
/// \sa Sensor()
/// \param[in] _sdf SDF Sensor DOM object.
/// \return A sensor id that refers to the created sensor. Null is
/// is returned on error.
/// \deprecated Sensor registration is deprecated, so it's necessary to
/// provide the specific sensor type to create it. Use the templated
/// `CreateSensor` function.
public: std::unique_ptr<Sensor> GZ_DEPRECATED(6) CreateSensor(
const sdf::Sensor &_sdf);

/// \brief Add additional path to search for sensor plugins
/// \param[in] _path Search path
/// \deprecated Sensor plugins aren't supported anymore.
public: void GZ_DEPRECATED(6) AddPluginPaths(const std::string &_path);

GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief private data pointer
private: std::unique_ptr<SensorFactoryPrivate> dataPtr;
Expand Down
19 changes: 0 additions & 19 deletions include/ignition/sensors.hh

This file was deleted.

19 changes: 0 additions & 19 deletions include/ignition/sensors/AirPressureSensor.hh

This file was deleted.

19 changes: 0 additions & 19 deletions include/ignition/sensors/AltimeterSensor.hh

This file was deleted.

19 changes: 0 additions & 19 deletions include/ignition/sensors/BoundingBoxCameraSensor.hh

This file was deleted.

19 changes: 0 additions & 19 deletions include/ignition/sensors/BrownDistortionModel.hh

This file was deleted.

19 changes: 0 additions & 19 deletions include/ignition/sensors/CameraSensor.hh

This file was deleted.

19 changes: 0 additions & 19 deletions include/ignition/sensors/DepthCameraSensor.hh

This file was deleted.

19 changes: 0 additions & 19 deletions include/ignition/sensors/Distortion.hh

This file was deleted.

19 changes: 0 additions & 19 deletions include/ignition/sensors/Export.hh

This file was deleted.

19 changes: 0 additions & 19 deletions include/ignition/sensors/ForceTorqueSensor.hh

This file was deleted.

19 changes: 0 additions & 19 deletions include/ignition/sensors/GaussianNoiseModel.hh

This file was deleted.

19 changes: 0 additions & 19 deletions include/ignition/sensors/GpuLidarSensor.hh

This file was deleted.

Loading

0 comments on commit a516493

Please sign in to comment.