Skip to content

Commit

Permalink
Merge pull request #391 from gazebosim/merge_8_main_20231010
Browse files Browse the repository at this point in the history
Merge: 8 -> main
  • Loading branch information
iche033 committed Oct 10, 2023
2 parents bd695b2 + 2cab123 commit d44b7dc
Show file tree
Hide file tree
Showing 10 changed files with 167 additions and 64 deletions.
8 changes: 3 additions & 5 deletions .github/workflows/triage.yml
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,8 @@ jobs:
runs-on: ubuntu-latest
steps:
- name: Add ticket to inbox
uses: technote-space/create-project-card-action@v1
uses: actions/[email protected]
with:
PROJECT: Core development
COLUMN: Inbox
GITHUB_TOKEN: ${{ secrets.TRIAGE_TOKEN }}
CHECK_ORG_PROJECT: true
project-url: https://github.com/orgs/gazebosim/projects/7
github-token: ${{ secrets.TRIAGE_TOKEN }}

2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ find_package(gz-cmake3 REQUIRED)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)

gz_configure_project(VERSION_SUFFIX pre1)
gz_configure_project(VERSION_SUFFIX)

#============================================================================
# Set project-specific options
Expand Down
92 changes: 91 additions & 1 deletion Changelog.md
Original file line number Diff line number Diff line change
@@ -1,9 +1,99 @@
## Gazebo Sensors 8

### Gazebo Sensors 8.0.0 (202X-XX-XX)
### Gazebo Sensors 8.0.0 (2023-09-29)

1. Documentation fixes
* [Pull request #385](https://github.com/gazebosim/gz-sensors/pull/385)
* [Pull request #382](https://github.com/gazebosim/gz-sensors/pull/382)
* [Pull request #379](https://github.com/gazebosim/gz-sensors/pull/379)
* [Pull request #380](https://github.com/gazebosim/gz-sensors/pull/380)
* [Pull request #381](https://github.com/gazebosim/gz-sensors/pull/381)
* [Pull request #378](https://github.com/gazebosim/gz-sensors/pull/378)
* [Pull request #344](https://github.com/gazebosim/gz-sensors/pull/344)

1. populate the covariance fields using the noise models
* [Pull request #333](https://github.com/gazebosim/gz-sensors/pull/333)

1. Tests need to include message types they are using
* [Pull request #375](https://github.com/gazebosim/gz-sensors/pull/375)

1. Update air sensor with air_speed.proto
* [Pull request #374](https://github.com/gazebosim/gz-sensors/pull/374)

1. Bumps in harmonic : sdformat14, rendering8, transport13
* [Pull request #367](https://github.com/gazebosim/gz-sensors/pull/367)
* [Pull request #316](https://github.com/gazebosim/gz-sensors/pull/316)

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

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

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

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

1. Minor cleanup - lint, typos
* [Pull request #352](https://github.com/gazebosim/gz-sensors/pull/352)

1. Fix frame_id for depth camera point cloud
* [Pull request #350](https://github.com/gazebosim/gz-sensors/pull/350)

1. Fix dvl integration test
* [Pull request #348](https://github.com/gazebosim/gz-sensors/pull/348)

1. Add support for bayer images to camera sensor
* [Pull request #336](https://github.com/gazebosim/gz-sensors/pull/336)

1. Fix flaky trigger camera test
* [Pull request #346](https://github.com/gazebosim/gz-sensors/pull/346)

1. Generate default trigger topic name if empty
* [Pull request #343](https://github.com/gazebosim/gz-sensors/pull/343)

1. Add DopplerVelocityLog sensor
* [Pull request #290](https://github.com/gazebosim/gz-sensors/pull/290)

1. ⬆️ Bump main to 8.0.0~pre1
* [Pull request #254](https://github.com/gazebosim/gz-sensors/pull/254)

## Gazebo Sensors 7

### Gazebo Sensors 7.3.0 (2023-09-26)

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

1. Expose optical frame in CameraSensor so it can be set in DepthCameraSensor
* [Pull request #362](https://github.com/gazebosim/gz-sensors/pull/362)

1. Fix CameraSensor to check if element is null before access
* [Pull request #361](https://github.com/gazebosim/gz-sensors/pull/361)

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

1. Minor cleanup - lint, typos
* [Pull request #352](https://github.com/gazebosim/gz-sensors/pull/352)
* [Pull request #344](https://github.com/gazebosim/gz-sensors/pull/344)

1. Fix frame_id for depth camera point cloud
* [Pull request #350](https://github.com/gazebosim/gz-sensors/pull/350)

1. Add support for bayer images to camera sensor
* [Pull request #336](https://github.com/gazebosim/gz-sensors/pull/336)

1. Fix flaky trigger camera test
* [Pull request #346](https://github.com/gazebosim/gz-sensors/pull/346)

1. Generate default trigger topic name if empty
* [Pull request #343](https://github.com/gazebosim/gz-sensors/pull/343)


### Gazebo Sensors 7.2.0 (2023-04-13)

1. Cleanup resources in CameraSensor destructor
Expand Down
8 changes: 4 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,13 +10,13 @@
Build | Status
-- | --
Test coverage | [![codecov](https://codecov.io/gh/gazebosim/gz-sensors/branch/main/graph/badge.svg)](https://codecov.io/gh/gazebosim/gz-sensors/branch/main)
Ubuntu Focal | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_sensors-ci-main-focal-amd64)](https://build.osrfoundation.org/job/ignition_sensors-ci-main-focal-amd64)
Ubuntu Jammy | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=gz_sensors-ci-main-jammy-amd64)](https://build.osrfoundation.org/job/gz_sensors-ci-main-jammy-amd64)
Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_sensors-ci-main-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_sensors-ci-main-homebrew-amd64)
Windows | [![Build Status](https://build.osrfoundation.org/job/ign_sensors-ci-win/badge/icon)](https://build.osrfoundation.org/job/ign_sensors-ci-win/)

Gazebo Sensors, a component of [Gazebo](https://gazebosim.org),
provides numerous sensor models
designed to generate realistic data from simulation environments. Gazebo Sensors is used in conjunction with [Gazebo Libraries](https://gazebosim/libs), and especially relies on the rendering capabilities from [Gazebo Rendering](https://gazebosim.org/libs/rendering) and physics simulation from [Gazebo Physics](https://gazebosim.org/libs/physics).
designed to generate realistic data from simulation environments. Gazebo Sensors is used in conjunction with [Gazebo Libraries](https://gazebosim.org/libs), and especially relies on the rendering capabilities from [Gazebo Rendering](https://gazebosim.org/libs/rendering) and physics simulation from [Gazebo Physics](https://gazebosim.org/libs/physics).

# Table of Contents

Expand Down Expand Up @@ -45,11 +45,11 @@ models into sensor streams.

# Install

See the [installation tutorial](https://gazebosim.org/api/sensors/7.0/installation.html).
See the [installation tutorial](https://gazebosim.org/api/sensors/8/installation.html).

# Usage

Please refer to the [examples directory](https://github.com/gazebosim/gz-sensors/raw/main/examples/).
Please refer to the [examples directory](https://github.com/gazebosim/gz-sensors/tree/main/examples).

# Folder Structure

Expand Down
4 changes: 4 additions & 0 deletions include/gz/sensors/CameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -144,6 +144,10 @@ namespace gz
/// \return True if there are info subscribers, false otherwise
public: virtual bool HasInfoConnections() const;

/// \brief Get the camera optical frame
/// \return The camera optical frame
public: const std::string& OpticalFrameId() const;

/// \brief Advertise camera info topic.
/// \return True if successful.
protected: bool AdvertiseInfo();
Expand Down
9 changes: 8 additions & 1 deletion src/CameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -195,7 +195,8 @@ bool CameraSensor::CreateCamera()
this->dataPtr->camera->SetAspectRatio(static_cast<double>(width)/height);
this->dataPtr->camera->SetHFOV(angle);

if (cameraSdf->Element()->HasElement("distortion")) {
if (cameraSdf->Element() != nullptr &&
cameraSdf->Element()->HasElement("distortion")) {
this->dataPtr->distortion =
ImageDistortionFactory::NewDistortionModel(*cameraSdf, "camera");
this->dataPtr->distortion->Load(*cameraSdf);
Expand Down Expand Up @@ -857,3 +858,9 @@ bool CameraSensor::HasInfoConnections() const
{
return this->dataPtr->infoPub && this->dataPtr->infoPub.HasConnections();
}

//////////////////////////////////////////////////
const std::string& CameraSensor::OpticalFrameId() const
{
return this->dataPtr->opticalFrameId;
}
26 changes: 15 additions & 11 deletions src/DepthCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -301,15 +301,6 @@ bool DepthCameraSensor::Load(const sdf::Sensor &_sdf)
gzdbg << "Points for [" << this->Name() << "] advertised on ["
<< this->Topic() << "/points]" << std::endl;

// Initialize the point message.
// \todo(anyone) The true value in the following function call forces
// the xyz and rgb fields to be aligned to memory boundaries. This is need
// by ROS1: https://github.com/ros/common_msgs/pull/77. Ideally, memory
// alignment should be configured.
msgs::InitPointCloudPacked(this->dataPtr->pointMsg, this->FrameId(), true,
{{"xyz", msgs::PointCloudPacked::Field::FLOAT32},
{"rgb", msgs::PointCloudPacked::Field::FLOAT32}});

if (this->Scene())
{
this->CreateCamera();
Expand Down Expand Up @@ -495,6 +486,18 @@ bool DepthCameraSensor::CreateCamera()
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3,
std::placeholders::_4, std::placeholders::_5));

// Initialize the point message.
// \todo(anyone) The true value in the following function call forces
// the xyz and rgb fields to be aligned to memory boundaries. This is need
// by ROS1: https://github.com/ros/common_msgs/pull/77. Ideally, memory
// alignment should be configured.
msgs::InitPointCloudPacked(
this->dataPtr->pointMsg,
this->OpticalFrameId(),
true,
{{"xyz", msgs::PointCloudPacked::Field::FLOAT32},
{"rgb", msgs::PointCloudPacked::Field::FLOAT32}});

// Set the values of the point message based on the camera information.
this->dataPtr->pointMsg.set_width(this->ImageWidth());
this->dataPtr->pointMsg.set_height(this->ImageHeight());
Expand Down Expand Up @@ -622,9 +625,10 @@ bool DepthCameraSensor::Update(
rendering::PF_FLOAT32_R));
msg.set_pixel_format_type(msgsFormat);
*msg.mutable_header()->mutable_stamp() = msgs::Convert(_now);
auto frame = msg.mutable_header()->add_data();

auto* frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
frame->add_value(this->FrameId());
frame->add_value(this->OpticalFrameId());

std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
msg.set_data(this->dataPtr->depthBuffer,
Expand Down
69 changes: 35 additions & 34 deletions tutorials/install.md
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ sudo apt-get update

2. Install Gazebo Sensors
```{.sh}
# Change <#> to a version number, like 3 or 4
# Change <#> to a version number, like 7 or 8
sudo apt install libgz-sensors<#>-dev
```

Expand All @@ -35,12 +35,32 @@ sudo apt install libgz-sensors<#>-dev
brew install gz-sensors<#>
```

Be sure to replace `<#>` with a number value, such as 5 or 6, depending on
Be sure to replace `<#>` with a number value, such as 7 or 8, depending on
which version you need.

### Windows

Binary install is pending `gz-rendering` and `gz-sensors` being added to conda-forge.
#### Install Prerequisites

First, follow the [gz-cmake](https://github.com/gazebosim/gz-cmake) tutorial for installing Conda, Visual Studio, CMake, etc., prerequisites, and creating a Conda environment.

Navigate to `condabin` if necessary to use the `conda` command (i.e., if Conda is not in your `PATH` environment variable. You can find the location of `condabin` in Anaconda Prompt, `where conda`).

Create if necessary, and activate a Conda environment:

```
conda create -n gz-ws
conda activate gz-ws
```

#### Binary Installation

```
conda install libgz-sensors<#> --channel conda-forge
```

Be sure to replace `<#>` with a number value, such as 7 or 8, depending on
which version you need.

## Source Install

Expand Down Expand Up @@ -85,14 +105,14 @@ Gazebo Sensors requires:

1. Clone the repository
```
git clone https://github.com/gazebosim/gz-sensors -b ign-sensors<#>
git clone https://github.com/gazebosim/gz-sensors -b gz-sensors<#>
```
Be sure to replace `<#>` with a number value, such as 5 or 6, depending on
which version you need.

2. Install dependencies
```
brew install --only-dependencies ignition-sensors<#>
brew install --only-dependencies gz-sensors<#>
```
Be sure to replace `<#>` with a number value, such as 5 or 6, depending on
which version you need.
Expand All @@ -113,37 +133,24 @@ Gazebo Sensors requires:

### Windows

#### Install Prerequisites

First, follow the [gz-cmake](https://github.com/gazebosim/gz-cmake) tutorial for installing Conda, Visual Studio, CMake, etc., prerequisites, and creating a Conda environment.

Navigate to `condabin` if necessary to use the `conda` command (i.e., if Conda is not in your `PATH` environment variable. You can find the location of `condabin` in Anaconda Prompt, `where conda`).

Create if necessary, and activate a Conda environment:
This assumes you have created and activated a Conda environment while [installing the Prerequisites](#install-prerequisites).

```
conda create -n gz-ws
conda activate gz-ws
```
1. Install Gazebo dependencies:

Install Gazebo dependencies, replacing `<#>` with the desired versions:

```
conda install libgz-cmake<#> libgz-common<#> libgz-math<#> libgz-transport<#> libgz-msgs<#> --channel conda-forge
```

Before [gz-rendering](https://github.com/gazebosim/gz-rendering) becomes available on conda-forge, follow its tutorial to build it from source.
You can view available versions and their dependencies:
```
conda search libgz-sensors* --channel conda-forge --info
```

#### Build from source
Install dependencies, replacing `<#>` with the desired versions:

1. Activate the Conda environment created in the prerequisites:
```
conda activate gz-ws
conda install libgz-cmake<#> libgz-common<#> libgz-math<#> libgz-transport<#> libgz-msgs<#> libgz-rendering<#> --channel conda-forge
```

2. Navigate to where you would like to build the library, and clone the repository.
```
# Optionally, append `-b ign-sensors#` (replace # with a number) to check out a specific version
# Optionally, append `-b gz-sensors#` (replace # with a number) to check out a specific version
git clone https://github.com/gazebosim/gz-sensors.git
```

Expand All @@ -154,13 +161,7 @@ Before [gz-rendering](https://github.com/gazebosim/gz-rendering) becomes availab
cd build
```

4. Before `gz-rendering` becomes available on conda-forge, we need to build it from source and specify the path containing `gz-rendering-config.cmake` in `CMAKE_PREFIX_PATH`, for cmake to find `gz-rendering`. That path could be `gz-rendering-install-path\lib\cmake\gz-rendering4`, for example.
```
cmake .. -DBUILD_TESTING=OFF -DCMAKE_PREFIX_PATH=path\containing\ignition-rendering-config # Optionally, -DCMAKE_INSTALL_PREFIX=path\to\install
cmake --build . --config Release
```

5. Optionally, install. You will likely need to run a terminal with admin privileges for this call to succeed.
4. Optionally, install. You will likely need to run a terminal with admin privileges for this call to succeed.
```
cmake --install . --config Release
```
Expand Down
7 changes: 3 additions & 4 deletions tutorials/intro.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@ noise models accessible through a C++ interface. The goal of Gazebo
Sensors is to generate realistic sensor data suitable for use in robotic
applications and simulation. The code behind Gazebo Sensors was originally
developed as a suite of sensor models internal to
[Gazebo](http://gazebosim.org). With the addition of some refactoring, the
high-quality sensor models previously contained within Gazebo are now
available for use in your next project without encumbering you with
a complete simulation system.
[Gazebo Classic](http://classic.gazebosim.org). With the addition of some
refactoring, the high-quality sensor models are now available for use in
your next project without encumbering you with a complete simulation system.
6 changes: 3 additions & 3 deletions tutorials/thermal_camera.md
Original file line number Diff line number Diff line change
Expand Up @@ -253,7 +253,7 @@ You should see something similar to this:

Taking a look at the [SDF file](https://github.com/gazebosim/gz-sim/blob/e647570f25f962d63af75cf669ff72731d57bd5e/examples/worlds/thermal_camera.sdf) for this example shows that the box was assigned a temperature of 285 Kelvin.

If we take a look at the Rescue Randy and Samsung J8 [fuel models](https://app.gazebosim.org/dashboard), we see that they have the following temperature range (the SDF file we are using with these models has an [ambient temperature of 300 Kelvin](https://github.com/gazebosim/gz-sim/blob/e647570f25f962d63af75cf669ff72731d57bd5e/examples/worlds/thermal_camera.sdf#L135-L144)):
If we take a look at the [Rescue Randy](https://app.gazebosim.org/OpenRobotics/fuel/models/Rescue%20Randy) and [Samsung J8](https://app.gazebosim.org/OpenRobotics/fuel/models/Samsung%20J8%20Black) Fuel models, we see that they have the following temperature range (the SDF file we are using with these models has an [ambient temperature of 300 Kelvin](https://github.com/gazebosim/gz-sim/blob/e647570f25f962d63af75cf669ff72731d57bd5e/examples/worlds/thermal_camera.sdf#L135-L144)):
* Rescue Randy: 300 Kelvin to 310 Kelvin
* Samsung J8: 298.75 Kelvin to 300 Kelvin

Expand All @@ -262,12 +262,12 @@ The object with the highest temperature in the camera's view will always have wh
If you move the object with the highest temperature out of the camera's view, the object with second highest temperature now becomes white.

You can move the position of the objects and/or camera around in the world to see the effect it has on the camera's output (the different "camera outputs" are how they are visualized in the GUI).
An easy way to move objects in the world is by using `Transform Control`:
An easy way to move objects in the world is by using the `Transform Control` tool:

@image html files/thermal_camera/thermal_camera_demo_2.png

Another thing that you can do is modify the temperature ranges for objects with a heat signature.
For example, if you go to the fuel cache on your machine (located at `~/.gz/fuel/` by default) and then modify Rescue Randy's `model.sdf` to have `min_temp` be `200`, and `max_temp` be `500`, you should see output similar to this (be sure to re-start the simulator by killing the current simulator (`ctrl-c` will do) and then re-running `gz sim -r thermal_camera.sdf`):
For example, if you go to the fuel cache on your machine (located at `~/.gz/fuel/` by default) and then modify Rescue Randy's `model.sdf` to have `min_temp` be `200`, and `max_temp` be `500`, you should see output similar to this (be sure to re-start the simulator by closing the current simulator and then re-running `gz sim -r thermal_camera.sdf`):

@image html files/thermal_camera/thermal_camera_demo_3.png

Expand Down

0 comments on commit d44b7dc

Please sign in to comment.