Skip to content

Commit

Permalink
Merge branch 'main' into scpeters/state_1_12_suffix
Browse files Browse the repository at this point in the history
  • Loading branch information
scpeters authored Jul 8, 2024
2 parents f84706e + dcd0964 commit e577e15
Show file tree
Hide file tree
Showing 12 changed files with 100 additions and 4 deletions.
12 changes: 12 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,18 @@ but with improved human-readability..
matches `"0"`, `"1"`, `"true"`, or `"false"` and returns `false`
otherwise.

### Deprecations

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


## libsdformat 13.x to 14.x

### Additions
Expand Down
4 changes: 2 additions & 2 deletions include/sdf/Camera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -363,12 +363,12 @@ namespace sdf
/// 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 OpticalFrameId() const;
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 SetOpticalFrameId(const std::string &_frame);
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,
Expand Down
8 changes: 8 additions & 0 deletions include/sdf/Sensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -160,6 +160,14 @@ namespace sdf
/// \param[in] _name Name of the sensor.
public: void SetName(const std::string &_name);

/// \brief Get the frame ID of the sensor.
/// \return Sensor frame ID.
public: std::string FrameId() const;

/// \brief Set the frame ID of the sensor.
/// \param[in] _frameId Frame ID to set.
public: void SetFrameId(const std::string &_frameId);

/// \brief Get the topic on which sensor data should be published.
/// \return Topic for this sensor's data.
public: std::string Topic() const;
Expand Down
5 changes: 5 additions & 0 deletions python/src/sdf/pyCamera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,9 @@ 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 @@ -296,6 +299,8 @@ void defineCamera(pybind11::object module)
.value("BAYER_BGGR8", sdf::PixelFormatType::BAYER_BGGR8)
.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: 4 additions & 0 deletions python/src/sdf/pySensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,10 @@ void defineSensor(pybind11::object module)
"Get the name of the sensor.")
.def("set_name", &sdf::Sensor::SetName,
"Set the name of the sensor.")
.def("frame_id", &sdf::Sensor::FrameId,
"Get the frame id of the sensor.")
.def("set_frame_id", &sdf::Sensor::SetFrameId,
"Set the frame id of the sensor.")
.def("topic", &sdf::Sensor::Topic,
"Get the topic on which sensor data should be published.")
.def("set_topic", &sdf::Sensor::SetTopic,
Expand Down
7 changes: 7 additions & 0 deletions python/test/pySensor_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -60,12 +60,14 @@ def test_default_construction(self):

self.assertAlmostEqual(0.0, sensor.update_rate())

self.assertFalse(sensor.frame_id())
self.assertFalse(sensor.topic())
self.assertFalse(sensor == sensor2)
self.assertTrue(sensor != sensor2)

def test_copy_construction(self):
sensor = Sensor()
sensor.set_frame_id("test_frame_id")
sensor.set_raw_pose(Pose3d(1, 2, 3, 0, 0, 0))
sensor.set_type(sdf.Sensortype.MAGNETOMETER)
sensor.set_pose_relative_to("a_frame")
Expand All @@ -79,13 +81,15 @@ def test_copy_construction(self):

sensor2 = Sensor(sensor)

self.assertEqual("test_frame_id", sensor.frame_id())
self.assertEqual(sdf.Sensortype.MAGNETOMETER, sensor.type())
self.assertEqual(Pose3d(1, 2, 3, 0, 0, 0), sensor.raw_pose())
self.assertEqual("a_frame", sensor.pose_relative_to())
self.assertTrue(None != sensor.magnetometer_sensor())
self.assertAlmostEqual(mag.x_noise().mean(),
sensor.magnetometer_sensor().x_noise().mean())

self.assertEqual("test_frame_id", sensor2.frame_id())
self.assertEqual(sdf.Sensortype.MAGNETOMETER, sensor2.type())
self.assertEqual(Pose3d(1, 2, 3, 0, 0, 0), sensor2.raw_pose())
self.assertEqual("a_frame", sensor2.pose_relative_to())
Expand All @@ -96,6 +100,7 @@ def test_copy_construction(self):

def test_deepcopy(self):
sensor = Sensor()
sensor.set_frame_id("test_frame_id")
sensor.set_raw_pose(Pose3d(1, 2, 3, 0, 0, 0))
sensor.set_type(sdf.Sensortype.MAGNETOMETER)
sensor.set_pose_relative_to("a_frame")
Expand All @@ -108,13 +113,15 @@ def test_deepcopy(self):

sensor2 = copy.deepcopy(sensor)

self.assertEqual("test_frame_id", sensor.frame_id())
self.assertEqual(sdf.Sensortype.MAGNETOMETER, sensor.type())
self.assertEqual(Pose3d(1, 2, 3, 0, 0, 0), sensor.raw_pose())
self.assertEqual("a_frame", sensor.pose_relative_to())
self.assertTrue(None != sensor.magnetometer_sensor())
self.assertAlmostEqual(mag.x_noise().mean(),
sensor.magnetometer_sensor().x_noise().mean())

self.assertEqual("test_frame_id", sensor2.frame_id())
self.assertEqual(sdf.Sensortype.MAGNETOMETER, sensor2.type())
self.assertEqual(Pose3d(1, 2, 3, 0, 0, 0), sensor2.raw_pose())
self.assertEqual("a_frame", sensor2.pose_relative_to())
Expand Down
2 changes: 1 addition & 1 deletion sdf/1.12/camera.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -222,7 +222,7 @@
<description><![CDATA[Visibility mask of a camera. When (camera's visibility_mask & visual's visibility_flags) evaluates to non-zero, the visual will be visible to the camera.]]></description>
</element>

<element name="optical_frame_id" type="string" default="" required="0">
<element name="optical_frame_id" type="string" default="" required="-1">
<description>An optional frame id name to be used in the camera_info message header.</description>
</element>

Expand Down
4 changes: 4 additions & 0 deletions sdf/1.12/sensor.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,10 @@
<description>If true, the sensor will publish performance metrics</description>
</element>

<element name="frame_id" type="string" default="" required="0">
<description>An optional frame id which indicates the sensor's frame of reference.</description>
</element>

<include filename="pose.sdf" required="0"/>
<include filename="plugin.sdf" required="*"/>
<include filename="air_pressure.sdf" required="0"/>
Expand Down
7 changes: 7 additions & 0 deletions src/Camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -752,6 +752,9 @@ 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 @@ -764,6 +767,7 @@ bool Camera::operator==(const Camera &_cam) const
this->ImageNoise() == _cam.ImageNoise() &&
this->VisibilityMask() == _cam.VisibilityMask() &&
this->OpticalFrameId() == _cam.OpticalFrameId();
GZ_UTILS_WARN_RESUME__DEPRECATED_DECLARATION
}

//////////////////////////////////////////////////
Expand Down Expand Up @@ -1332,8 +1336,11 @@ 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;
}
13 changes: 13 additions & 0 deletions src/Camera_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -134,9 +134,12 @@ 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");
Expand Down Expand Up @@ -273,7 +276,12 @@ TEST(DOMCamera, ToElement)
cam.SetPoseRelativeTo("/frame");
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 @@ -296,7 +304,12 @@ TEST(DOMCamera, ToElement)
EXPECT_EQ("/frame", cam2.PoseRelativeTo());
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
19 changes: 18 additions & 1 deletion src/Sensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,9 @@ class sdf::Sensor::Implementation
/// \brief Name of the sensor.
public: std::string name = "";

/// \brief Sensor frame ID
public: std::string frameId{""};

/// \brief Sensor data topic.
public: std::string topic = "";

Expand Down Expand Up @@ -243,7 +246,8 @@ Errors Sensor::Load(ElementPtr _sdf)
"The supplied sensor name [" + this->dataPtr->name +
"] is reserved."});
}

this->dataPtr->frameId = _sdf->Get<std::string>("frame_id",
this->dataPtr->frameId).first;
this->dataPtr->updateRate = _sdf->Get<double>("update_rate",
this->dataPtr->updateRate).first;
this->dataPtr->topic = _sdf->Get<std::string>("topic");
Expand Down Expand Up @@ -439,6 +443,18 @@ void Sensor::SetName(const std::string &_name)
this->dataPtr->name = _name;
}

/////////////////////////////////////////////////
std::string Sensor::FrameId() const
{
return this->dataPtr->frameId;
}

/////////////////////////////////////////////////
void Sensor::SetFrameId(const std::string &_frameId)
{
this->dataPtr->frameId = _frameId;
}

/////////////////////////////////////////////////
std::string Sensor::Topic() const
{
Expand Down Expand Up @@ -750,6 +766,7 @@ sdf::ElementPtr Sensor::ToElement(sdf::Errors &_errors) const
}
poseElem->Set<gz::math::Pose3d>(this->RawPose());

elem->GetElement("frame_id")->Set<std::string>(this->FrameId());
elem->GetElement("topic")->Set<std::string>(this->Topic());
elem->GetElement("update_rate")->Set<double>(this->UpdateRate());
elem->GetElement("enable_metrics")->Set<double>(this->EnableMetrics());
Expand Down
Loading

0 comments on commit e577e15

Please sign in to comment.