Skip to content

Commit

Permalink
Merge pull request #445 from gazebosim/merge_8_main_2024-07-04
Browse files Browse the repository at this point in the history
Merge 8 -> main
  • Loading branch information
Crola1702 authored Jul 4, 2024
2 parents 54ba448 + 88ae24a commit e642ad6
Show file tree
Hide file tree
Showing 12 changed files with 34 additions and 14 deletions.
8 changes: 8 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,14 @@

## Gazebo Sensors 8

### Gazebo Sensors 8.2.0 (2024-06-14)

1. Add API to check if sensor is in trigger mode
* [Pull request #441](https://github.com/gazebosim/gz-sensors/pull/441)

1. Set rendering sensor pose
* [Pull request #439](https://github.com/gazebosim/gz-sensors/pull/439)

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

1. Set camera projection matrix based on lens params for other types of cameras
Expand Down
4 changes: 4 additions & 0 deletions include/gz/sensors/Sensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -253,6 +253,10 @@ namespace gz
/// trigger.
public: bool HasPendingTrigger() const;

/// \brief Whether the sensor trigger mode is enabled.
/// \return True if the sensor is in trigger mode, false otherwise
public: bool IsTriggered() const;

GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \internal
/// \brief Data pointer for private data
Expand Down
7 changes: 5 additions & 2 deletions src/BoundingBoxCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -321,6 +321,7 @@ bool BoundingBoxCameraSensor::CreateCamera()
this->dataPtr->boundingboxCamera->SetVisibilityMask(
sdfCamera->VisibilityMask());
this->dataPtr->boundingboxCamera->SetBoundingBoxType(this->dataPtr->type);
this->dataPtr->boundingboxCamera->SetLocalPose(this->Pose());

// Add the camera to the scene
this->Scene()->RootVisual()->AddChild(this->dataPtr->rgbCamera);
Expand All @@ -330,11 +331,13 @@ bool BoundingBoxCameraSensor::CreateCamera()
this->AddSensor(this->dataPtr->boundingboxCamera);
this->AddSensor(this->dataPtr->rgbCamera);

// use a copy so we do not modify the original sdfCamera
// when updating bounding box camera
auto sdfCameraCopy = *sdfCamera;
this->UpdateLensIntrinsicsAndProjection(this->dataPtr->rgbCamera,
*sdfCamera);
sdfCameraCopy);
this->UpdateLensIntrinsicsAndProjection(this->dataPtr->boundingboxCamera,
*sdfCamera);

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

Expand Down
4 changes: 1 addition & 3 deletions src/CameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -150,6 +150,7 @@ bool CameraSensor::CreateCamera()
this->dataPtr->camera->SetNearClipPlane(cameraSdf->NearClip());
this->dataPtr->camera->SetFarClipPlane(cameraSdf->FarClip());
this->dataPtr->camera->SetVisibilityMask(cameraSdf->VisibilityMask());
this->dataPtr->camera->SetLocalPose(this->Pose());
this->AddSensor(this->dataPtr->camera);

const std::map<SensorNoiseType, sdf::Noise> noises = {
Expand Down Expand Up @@ -391,9 +392,6 @@ bool CameraSensor::Update(const std::chrono::steady_clock::duration &_now)

std::lock_guard<std::mutex> lock(this->dataPtr->mutex);

// move the camera to the current pose
this->dataPtr->camera->SetLocalPose(this->Pose());

if (this->HasInfoConnections())
{
// publish the camera info message
Expand Down
2 changes: 1 addition & 1 deletion src/DepthCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -351,7 +351,7 @@ bool DepthCameraSensor::CreateCamera()
this->dataPtr->depthCamera->SetFarClipPlane(far);
this->dataPtr->depthCamera->SetVisibilityMask(
cameraSdf->VisibilityMask());

this->dataPtr->depthCamera->SetLocalPose(this->Pose());
this->AddSensor(this->dataPtr->depthCamera);

const std::map<SensorNoiseType, sdf::Noise> noises = {
Expand Down
4 changes: 1 addition & 3 deletions src/GpuLidarSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -194,9 +194,6 @@ bool GpuLidarSensor::CreateLidar()
return false;
}

this->dataPtr->gpuRays->SetWorldPosition(this->Pose().Pos());
this->dataPtr->gpuRays->SetWorldRotation(this->Pose().Rot());

this->dataPtr->gpuRays->SetNearClipPlane(this->RangeMin());
this->dataPtr->gpuRays->SetFarClipPlane(this->RangeMax());

Expand All @@ -214,6 +211,7 @@ bool GpuLidarSensor::CreateLidar()
this->dataPtr->gpuRays->SetRayCount(this->RayCount());
this->dataPtr->gpuRays->SetVerticalRayCount(
this->VerticalRayCount());
this->dataPtr->gpuRays->SetLocalPose(this->Pose());

this->Scene()->RootVisual()->AddChild(
this->dataPtr->gpuRays);
Expand Down
1 change: 1 addition & 0 deletions src/RgbdCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -328,6 +328,7 @@ bool RgbdCameraSensor::CreateCameras()
}

this->dataPtr->depthCamera->SetVisibilityMask(cameraSdf->VisibilityMask());
this->dataPtr->depthCamera->SetLocalPose(this->Pose());

this->AddSensor(this->dataPtr->depthCamera);

Expand Down
1 change: 1 addition & 0 deletions src/SegmentationCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -369,6 +369,7 @@ bool SegmentationCameraSensor::CreateCamera()
this->dataPtr->camera->SetFarClipPlane(sdfCamera->FarClip());
this->dataPtr->camera->SetAspectRatio(aspectRatio);
this->dataPtr->camera->SetHFOV(angle);
this->dataPtr->camera->SetLocalPose(this->Pose());

// Add the camera to the scene
this->Scene()->RootVisual()->AddChild(this->dataPtr->camera);
Expand Down
9 changes: 8 additions & 1 deletion src/Sensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -653,10 +653,17 @@ void SensorPrivate::DisableTriggered() {
}

//////////////////////////////////////////////////
bool Sensor::HasPendingTrigger() const {
bool Sensor::HasPendingTrigger() const
{
if (!this->dataPtr->IsTriggered())
return false;

std::lock_guard<std::mutex> triggerLock(this->dataPtr->triggerMutex);
return this->dataPtr->pendingTrigger;
}

//////////////////////////////////////////////////
bool Sensor::IsTriggered() const
{
return this->dataPtr->IsTriggered();
}
2 changes: 2 additions & 0 deletions src/Sensor_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -477,8 +477,10 @@ TEST(Sensor_TEST, Trigger)
sensor.SetUpdateRate(5);
EXPECT_DOUBLE_EQ(kUpdateRate, sensor.UpdateRate());

EXPECT_FALSE(sensor.IsTriggered());
constexpr char kTriggerTopic[] = "/trigger";
EXPECT_TRUE(sensor.SetTriggered(true, kTriggerTopic));
EXPECT_TRUE(sensor.IsTriggered());
EXPECT_FALSE(sensor.HasPendingTrigger());

transport::Node node;
Expand Down
2 changes: 1 addition & 1 deletion src/ThermalCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -300,7 +300,7 @@ bool ThermalCameraSensor::CreateCamera()
this->dataPtr->thermalCamera->SetMinTemperature(this->dataPtr->minTemp);
this->dataPtr->thermalCamera->SetMaxTemperature(this->dataPtr->maxTemp);
this->dataPtr->thermalCamera->SetLinearResolution(this->dataPtr->resolution);

this->dataPtr->thermalCamera->SetLocalPose(this->Pose());
this->AddSensor(this->dataPtr->thermalCamera);

const std::map<SensorNoiseType, sdf::Noise> noises = {
Expand Down
4 changes: 1 addition & 3 deletions src/WideAngleCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -240,6 +240,7 @@ bool WideAngleCameraSensor::CreateCamera()
this->dataPtr->camera->SetNearClipPlane(cameraSdf->NearClip());
this->dataPtr->camera->SetFarClipPlane(cameraSdf->FarClip());
this->dataPtr->camera->SetVisibilityMask(cameraSdf->VisibilityMask());
this->dataPtr->camera->SetLocalPose(this->Pose());

rendering::CameraLens lens;
std::string lensType = cameraSdf->LensType();
Expand Down Expand Up @@ -413,9 +414,6 @@ bool WideAngleCameraSensor::Update(
return false;
}

// move the camera to the current pose
this->dataPtr->camera->SetLocalPose(this->Pose());

// render only if necessary
if (!this->dataPtr->pub.HasConnections() &&
this->dataPtr->imageEvent.ConnectionCount() <= 0 &&
Expand Down

0 comments on commit e642ad6

Please sign in to comment.