Skip to content

Commit

Permalink
Merge ign-sensors2 to ign-sensors3 (#44)
Browse files Browse the repository at this point in the history
* mv hgignore

Signed-off-by: claireyywang <clairewang@openrobotics.org>

* add gitignore

Signed-off-by: claireyywang <clairewang@openrobotics.org>

* [ign-sensors2] Update BitBucket links (#10)

* [ign-sensors2] Update BitBucket links

Signed-off-by: Louise Poubel <louise@openrobotics.org>

* [ign-sensors2] Update BitBucket links

Signed-off-by: Louise Poubel <louise@openrobotics.org>

* [ign-sensors2] Workflow updates (#20)

Signed-off-by: Louise Poubel <louise@openrobotics.org>

* Make topics valid (#33)

Signed-off-by: Louise Poubel <louise@openrobotics.org>

* add noise to depth camera

Signed-off-by: Ian Chen <ichen@osrfoundation.org>

* 2.9.0 release prep

Signed-off-by: Nate Koenig <nate@openrobotics.org>

* Fix version numbers in config.hh (#42)

Signed-off-by: Carlos Agüero <caguero@openrobotics.org>

* ci fixes

Signed-off-by: Ian Chen <ichen@osrfoundation.org>

Co-authored-by: claireyywang <clairewang@openrobotics.org>
Co-authored-by: chapulina <lupoubel@hotmail.com>
Co-authored-by: Louise Poubel <louise@openrobotics.org>
Co-authored-by: Nate Koenig <nkoenig@users.noreply.github.com>
Co-authored-by: Nate Koenig <nate@openrobotics.org>
Co-authored-by: Carlos Agüero <caguero@osrfoundation.org>
  • Loading branch information
7 people authored Sep 1, 2020
1 parent 6f1e16a commit ef3c85b
Show file tree
Hide file tree
Showing 28 changed files with 669 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-msgs5-dev
libignition-plugin-dev
libignition-rendering3-dev
libignition-tools-dev
libignition-transport8-dev
libsdformat9-dev
xvfb
25 changes: 25 additions & 0 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
name: Ubuntu CI

on: [push]

jobs:
bionic-ci:
runs-on: ubuntu-latest
name: Ubuntu Bionic CI
steps:
- name: Checkout
uses: actions/checkout@v2
- name: Compile and test
id: ci
uses: ignition-tooling/action-ignition-ci@master
with:
codecov-token: ${{ secrets.CODECOV_TOKEN }}
focal-ci:
runs-on: ubuntu-latest
name: Ubuntu Focal CI
steps:
- name: Checkout
uses: actions/checkout@v2
- name: Compile and test
id: ci
uses: ignition-tooling/action-ignition-ci@focal
11 changes: 11 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,17 @@

## Ignition Sensors 2

### Ignition Sensors 2.9.0 (2020-08-07)

1. Add noise to RGBD camera.
* [Pull Request 35](https://github.com/ignitionrobotics/ign-sensors/pull/35)

1. Make sure all sensors have a default topic.When invalid topics are passed
in, convert them to valid topics if possible. If not possible to convert
into valid topic, fail gracefully.
* [Pull Request 33](https://github.com/ignitionrobotics/ign-sensors/pull/33)


### Ignition Sensors 2.8.0 (2020-03-04)

1. Added sequence numbers to sensor data messages.
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
6 changes: 3 additions & 3 deletions include/ignition/sensors/config.hh.in
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
/* Config.hh. Generated by CMake for @PROJECT_NAME_NO_VERSION@. */

/* Version number */
#define IGNITION_SENSORS_MAJOR_VERSION ${PROJECT_MAJOR_VERSION}
#define IGNITION_SENSORS_MINOR_VERSION ${PROJECT_MINOR_VERSION}
#define IGNITION_SENSORS_PATCH_VERSION ${PROJECT_PATCH_VERSION}
#define IGNITION_SENSORS_MAJOR_VERSION ${PROJECT_VERSION_MAJOR}
#define IGNITION_SENSORS_MINOR_VERSION ${PROJECT_VERSION_MINOR}
#define IGNITION_SENSORS_PATCH_VERSION ${PROJECT_VERSION_PATCH}

#define IGNITION_SENSORS_VERSION "${PROJECT_VERSION}"
#define IGNITION_SENSORS_VERSION_FULL "${PROJECT_VERSION_FULL}"
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 @@ -247,6 +247,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 @@ -29,7 +29,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 @@ -46,7 +46,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 @@ -128,7 +128,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 @@ -157,6 +157,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 @@ -264,6 +264,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 @@ -122,14 +122,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
2 changes: 1 addition & 1 deletion src/ImageNoise.cc
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ NoisePtr ImageNoiseFactory::NewNoiseModel(const sdf::Noise &_sdf,
{
if (_sensorType == "camera" || _sensorType == "depth" ||
_sensorType == "multicamera" || _sensorType == "wideanglecamera" ||
_sensorType == "thermal_camera")
_sensorType == "thermal_camera" || _sensorType == "rgbd_camera")
{
noise.reset(new ImageGaussianNoiseModel());
}
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 @@ -106,6 +106,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 @@ -104,16 +104,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
2 changes: 1 addition & 1 deletion src/Noise.cc
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ NoisePtr NoiseFactory::NewNoiseModel(const sdf::Noise &_sdf,
{
if (_sensorType == "camera" || _sensorType == "depth" ||
_sensorType == "multicamera" || _sensorType == "wideanglecamera" ||
_sensorType == "thermal_camera")
_sensorType == "thermal_camera" || _sensorType == "rgbd_camera")
{
ignerr << "Image noise requested. "
<< "Please use ImageNoiseFactory::NoiseModel instead"
Expand Down
Loading

0 comments on commit ef3c85b

Please sign in to comment.