Skip to content

Commit 898570d

Browse files
ahcordeiche033
andauthored
Added Camera Info topic support for cameras (#285)
* Added Camera Info topic support for cameras --------- Signed-off-by: ahcorde <[email protected]> Signed-off-by: Alejandro Hernández Cordero <[email protected]> Co-authored-by: Ian Chen <[email protected]>
1 parent 425359e commit 898570d

File tree

2 files changed

+26
-16
lines changed

2 files changed

+26
-16
lines changed

src/CameraSensor.cc

Lines changed: 14 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -257,6 +257,11 @@ bool CameraSensor::Load(const sdf::Sensor &_sdf)
257257
if (this->Topic().empty())
258258
this->SetTopic("/camera");
259259

260+
if (!_sdf.CameraSensor()->CameraInfoTopic().empty())
261+
{
262+
this->dataPtr->infoTopic = _sdf.CameraSensor()->CameraInfoTopic();
263+
}
264+
260265
this->dataPtr->pub =
261266
this->dataPtr->node.Advertise<msgs::Image>(
262267
this->Topic());
@@ -491,17 +496,17 @@ std::string CameraSensor::InfoTopic() const
491496
//////////////////////////////////////////////////
492497
bool CameraSensor::AdvertiseInfo()
493498
{
494-
// TODO(anyone) Make info topic configurable from SDF
495-
// Info topic must be at same level as image topic
496-
auto parts = common::Split(this->Topic(), '/');
497-
parts.pop_back();
498-
499-
for (const auto &part : parts)
499+
if (this->dataPtr->infoTopic.empty())
500500
{
501-
if (!part.empty())
502-
this->dataPtr->infoTopic += "/" + part;
501+
auto parts = common::Split(this->Topic(), '/');
502+
parts.pop_back();
503+
for (const auto &part : parts)
504+
{
505+
if (!part.empty())
506+
this->dataPtr->infoTopic += "/" + part;
507+
}
508+
this->dataPtr->infoTopic += "/camera_info";
503509
}
504-
this->dataPtr->infoTopic += "/camera_info";
505510

506511
return this->AdvertiseInfo(this->dataPtr->infoTopic);
507512
}

src/Camera_TEST.cc

Lines changed: 12 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,8 @@ sdf::ElementPtr cameraToBadSdf()
4848

4949
sdf::ElementPtr CameraToSdf(const std::string &_type,
5050
const std::string &_name, double _updateRate,
51-
const std::string &_topic, bool _alwaysOn, bool _visualize)
51+
const std::string &_topic, const std::string &_cameraInfoTopic,
52+
bool _alwaysOn, bool _visualize)
5253
{
5354
std::ostringstream stream;
5455
stream
@@ -58,6 +59,7 @@ sdf::ElementPtr CameraToSdf(const std::string &_type,
5859
<< " <link name='link1'>"
5960
<< " <sensor name='" << _name << "' type='" << _type << "'>"
6061
<< " <topic>" << _topic << "</topic>"
62+
<< " <topic>" << _cameraInfoTopic << "</topic>"
6163
<< " <update_rate>"<< _updateRate <<"</update_rate>"
6264
<< " <always_on>"<< _alwaysOn <<"</always_on>"
6365
<< " <visualize>" << _visualize << "</visualize>"
@@ -146,8 +148,8 @@ TEST(Camera_TEST, CreateCamera)
146148
{
147149
gz::sensors::Manager mgr;
148150

149-
sdf::ElementPtr camSdf = CameraToSdf("camera", "my_camera", 60.0, "/cam",
150-
true, true);
151+
sdf::ElementPtr camSdf = CameraToSdf("camera", "my_camera", 60.0,
152+
"/cam", "my_camera/camera_info", true, true);
151153

152154
// Create a CameraSensor
153155
gz::sensors::CameraSensor *cam =
@@ -190,8 +192,9 @@ TEST(Camera_TEST, Topic)
190192
// Default topic
191193
{
192194
const std::string topic;
193-
auto cameraSdf = CameraToSdf(type, name, updateRate, topic, alwaysOn,
194-
visualize);
195+
const std::string cameraInfoTopic;
196+
auto cameraSdf = CameraToSdf(type, name, updateRate, topic, cameraInfoTopic,
197+
alwaysOn, visualize);
195198

196199
auto sensorId = mgr.CreateSensor(cameraSdf);
197200
EXPECT_NE(gz::sensors::NO_SENSOR, sensorId);
@@ -203,12 +206,13 @@ TEST(Camera_TEST, Topic)
203206
ASSERT_NE(nullptr, camera);
204207

205208
EXPECT_EQ("/camera", camera->Topic());
209+
EXPECT_EQ("/camera_info", camera->InfoTopic());
206210
}
207211

208212
// Convert to valid topic
209213
{
210214
const std::string topic = "/topic with spaces/@~characters//";
211-
auto cameraSdf = CameraToSdf(type, name, updateRate, topic, alwaysOn,
215+
auto cameraSdf = CameraToSdf(type, name, updateRate, topic, "", alwaysOn,
212216
visualize);
213217

214218
auto sensorId = mgr.CreateSensor(cameraSdf);
@@ -221,12 +225,13 @@ TEST(Camera_TEST, Topic)
221225
ASSERT_NE(nullptr, camera);
222226

223227
EXPECT_EQ("/topic_with_spaces/characters", camera->Topic());
228+
EXPECT_EQ("/topic_with_spaces/camera_info", camera->InfoTopic());
224229
}
225230

226231
// Invalid topic
227232
{
228233
const std::string topic = "@@@";
229-
auto cameraSdf = CameraToSdf(type, name, updateRate, topic, alwaysOn,
234+
auto cameraSdf = CameraToSdf(type, name, updateRate, topic, "", alwaysOn,
230235
visualize);
231236

232237
auto sensorId = mgr.CreateSensor(cameraSdf);

0 commit comments

Comments
 (0)