Skip to content

Commit

Permalink
Make topics valid (#33)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina authored Aug 4, 2020
1 parent 3c3bb77 commit a2b4904
Show file tree
Hide file tree
Showing 24 changed files with 604 additions and 73 deletions.
12 changes: 12 additions & 0 deletions .github/ci/after_make.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
#!/bin/sh -l

set -x
set -e

# Install (needed for some tests)
make install

Xvfb :1 -screen 0 1280x1024x24 &
export DISPLAY=:1.0
export RENDER_ENGINE_VALUES=ogre2
export MESA_GL_VERSION_OVERRIDE=3.3
10 changes: 10 additions & 0 deletions .github/ci/packages.apt
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
libignition-cmake2-dev
libignition-common3-dev
libignition-math6-dev
libignition-msgs4-dev
libignition-plugin-dev
libignition-rendering2-dev
libignition-tools-dev
libignition-transport7-dev
libsdformat8-dev
xvfb
8 changes: 4 additions & 4 deletions .github/workflows/ci-bionic.yml → .github/workflows/ci.yml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
name: Ubuntu Bionic CI
name: Ubuntu CI

on: [push, pull_request]
on: [push]

jobs:
bionic-ci:
Expand All @@ -9,9 +9,9 @@ jobs:
steps:
- name: Checkout
uses: actions/checkout@v2
- name: Bionic CI
- name: Compile and test
id: ci
uses: ignition-tooling/ubuntu-bionic-ci-action@master
uses: ignition-tooling/action-ignition-ci@master
with:
apt-dependencies: 'libignition-cmake2-dev libignition-common3-dev libignition-math6-dev libignition-msgs4-dev libignition-rendering2-dev libignition-transport7-dev libignition-tools-dev libignition-plugin-dev libsdformat8-dev'
codecov-token: ${{ secrets.CODECOV_TOKEN }}
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ set(IGN_COMMON_VER ${ignition-common3_VERSION_MAJOR})

#--------------------------------------
# Find ignition-transport
ign_find_package(ignition-transport7 REQUIRED)
ign_find_package(ignition-transport7 REQUIRED VERSION 7.5)
set(IGN_TRANSPORT_VER ${ignition-transport7_VERSION_MAJOR})

#--------------------------------------
Expand Down
5 changes: 5 additions & 0 deletions include/ignition/sensors/Sensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -132,6 +132,11 @@ namespace ignition
/// \return Topic sensor publishes data to
public: std::string Topic() const;

/// \brief Set topic where sensor data is published.
/// \param[in] _topic Topic sensor publishes data to.
/// \return True if a valid topic was set.
public: bool SetTopic(const std::string &_topic);

/// \brief Get parent link of the sensor.
/// \return Parent link of sensor.
public: std::string Parent() const;
Expand Down
10 changes: 5 additions & 5 deletions src/AirPressureSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -100,16 +100,16 @@ bool AirPressureSensor::Load(const sdf::Sensor &_sdf)
return false;
}

std::string topic = this->Topic();
if (topic.empty())
topic = "/air_pressure";
if (this->Topic().empty())
this->SetTopic("/air_pressure");

this->dataPtr->pub =
this->dataPtr->node.Advertise<ignition::msgs::FluidPressure>(topic);
this->dataPtr->node.Advertise<ignition::msgs::FluidPressure>(
this->Topic());

if (!this->dataPtr->pub)
{
ignerr << "Unable to create publisher on topic[" << topic << "].\n";
ignerr << "Unable to create publisher on topic[" << this->Topic() << "].\n";
return false;
}

Expand Down
9 changes: 4 additions & 5 deletions src/AltimeterSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -88,16 +88,15 @@ bool AltimeterSensor::Load(const sdf::Sensor &_sdf)
return false;
}

std::string topic = this->Topic();
if (topic.empty())
topic = "/altimeter";
if (this->Topic().empty())
this->SetTopic("/altimeter");

this->dataPtr->pub =
this->dataPtr->node.Advertise<ignition::msgs::Altimeter>(topic);
this->dataPtr->node.Advertise<ignition::msgs::Altimeter>(this->Topic());

if (!this->dataPtr->pub)
{
ignerr << "Unable to create publisher on topic[" << topic << "].\n";
ignerr << "Unable to create publisher on topic[" << this->Topic() << "].\n";
return false;
}

Expand Down
3 changes: 3 additions & 0 deletions src/CameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -234,6 +234,9 @@ bool CameraSensor::Load(const sdf::Sensor &_sdf)

this->dataPtr->sdfSensor = _sdf;

if (this->Topic().empty())
this->SetTopic("/camera");

this->dataPtr->pub =
this->dataPtr->node.Advertise<ignition::msgs::Image>(
this->Topic());
Expand Down
65 changes: 62 additions & 3 deletions src/Camera_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ sdf::ElementPtr cameraToBadSdf()
<< "<sdf version='1.6'>"
<< " <model name='m1'>"
<< " <link name='link1'>"
<< " <sensor name='cam_name' type='camera'>"
<< " <sensor name='cam_name' type='not_camera'>"
<< " <not_camera>"
<< " </not_camera>"
<< " </sensor>"
Expand All @@ -45,7 +45,7 @@ sdf::ElementPtr cameraToBadSdf()
->GetElement("sensor");
}

sdf::ElementPtr cameraToSdf(const std::string &_type,
sdf::ElementPtr CameraToSdf(const std::string &_type,
const std::string &_name, double _updateRate,
const std::string &_topic, bool _alwaysOn, bool _visualize)
{
Expand Down Expand Up @@ -127,7 +127,7 @@ TEST(Camera_TEST, CreateCamera)
{
ignition::sensors::Manager mgr;

sdf::ElementPtr camSdf = cameraToSdf("camera", "my_camera", 60.0, "/cam",
sdf::ElementPtr camSdf = CameraToSdf("camera", "my_camera", 60.0, "/cam",
true, true);

// Create a CameraSensor
Expand Down Expand Up @@ -156,6 +156,65 @@ TEST(Camera_TEST, CreateCamera)
EXPECT_TRUE(badCam == nullptr);
}

/////////////////////////////////////////////////
TEST(Camera_TEST, Topic)
{
const std::string type = "camera";
const std::string name = "TestCamera";
const double updateRate = 30;
const bool alwaysOn = 1;
const bool visualize = 1;

// Factory
ignition::sensors::Manager mgr;

// Default topic
{
const std::string topic;
auto cameraSdf = CameraToSdf(type, name, updateRate, topic, alwaysOn,
visualize);

auto sensorId = mgr.CreateSensor(cameraSdf);
EXPECT_NE(ignition::sensors::NO_SENSOR, sensorId);

auto sensor = mgr.Sensor(sensorId);
EXPECT_NE(nullptr, sensor);

auto camera = dynamic_cast<ignition::sensors::CameraSensor *>(sensor);
ASSERT_NE(nullptr, camera);

EXPECT_EQ("/camera", camera->Topic());
}

// Convert to valid topic
{
const std::string topic = "/topic with spaces/@~characters//";
auto cameraSdf = CameraToSdf(type, name, updateRate, topic, alwaysOn,
visualize);

auto sensorId = mgr.CreateSensor(cameraSdf);
EXPECT_NE(ignition::sensors::NO_SENSOR, sensorId);

auto sensor = mgr.Sensor(sensorId);
EXPECT_NE(nullptr, sensor);

auto camera = dynamic_cast<ignition::sensors::CameraSensor *>(sensor);
ASSERT_NE(nullptr, camera);

EXPECT_EQ("/topic_with_spaces/characters", camera->Topic());
}

// Invalid topic
{
const std::string topic = "@@@";
auto cameraSdf = CameraToSdf(type, name, updateRate, topic, alwaysOn,
visualize);

auto sensorId = mgr.CreateSensor(cameraSdf);
EXPECT_EQ(ignition::sensors::NO_SENSOR, sensorId);
}
}

//////////////////////////////////////////////////
int main(int argc, char **argv)
{
Expand Down
3 changes: 3 additions & 0 deletions src/DepthCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -252,6 +252,9 @@ bool DepthCameraSensor::Load(const sdf::Sensor &_sdf)

this->dataPtr->sdfSensor = _sdf;

if (this->Topic().empty())
this->SetTopic("/camera/depth");

this->dataPtr->pub =
this->dataPtr->node.Advertise<ignition::msgs::Image>(
this->Topic());
Expand Down
6 changes: 4 additions & 2 deletions src/GpuLidarSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -121,14 +121,16 @@ bool GpuLidarSensor::Load(const sdf::Sensor &_sdf)
std::bind(&GpuLidarSensor::SetScene, this, std::placeholders::_1));

// Create the point cloud publisher
this->SetTopic(this->Topic() + "/points");

this->dataPtr->pointPub =
this->dataPtr->node.Advertise<ignition::msgs::PointCloudPacked>(
this->Topic() + "/points");
this->Topic());

if (!this->dataPtr->pointPub)
{
ignerr << "Unable to create publisher on topic["
<< this->Topic() + "/points" << "].\n";
<< this->Topic() << "].\n";
return false;
}

Expand Down
9 changes: 4 additions & 5 deletions src/ImuSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -104,16 +104,15 @@ bool ImuSensor::Load(const sdf::Sensor &_sdf)
return false;
}

std::string topic = this->Topic();
if (topic.empty())
topic = "/imu";
if (this->Topic().empty())
this->SetTopic("/imu");

this->dataPtr->pub =
this->dataPtr->node.Advertise<ignition::msgs::IMU>(topic);
this->dataPtr->node.Advertise<ignition::msgs::IMU>(this->Topic());

if (!this->dataPtr->pub)
{
ignerr << "Unable to create publisher on topic[" << topic << "].\n";
ignerr << "Unable to create publisher on topic[" << this->Topic() << "].\n";
return false;
}

Expand Down
3 changes: 3 additions & 0 deletions src/Lidar.cc
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,9 @@ bool Lidar::Load(const sdf::Sensor &_sdf)
}

// Register publisher
if (this->Topic().empty())
this->SetTopic("/lidar");

this->dataPtr->pub =
this->dataPtr->node.Advertise<ignition::msgs::LaserScan>(
this->Topic());
Expand Down
10 changes: 5 additions & 5 deletions src/LogicalCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -103,16 +103,16 @@ bool LogicalCameraSensor::Load(sdf::ElementPtr _sdf)
if (!Sensor::Load(_sdf))
return false;

std::string topic = this->Topic();
if (topic.empty())
topic = "/logical_camera";
if (this->Topic().empty())
this->SetTopic("/logical_camera");

this->dataPtr->pub =
this->dataPtr->node.Advertise<ignition::msgs::LogicalCameraImage>(topic);
this->dataPtr->node.Advertise<ignition::msgs::LogicalCameraImage>(
this->Topic());

if (!this->dataPtr->pub)
{
ignerr << "Unable to create publisher on topic[" << topic << "].\n";
ignerr << "Unable to create publisher on topic[" << this->Topic() << "].\n";
return false;
}

Expand Down
10 changes: 5 additions & 5 deletions src/MagnetometerSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -92,16 +92,16 @@ bool MagnetometerSensor::Load(const sdf::Sensor &_sdf)
return false;
}

std::string topic = this->Topic();
if (topic.empty())
topic = "/magnetometer";
if (this->Topic().empty())
this->SetTopic("/magnetometer");

this->dataPtr->pub =
this->dataPtr->node.Advertise<ignition::msgs::Magnetometer>(topic);
this->dataPtr->node.Advertise<ignition::msgs::Magnetometer>(
this->Topic());

if (!this->dataPtr->pub)
{
ignerr << "Unable to create publisher on topic[" << topic << "].\n";
ignerr << "Unable to create publisher on topic[" << this->Topic() << "].\n";
return false;
}

Expand Down
32 changes: 31 additions & 1 deletion src/Sensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <ignition/sensors/Manager.hh>
#include <ignition/common/Console.hh>
#include <ignition/common/Profiler.hh>
#include <ignition/transport/TopicUtils.hh>

using namespace ignition::sensors;

Expand All @@ -30,6 +31,11 @@ class ignition::sensors::SensorPrivate
/// \brief Populates fields from a <sensor> DOM
public: bool PopulateFromSDF(const sdf::Sensor &_sdf);

/// \brief Set topic where sensor data is published.
/// \param[in] _topic Topic sensor publishes data to.
/// \return True if a valid topic was set.
public: bool SetTopic(const std::string &_topic);

/// \brief id given to sensor when constructed
public: SensorId id;

Expand Down Expand Up @@ -88,7 +94,11 @@ bool SensorPrivate::PopulateFromSDF(const sdf::Sensor &_sdf)

// \todo(nkoenig) how to use frame?
this->name = _sdf.Name();
this->topic = _sdf.Topic();
if (!_sdf.Topic().empty())
{
if (!this->SetTopic(_sdf.Topic()))
return false;
}
this->pose = _sdf.Pose();
this->updateRate = _sdf.UpdateRate();
return true;
Expand Down Expand Up @@ -157,6 +167,26 @@ std::string Sensor::Topic() const
return this->dataPtr->topic;
}

//////////////////////////////////////////////////
bool Sensor::SetTopic(const std::string &_topic)
{
return this->dataPtr->SetTopic(_topic);
}

//////////////////////////////////////////////////
bool SensorPrivate::SetTopic(const std::string &_topic)
{
auto validTopic = transport::TopicUtils::AsValidTopic(_topic);
if (validTopic.empty())
{
ignerr << "Failed to set sensor topic [" << _topic << "]" << std::endl;
return false;
}

this->topic = validTopic;
return true;
}

//////////////////////////////////////////////////
ignition::math::Pose3d Sensor::Pose() const
{
Expand Down
Loading

0 comments on commit a2b4904

Please sign in to comment.