Skip to content

Commit

Permalink
Merge pull request #437 from gazebosim/merge_8_main_20240528
Browse files Browse the repository at this point in the history
Merge 8 -> main
  • Loading branch information
azeey authored May 28, 2024
2 parents bdb7e16 + 357ed54 commit 54ba448
Show file tree
Hide file tree
Showing 20 changed files with 1,013 additions and 353 deletions.
11 changes: 11 additions & 0 deletions .github/workflows/package_xml.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
name: Validate package.xml

on:
pull_request:

jobs:
package-xml:
runs-on: ubuntu-latest
name: Validate package.xml
steps:
- uses: gazebo-tooling/action-gz-ci/validate_package_xml@jammy
35 changes: 35 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,41 @@

## Gazebo Sensors 8

### Gazebo Sensors 8.1.0 (2024-05-16)

1. Set camera projection matrix based on lens params for other types of cameras
* [Pull request #432](https://github.com/gazebosim/gz-sensors/pull/432)

1. Move trigger logic to base Sensor class and enable trigger for all camera sensors
* [Pull request #431](https://github.com/gazebosim/gz-sensors/pull/431)

1. Add package.xml
* [Pull request #422](https://github.com/gazebosim/gz-sensors/pull/422)

### Gazebo Sensors 8.0.1 (2024-03-15)

1. Avoid calling DblNormal with invalid standard deviation
* [Pull request #396](https://github.com/gazebosim/gz-sensors/pull/396)

1. DepthCamera and RGBDCamera - optimize RGB point cloud connection
* [Pull request #413](https://github.com/gazebosim/gz-sensors/pull/413)

1. Update CI badges to point to release branch job
* [Pull request #406](https://github.com/gazebosim/gz-sensors/pull/406)
* [Pull request #405](https://github.com/gazebosim/gz-sensors/pull/405)

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

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)

### Gazebo Sensors 8.0.0 (2023-09-29)

1. Documentation fixes
Expand Down
4 changes: 0 additions & 4 deletions include/gz/sensors/BoundingBoxCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -103,10 +103,6 @@ namespace gz
/// \return True on success.
private: bool CreateCamera();

/// \brief Callback for triggered subscription
/// \param[in] _msg Boolean message
private: void OnTrigger(const gz::msgs::Boolean &/*_msg*/);

GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
Expand Down
15 changes: 11 additions & 4 deletions include/gz/sensors/CameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -148,6 +148,17 @@ namespace gz
/// \return The camera optical frame
public: const std::string& OpticalFrameId() const;

/// \brief Set camera lens intrinsics and projection based on
/// values from SDF. If the camera SDF does not contain intrinsic or
/// projection parameters, the camera will not be updated. Instead, the
/// camera SDF will be updated with intrinsic and projection values
/// computed manually from current camera intrinsic properties.
/// \param[in] _camera Camera to set intrinsic and projection params.
/// \param[in,out] _cameraSdf Camera sdf with intrinisc and projection
/// parameters.
public: void UpdateLensIntrinsicsAndProjection(
rendering::CameraPtr _camera, sdf::Camera &_cameraSdf);

/// \brief Advertise camera info topic.
/// \return True if successful.
protected: bool AdvertiseInfo();
Expand Down Expand Up @@ -178,10 +189,6 @@ namespace gz
/// \param[in] _scene Pointer to the new scene.
private: void OnSceneChange(gz::rendering::ScenePtr /*_scene*/);

/// \brief Callback for triggered subscription
/// \param[in] _msg Boolean message
private: void OnTrigger(const gz::msgs::Boolean &/*_msg*/);

GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
Expand Down
26 changes: 24 additions & 2 deletions include/gz/sensors/Sensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -113,8 +113,8 @@ namespace gz
/// subclasses' Update() method will be called.
/// \param[in] _now The current time
/// \param[in] _force Force the update to happen even if it's not time
/// \return True if the update was triggered (_force was true or _now
/// >= next_update_time) and the sensor's
/// \return True if the update was performed (_force was true or _now
/// >= next_update_time or sensor had a pending trigger) and the sensor's
/// bool Sensor::Update(std::chrono::steady_clock::time_point)
/// function returned true.
/// False otherwise.
Expand Down Expand Up @@ -231,6 +231,28 @@ namespace gz
/// \return True if there are subscribers, false otherwise
public: virtual bool HasConnections() const;

/// \brief Enable or disable triggered mode. In this mode,
/// - the sensor will only update if a new message has been published to
/// the passed _triggerTopic since the last update,
/// - until the next message is published on _triggerTopic, all Update
/// calls will return false, and
/// - if the sensor has a pending trigger, the next Update call will
/// ignore the sensor's update rate and try generate data immediately.
/// \param[in] _triggered Sets triggered mode if true and disables it if
/// false.
/// \param[in] _triggerTopic The topic on which the sensor will listen
/// for trigger messages in triggered mode. If _triggered is true, this
/// value should not be empty. If _triggered is false, this value is
/// ignored.
/// \return True if the operation succeeded.
public: bool SetTriggered(bool _triggered,
const std::string &_triggerTopic = "");

/// \brief Whether the sensor has a pending trigger.
/// \return True if the sensor is in trigger mode and has a pending
/// trigger.
public: bool HasPendingTrigger() const;

GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \internal
/// \brief Data pointer for private data
Expand Down
28 changes: 28 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>gz-sensors9</name>
<version>9.0.0</version>
<description>Gazebo Sensors : Sensor models for simulation</description>
<maintainer email="[email protected]">Ian Chen</maintainer>
<license>Apache License 2.0</license>
<url type="website">https://github.com/gazebosim/gz-sensors</url>

<buildtool_depend>cmake</buildtool_depend>

<build_depend>gz-cmake4</build_depend>

<depend>gz-common6</depend>
<depend>gz-math8</depend>
<depend>gz-msgs11</depend>
<depend>gz-rendering9</depend>
<depend>gz-tools2</depend>
<depend>gz-transport14</depend>
<depend>sdformat15</depend>

<test_depend>xvfb</test_depend>

<export>
<build_type>cmake</build_type>
</export>
</package>
72 changes: 16 additions & 56 deletions src/BoundingBoxCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@
*/

#include <mutex>
#include <ostream>
#include <string>

#include <gz/msgs/boolean.pb.h>
#include <gz/msgs/image.pb.h>
Expand All @@ -32,6 +34,7 @@
#include <gz/rendering/BoundingBoxCamera.hh>
#include <gz/transport/Node.hh>
#include <gz/transport/Publisher.hh>
#include <gz/transport/TopicUtils.hh>

#include "gz/sensors/BoundingBoxCameraSensor.hh"
#include "gz/sensors/RenderingEvents.hh"
Expand Down Expand Up @@ -88,15 +91,6 @@ class gz::sensors::BoundingBoxCameraSensorPrivate
/// \brief Just a mutex for thread safety
public: std::mutex mutex;

/// \brief True if camera is triggered by a topic
public: bool isTriggeredCamera{false};

/// \brief True if camera has been triggered by a topic
public: bool isTriggered{false};

/// \brief Topic for camera trigger
public: std::string triggerTopic{""};

/// \brief BoundingBoxes type
public: rendering::BoundingBoxType type
{rendering::BoundingBoxType::BBT_VISIBLEBOX2D};
Expand Down Expand Up @@ -231,30 +225,13 @@ bool BoundingBoxCameraSensor::Load(const sdf::Sensor &_sdf)

if (_sdf.CameraSensor()->Triggered())
{
if (!_sdf.CameraSensor()->TriggerTopic().empty())
{
this->dataPtr->triggerTopic = _sdf.CameraSensor()->TriggerTopic();
}
else
std::string triggerTopic = _sdf.CameraSensor()->TriggerTopic();
if (triggerTopic.empty())
{
this->dataPtr->triggerTopic =
transport::TopicUtils::AsValidTopic(
this->Topic() + "/trigger");

if (this->dataPtr->triggerTopic.empty())
{
gzerr << "Invalid trigger topic name [" <<
this->dataPtr->triggerTopic << "]" << std::endl;
return false;
}
triggerTopic = transport::TopicUtils::AsValidTopic(this->Topic() +
"/trigger");
}

this->dataPtr->node.Subscribe(this->dataPtr->triggerTopic,
&BoundingBoxCameraSensor::OnTrigger, this);

gzdbg << "Camera trigger messages for [" << this->Name() << "] subscribed"
<< " on [" << this->dataPtr->triggerTopic << "]" << std::endl;
this->dataPtr->isTriggeredCamera = true;
this->SetTriggered(true, triggerTopic);
}

if (!this->AdvertiseInfo())
Expand Down Expand Up @@ -303,9 +280,6 @@ bool BoundingBoxCameraSensor::CreateCamera()
return false;
}

// Camera Info Msg
this->PopulateInfo(sdfCamera);

if (!this->dataPtr->rgbCamera)
{
// Create rendering camera
Expand Down Expand Up @@ -356,6 +330,14 @@ bool BoundingBoxCameraSensor::CreateCamera()
this->AddSensor(this->dataPtr->boundingboxCamera);
this->AddSensor(this->dataPtr->rgbCamera);

this->UpdateLensIntrinsicsAndProjection(this->dataPtr->rgbCamera,
*sdfCamera);
this->UpdateLensIntrinsicsAndProjection(this->dataPtr->boundingboxCamera,
*sdfCamera);

// Camera Info Msg
this->PopulateInfo(sdfCamera);

// Create the directory to store frames
if (sdfCamera->SaveFrames())
{
Expand Down Expand Up @@ -430,16 +412,6 @@ bool BoundingBoxCameraSensor::Update(
this->PublishInfo(_now);
}

// render only if necessary
{
std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
if (this->dataPtr->isTriggeredCamera &&
!this->dataPtr->isTriggered)
{
return true;
}
}

// don't render if there are no subscribers nor saving
if (!this->dataPtr->imagePublisher.HasConnections() &&
!this->dataPtr->boxesPublisher.HasConnections() &&
Expand Down Expand Up @@ -578,11 +550,6 @@ bool BoundingBoxCameraSensor::Update(
++this->dataPtr->saveCounter;
}

if (this->dataPtr->isTriggeredCamera)
{
return this->dataPtr->isTriggered = false;
}

return true;
}

Expand All @@ -598,13 +565,6 @@ unsigned int BoundingBoxCameraSensor::ImageWidth() const
return this->dataPtr->rgbCamera->ImageWidth();
}

//////////////////////////////////////////////////
void BoundingBoxCameraSensor::OnTrigger(const gz::msgs::Boolean &/*_msg*/)
{
std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
this->dataPtr->isTriggered = true;
}

//////////////////////////////////////////////////
void BoundingBoxCameraSensorPrivate::SaveImage()
{
Expand Down
Loading

0 comments on commit 54ba448

Please sign in to comment.