Skip to content

Commit

Permalink
Merge branch 'gz-sensors7' into 7_to_8
Browse files Browse the repository at this point in the history
Signed-off-by: Ian Chen <[email protected]>
  • Loading branch information
caguero authored and iche033 committed Jan 27, 2024
2 parents d522779 + 37db629 commit a1e068e
Show file tree
Hide file tree
Showing 6 changed files with 119 additions and 4 deletions.
10 changes: 8 additions & 2 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
@@ -1,14 +1,20 @@
name: Ubuntu CI

on: [push, pull_request]
on:
pull_request:
push:
branches:
- 'ign-sensors[0-9]'
- 'gz-sensors[0-9]?'
- 'main'

jobs:
jammy-ci:
runs-on: ubuntu-latest
name: Ubuntu Jammy CI
steps:
- name: Checkout
uses: actions/checkout@v3
uses: actions/checkout@v4
- name: Compile and test
id: ci
uses: gazebo-tooling/action-gz-ci@jammy
Expand Down
1 change: 0 additions & 1 deletion .github/workflows/triage.yml
Original file line number Diff line number Diff line change
Expand Up @@ -14,4 +14,3 @@ jobs:
with:
project-url: https://github.com/orgs/gazebosim/projects/7
github-token: ${{ secrets.TRIAGE_TOKEN }}

59 changes: 59 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -265,6 +265,40 @@

## Gazebo Sensors 6

### Gazebo Sensors 6.8.0 (2024-01-12)

1. Allow specifying gz_frame_id as an alternative to ignition_frame_id
* [Pull request #409](https://github.com/gazebosim/gz-sensors/pull/409)

1. [backport fortress] camera info topic published with the right data
* [Pull request #383](https://github.com/gazebosim/gz-sensors/pull/383)

1. Infrastructure
* [Pull request #401](https://github.com/gazebosim/gz-sensors/pull/401)

### Gazebo Sensors 6.7.1 (2023-09-01)

1. Support protobuf >= 22
* [Pull request #351](https://github.com/gazebosim/gz-sensors/pull/351)

1. Infrastructure
* [Pull request #335](https://github.com/gazebosim/gz-sensors/pull/335)

1. Rename COPYING to LICENSE
* [Pull request #334](https://github.com/gazebosim/gz-sensors/pull/334)

1. Fix links in Changelog
* [Pull request #330](https://github.com/gazebosim/gz-sensors/pull/330)

1. Fix Camera info test
* [Pull request #326](https://github.com/gazebosim/gz-sensors/pull/326)

1. clean up rendering resources
* [Pull request #324](https://github.com/gazebosim/gz-sensors/pull/324)

1. Added Camera Info topic support for cameras
* [Pull request #285](https://github.com/gazebosim/gz-sensors/pull/285)

### Gazebo Sensors 6.7.0 (2023-02-13)

1. Disable thermal camera test on MacOS.
Expand Down Expand Up @@ -532,6 +566,31 @@

## Gazebo Sensors 3

### Gazebo Sensors 3.6.0 (2024-01-05)

1. Update github action workflows
* [Pull request #401](https://github.com/gazebosim/gz-sensors/pull/401)
* [Pull request #335](https://github.com/gazebosim/gz-sensors/pull/335)
* [Pull request #334](https://github.com/gazebosim/gz-sensors/pull/334)

1. Clean up rendering resources
* [Pull request #324](https://github.com/gazebosim/gz-sensors/pull/324)

1. Destroy rendering sensors when sensor is removed
* [Pull request #169](https://github.com/gazebosim/gz-sensors/pull/169)

1. Support protobuf >= 22
* [Pull request #351](https://github.com/gazebosim/gz-sensors/pull/351)

1. Fix links in Changelog
* [Pull request #330](https://github.com/gazebosim/gz-sensors/pull/330)

1. Fix Camera info test
* [Pull request #326](https://github.com/gazebosim/gz-sensors/pull/326)

1. Added Camera Info topic support for cameras
* [Pull request #285](https://github.com/gazebosim/gz-sensors/pull/285)

### Gazebo Sensors 3.5.0 (2022-11-30)

1. Add missing DEPENDS_ON_COMPONENTS parameters.
Expand Down
2 changes: 1 addition & 1 deletion src/CameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
#include "gz/sensors/SensorFactory.hh"
#include "gz/sensors/SensorTypes.hh"

#include "gz/rendering/Utils.hh"
#include <gz/rendering/Utils.hh>

using namespace gz;
using namespace sensors;
Expand Down
49 changes: 49 additions & 0 deletions src/Sensor_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -349,6 +349,55 @@ TEST(Sensor_TEST, SetRateZeroService)
EXPECT_FLOAT_EQ(20.0, sensor.UpdateRate());
}

//////////////////////////////////////////////////
TEST(Sensor_TEST, FrameIdFromSdf)
{
auto loadSensorWithSdfParam =
[](TestSensor &_testSensor, const std::string &_sensorParam)
{
const std::string sensorSdf = R"(
<sdf version="1.9">
<model name="m1">
<link name="link1">
<sensor name="test" type="imu">)" +
_sensorParam + R"(
</sensor>
</link>
</model>
</sdf>
)";
sdf::Root root;
sdf::Errors errors = root.LoadSdfString(sensorSdf);
ASSERT_TRUE(errors.empty()) << errors;
auto *model = root.Model();
ASSERT_NE(model, nullptr);
auto *link = model->LinkByIndex(0);
ASSERT_NE(link, nullptr);
auto *sensor = link->SensorByIndex(0);
ASSERT_NE(sensor, nullptr);

_testSensor.Load(*sensor);
};

{
TestSensor testSensor;
loadSensorWithSdfParam(testSensor, "");
EXPECT_EQ("test", testSensor.FrameId());
}
{
TestSensor testSensor;
loadSensorWithSdfParam(testSensor,
"<gz_frame_id>custom_frame_id</gz_frame_id>");
EXPECT_EQ("custom_frame_id", testSensor.FrameId());
}
{
TestSensor testSensor;
loadSensorWithSdfParam(testSensor, R"(
<ignition_frame_id>custom_frame_id</ignition_frame_id>
<gz_frame_id>other_custom_frame_id</gz_frame_id>)");
EXPECT_EQ("other_custom_frame_id", testSensor.FrameId());
}
}
//////////////////////////////////////////////////
TEST_F(SensorUpdate, NextDataUpdateTime)
{
Expand Down
2 changes: 2 additions & 0 deletions test/integration/camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,13 @@

#include <gz/msgs/camera_info.pb.h>
#include <gz/msgs/image.pb.h>
#include <gz/common/Image.hh>

#include <gz/common/Console.hh>
#include <gz/common/Filesystem.hh>
#include <gz/sensors/Manager.hh>
#include <gz/sensors/CameraSensor.hh>
#include <gz/rendering/Utils.hh>

// TODO(louise) Remove these pragmas once gz-rendering is disabling the
// warnings
Expand Down

0 comments on commit a1e068e

Please sign in to comment.