Skip to content

Commit

Permalink
Merge pull request #1199 from gazebosim/ahcorde/sdf9_to_sdf12_15_11_2022
Browse files Browse the repository at this point in the history
sdf9 to sdf12
  • Loading branch information
scpeters authored Nov 16, 2022
2 parents 3bd64ee + c6282bd commit 2dca585
Show file tree
Hide file tree
Showing 9 changed files with 64 additions and 0 deletions.
8 changes: 8 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -1058,6 +1058,14 @@

## libsdformat 9.X

### libsdformat 9.9.1 (2022-11-08)

1. Fix static URDF models with fixed joints
* [Pull request #1193](https://github.com/gazebosim/sdformat/pull/1193)

1. Don't assume `CMAKE_INSTALL_*DIR` variables are relative
* [Pull request #1190](https://github.com/gazebosim/sdformat/pull/1190)

### libsdformat 9.9.0 (2022-09-07)

1. sdf/camera.sdf: fields for projection matrix
Expand Down
8 changes: 8 additions & 0 deletions include/sdf/Camera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,14 @@ namespace sdf
/// an error code and message. An empty vector indicates no error.
public: Errors Load(ElementPtr _sdf);

/// \brief Get the camera info topic
/// \return Topic for the camera info
public: std::string CameraInfoTopic() const;

/// \brief Set the camera info topic
/// \param[in] _cameraInfoTopic Topic for the camera info.
public: void SetCameraInfoTopic(const std::string& _cameraInfoTopic);

/// \brief Get a pointer to the SDF element that was used during
/// load.
/// \return SDF element pointer. The value will be nullptr if Load has
Expand Down
4 changes: 4 additions & 0 deletions sdf/1.7/camera.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,10 @@
<description>An optional name for the camera.</description>
</attribute>

<element name="camera_info_topic" type="string" default="camera_info" required="0">
<description>Name of the camera info</description>
</element> <!-- End camera Info topic -->

<element name="horizontal_fov" type="double" default="1.047" min="0.1" max="6.283186" required="1">
<description>Horizontal field of view</description>
</element> <!-- End Horizontal_FOV -->
Expand Down
4 changes: 4 additions & 0 deletions sdf/1.8/camera.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,10 @@
<description>An optional name for the camera.</description>
</attribute>

<element name="camera_info_topic" type="string" default="camera_info" required="0">
<description>Name of the camera info</description>
</element> <!-- End camera Info topic -->

<element name="horizontal_fov" type="double" default="1.047" min="0.1" max="6.283186" required="1">
<description>Horizontal field of view</description>
</element> <!-- End Horizontal_FOV -->
Expand Down
4 changes: 4 additions & 0 deletions sdf/1.9/camera.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,10 @@
<description>An optional name for the camera.</description>
</attribute>

<element name="camera_info_topic" type="string" default="camera_info" required="0">
<description>Name of the camera info</description>
</element> <!-- End camera Info topic -->

<element name="triggered" type="bool" default="false" required="0">
<description>If the camera will be triggered by a topic</description>
</element> <!-- End Triggered -->
Expand Down
24 changes: 24 additions & 0 deletions src/Camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,9 @@ class sdf::Camera::Implementation
/// \brief The SDF element pointer used during load.
public: sdf::ElementPtr sdf;

/// \brief Camera info topic.
public: std::string cameraInfoTopic = "";

/// \brief Name of the camera.
public: std::string name = "";

Expand Down Expand Up @@ -252,6 +255,9 @@ Errors Camera::Load(ElementPtr _sdf)
this->dataPtr->triggerTopic = _sdf->Get<std::string>("trigger_topic",
this->dataPtr->triggerTopic).first;

this->dataPtr->cameraInfoTopic = _sdf->Get<std::string>("camera_info_topic",
this->dataPtr->cameraInfoTopic).first;

this->dataPtr->hfov = _sdf->Get<ignition::math::Angle>("horizontal_fov",
this->dataPtr->hfov).first;

Expand Down Expand Up @@ -448,6 +454,18 @@ Errors Camera::Load(ElementPtr _sdf)
return errors;
}

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

/////////////////////////////////////////////////
void Camera::SetCameraInfoTopic(const std::string &_cameraInfoTopic)
{
this->dataPtr->cameraInfoTopic = _cameraInfoTopic;
}

/////////////////////////////////////////////////
sdf::ElementPtr Camera::Element() const
{
Expand Down Expand Up @@ -1194,6 +1212,12 @@ sdf::ElementPtr Camera::ToElement() const
imageElem->GetElement("format")->Set<std::string>(this->PixelFormatStr());
imageElem->GetElement("anti_aliasing")->Set<uint32_t>(
this->AntiAliasingValue());
elem->GetElement("camera_info_topic")->Set<std::string>(
this->CameraInfoTopic());
elem->GetElement("trigger_topic")->Set<std::string>(
this->TriggerTopic());
elem->GetElement("triggered")->Set<bool>(
this->Triggered());

sdf::ElementPtr clipElem = elem->GetElement("clip");
clipElem->GetElement("near")->Set<double>(this->NearClip());
Expand Down
10 changes: 10 additions & 0 deletions src/Camera_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,10 @@ TEST(DOMCamera, Construction)
cam.SetTriggerTopic("my_camera/trigger");
EXPECT_EQ("my_camera/trigger", cam.TriggerTopic());

EXPECT_EQ("", cam.CameraInfoTopic());
cam.SetCameraInfoTopic("/camera/camera_info");
EXPECT_EQ("/camera/camera_info", cam.CameraInfoTopic());

EXPECT_DOUBLE_EQ(1.047, cam.HorizontalFov().Radian());
cam.SetHorizontalFov(1.45);
EXPECT_DOUBLE_EQ(1.45, cam.HorizontalFov().Radian());
Expand Down Expand Up @@ -269,6 +273,9 @@ TEST(DOMCamera, ToElement)
cam.SetSaveFrames(true);
cam.SetSaveFramesPath("/tmp");
cam.SetOpticalFrameId("/optical_frame");
cam.SetCameraInfoTopic("/camera_info_test");
cam.SetTriggerTopic("/trigger_topic_test");
cam.SetTriggered(true);

sdf::ElementPtr camElem = cam.ToElement();
EXPECT_NE(nullptr, camElem);
Expand All @@ -289,6 +296,9 @@ TEST(DOMCamera, ToElement)
EXPECT_TRUE(cam2.SaveFrames());
EXPECT_EQ("/tmp", cam2.SaveFramesPath());
EXPECT_EQ("/optical_frame", cam2.OpticalFrameId());
EXPECT_EQ("/camera_info_test", cam2.CameraInfoTopic());
EXPECT_EQ("/trigger_topic_test", cam2.TriggerTopic());
EXPECT_TRUE(cam2.Triggered());

// make changes to DOM and verify ToElement produces updated values
cam2.SetNearClip(0.33);
Expand Down
1 change: 1 addition & 0 deletions test/integration/link_dom.cc
Original file line number Diff line number Diff line change
Expand Up @@ -277,6 +277,7 @@ TEST(DOMLink, Sensors)
EXPECT_EQ("", cameraSensor->Topic());
EXPECT_EQ("my_camera/trigger", camSensor->TriggerTopic());
EXPECT_TRUE(camSensor->Triggered());
EXPECT_EQ("/camera_sensor/camera_info", camSensor->CameraInfoTopic());
EXPECT_EQ(640u, camSensor->ImageWidth());
EXPECT_EQ(480u, camSensor->ImageHeight());
EXPECT_EQ(sdf::PixelFormatType::RGB_INT8, camSensor->PixelFormat());
Expand Down
1 change: 1 addition & 0 deletions test/sdf/sensors.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
<enable_metrics>false</enable_metrics>
<camera name="my_camera">
<pose>0.1 0.2 0.3 0 0 0</pose>
<camera_info_topic>/camera_sensor/camera_info</camera_info_topic>
<horizontal_fov>.75</horizontal_fov>
<triggered>true</triggered>
<trigger_topic>my_camera/trigger</trigger_topic>
Expand Down

0 comments on commit 2dca585

Please sign in to comment.