Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove deprecations: tock #1519

Merged
merged 3 commits into from
Dec 19, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
18 changes: 18 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,24 @@ forward programmatically.
This document aims to contain similar information to those files
but with improved human-readability..

## libsdformat 15.x to 16.x

### Removals

- **sdf/config.hh**:
+ The macro `SDF_SHARE_PATH` has been removed.
Please use `sdf::getSharePath()` instead.
+ The macro `SDF_VERSION_PATH` has been removed.

- **sdf/Camera.hh**:
+ The `//sensor/camera/optical_frame_id` SDF element and corresponding functions
in the Camera DOM class are removed. Please specify camera frame using
the `//sensor/frame_id` SDF element instead.
+ ***removal:*** std::string OpticalFrameId() const
+ ***Replacement:*** std::string Sensor::FrameId() const
+ ***removal:*** void SetOpticalFrameId(const std::string &)
+ ***Replacement:*** void Sensor::SetFrameId(const std::string &)

## libsdformat 14.x to 15.x

### Additions
Expand Down
14 changes: 0 additions & 14 deletions include/sdf/Camera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -356,20 +356,6 @@ namespace sdf
/// \param[in] _frame The name of the pose relative-to frame.
public: void SetPoseRelativeTo(const std::string &_frame);

/// \brief Get the name of the coordinate frame relative to which this
/// object's camera_info message header is expressed.
/// Note: while Gazebo interprets the camera frame to be looking towards +X,
/// other tools, such as ROS interprets this frame as looking towards +Z.
/// The Camera sensor assumes that the color and depth images are captured
/// at the same frame_id.
/// \return The name of the frame this camera uses in its camera_info topic.
public: const std::string GZ_DEPRECATED(15) OpticalFrameId() const;

/// \brief Set the name of the coordinate frame relative to which this
/// object's camera_info is expressed.
/// \param[in] _frame The frame this camera uses in its camera_info topic.
public: void GZ_DEPRECATED(15) SetOpticalFrameId(const std::string &_frame);

/// \brief Get the lens type. This is the type of the lens mapping.
/// Supported values are gnomonical, stereographic, equidistant,
/// equisolid_angle, orthographic, custom. For gnomonical (perspective)
Expand Down
4 changes: 0 additions & 4 deletions include/sdf/ParserConfig.hh
Original file line number Diff line number Diff line change
Expand Up @@ -221,10 +221,6 @@ class SDFORMAT_VISIBLE ParserConfig
/// and merge the child link into the parent.
public: bool URDFPreserveFixedJoint() const;

/// \brief Set the storeResolvedURIs flag value.
/// \sa SetStoreResolvedURIs
public: GZ_DEPRECATED(15) void SetStoreResovledURIs(bool _resolveURI);

/// \brief Set the storeResolvedURIs flag value.
/// \param[in] _resolveURI True to make the parser attempt to resolve any
/// URIs found and store them. False to preserve original URIs
Expand Down
8 changes: 0 additions & 8 deletions include/sdf/config.hh.in
Original file line number Diff line number Diff line change
Expand Up @@ -47,12 +47,4 @@

#cmakedefine SDFORMAT_DISABLE_CONSOLE_LOGFILE 1

#ifndef SDF_SHARE_PATH
#define SDF_SHARE_PATH _Pragma ("GCC warning \"'SDF_SHARE_PATH' macro is deprecated, use sdf::getSharePath() function instead. \"") "${CMAKE_INSTALL_FULL_DATAROOTDIR}/"
#endif

#ifndef SDF_VERSION_PATH
#define SDF_VERSION_PATH _Pragma ("GCC warning \"'SDF_VERSION_PATH' macro is deprecated and should not be used. \"") "${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/${PROJECT_VERSION}"
#endif

#endif // #ifndef SDF_CONFIG_HH_
14 changes: 0 additions & 14 deletions python/src/sdf/pyCamera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,6 @@ namespace python
/////////////////////////////////////////////////
void defineCamera(pybind11::object module)
{
// \todo(iche033) OpticalFrameId and SetOpticalFrameId are deprecated
// Remove sdformat16
GZ_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION
pybind11::class_<sdf::Camera> cameraModule(module, "Camera");
cameraModule
.def(pybind11::init<>())
Expand Down Expand Up @@ -178,16 +175,6 @@ void defineCamera(pybind11::object module)
"Set the name of the coordinate frame relative to which this "
"object's pose is expressed. An empty value indicates that the frame "
"is relative to the parent link.")
.def("optical_frame_id", &sdf::Camera::OpticalFrameId,
"Get the name of the coordinate frame relative to which this "
"object's camera_info message header is expressed. "
"Note: while Gazebo interprets the camera frame to be looking towards "
"+X, other tools, such as ROS interprets this frame as looking "
"towards +Z. The Camera sensor assumes that the color and depth "
"images are captured at the same frame_id.")
.def("set_optical_frame_id", &sdf::Camera::SetOpticalFrameId,
"Set the name of the coordinate frame relative to which this "
"object's camera_info is expressed.")
.def("lens_type", &sdf::Camera::LensType,
"Get the lens type. This is the type of the lens mapping. "
"Supported values are gnomonical, stereographic, equidistant, "
Expand Down Expand Up @@ -300,7 +287,6 @@ void defineCamera(pybind11::object module)
.value("BAYER_GBRG8", sdf::PixelFormatType::BAYER_GBRG8)
.value("BAYER_GRBG8", sdf::PixelFormatType::BAYER_GRBG8);

GZ_UTILS_WARN_RESUME__DEPRECATED_DECLARATION
}
} // namespace python
} // namespace SDF_VERSION_NAMESPACE
Expand Down
4 changes: 0 additions & 4 deletions python/test/pyCamera_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -135,10 +135,6 @@ def test_default_construction(self):
cam.set_pose_relative_to("/frame")
self.assertEqual("/frame", cam.pose_relative_to())

self.assertFalse(cam.optical_frame_id());
cam.set_optical_frame_id("/optical_frame");
self.assertEqual("/optical_frame", cam.optical_frame_id());

self.assertEqual("stereographic", cam.lens_type())
cam.set_lens_type("custom")
self.assertEqual("custom", cam.lens_type())
Expand Down
35 changes: 1 addition & 34 deletions src/Camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -147,9 +147,6 @@ class sdf::Camera::Implementation
/// \brief Frame of the pose.
public: std::string poseRelativeTo = "";

/// \brief Frame ID the camera_info message header is expressed.
public: std::string opticalFrameId{""};

/// \brief Lens type.
public: std::string lensType{"stereographic"};

Expand Down Expand Up @@ -382,13 +379,6 @@ Errors Camera::Load(ElementPtr _sdf)
// Load the pose. Ignore the return value since the pose is optional.
loadPose(_sdf, this->dataPtr->pose, this->dataPtr->poseRelativeTo);

// Load the optional optical_frame_id value.
if (_sdf->HasElement("optical_frame_id"))
{
this->dataPtr->opticalFrameId = _sdf->Get<std::string>("optical_frame_id",
this->dataPtr->opticalFrameId).first;
}

// Load the lens values.
if (_sdf->HasElement("lens"))
{
Expand Down Expand Up @@ -752,9 +742,6 @@ void Camera::SetSaveFramesPath(const std::string &_path)
//////////////////////////////////////////////////
bool Camera::operator==(const Camera &_cam) const
{

// \todo(iche033) Remove in sdformat16
GZ_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION
return this->Name() == _cam.Name() &&
this->HorizontalFov() == _cam.HorizontalFov() &&
this->ImageWidth() == _cam.ImageWidth() &&
Expand All @@ -765,9 +752,7 @@ bool Camera::operator==(const Camera &_cam) const
this->SaveFrames() == _cam.SaveFrames() &&
this->SaveFramesPath() == _cam.SaveFramesPath() &&
this->ImageNoise() == _cam.ImageNoise() &&
this->VisibilityMask() == _cam.VisibilityMask() &&
this->OpticalFrameId() == _cam.OpticalFrameId();
GZ_UTILS_WARN_RESUME__DEPRECATED_DECLARATION
this->VisibilityMask() == _cam.VisibilityMask();
}

//////////////////////////////////////////////////
Expand Down Expand Up @@ -884,18 +869,6 @@ void Camera::SetPoseRelativeTo(const std::string &_frame)
this->dataPtr->poseRelativeTo = _frame;
}

/////////////////////////////////////////////////
const std::string Camera::OpticalFrameId() const
{
return this->dataPtr->opticalFrameId;
}

/////////////////////////////////////////////////
void Camera::SetOpticalFrameId(const std::string &_frame)
{
this->dataPtr->opticalFrameId = _frame;
}

/////////////////////////////////////////////////
std::string Camera::LensType() const
{
Expand Down Expand Up @@ -1336,11 +1309,5 @@ sdf::ElementPtr Camera::ToElement() const
this->SegmentationType());
}

// \todo(iche033) Remove in sdformat16
GZ_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION
elem->GetElement("optical_frame_id")->Set<std::string>(
this->OpticalFrameId());
GZ_UTILS_WARN_RESUME__DEPRECATED_DECLARATION

return elem;
}
17 changes: 0 additions & 17 deletions src/Camera_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -134,13 +134,6 @@ TEST(DOMCamera, Construction)
cam.SetPoseRelativeTo("/frame");
EXPECT_EQ("/frame", cam.PoseRelativeTo());

// \todo(iche033) Remove in sdformat16
GZ_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION
EXPECT_TRUE(cam.OpticalFrameId().empty());
cam.SetOpticalFrameId("/optical_frame");
EXPECT_EQ("/optical_frame", cam.OpticalFrameId());
GZ_UTILS_WARN_RESUME__DEPRECATED_DECLARATION

EXPECT_EQ("stereographic", cam.LensType());
cam.SetLensType("custom");
EXPECT_EQ("custom", cam.LensType());
Expand Down Expand Up @@ -277,11 +270,6 @@ TEST(DOMCamera, ToElement)
cam.SetSaveFrames(true);
cam.SetSaveFramesPath("/tmp");

// \todo(iche033) Remove in sdformat16
GZ_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION
cam.SetOpticalFrameId("/optical_frame");
GZ_UTILS_WARN_RESUME__DEPRECATED_DECLARATION

cam.SetCameraInfoTopic("/camera_info_test");
cam.SetTriggerTopic("/trigger_topic_test");
cam.SetTriggered(true);
Expand All @@ -305,11 +293,6 @@ TEST(DOMCamera, ToElement)
EXPECT_TRUE(cam2.SaveFrames());
EXPECT_EQ("/tmp", cam2.SaveFramesPath());

// \todo(iche033) Remove in sdformat16
GZ_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION
EXPECT_EQ("/optical_frame", cam2.OpticalFrameId());
GZ_UTILS_WARN_RESUME__DEPRECATED_DECLARATION

EXPECT_EQ("/camera_info_test", cam2.CameraInfoTopic());
EXPECT_EQ("/trigger_topic_test", cam2.TriggerTopic());
EXPECT_TRUE(cam2.Triggered());
Expand Down
6 changes: 0 additions & 6 deletions src/ParserConfig.cc
Original file line number Diff line number Diff line change
Expand Up @@ -218,12 +218,6 @@ bool ParserConfig::URDFPreserveFixedJoint() const
return this->dataPtr->preserveFixedJoint;
}

/////////////////////////////////////////////////
void ParserConfig::SetStoreResovledURIs(bool _resolveURI)
{
this->SetStoreResolvedURIs(_resolveURI);
}

/////////////////////////////////////////////////
void ParserConfig::SetStoreResolvedURIs(bool _resolveURI)
{
Expand Down
Loading