Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merge ign-sensors6 ➡️ gz-sensors7 #283

Merged
merged 12 commits into from
Nov 11, 2022
17 changes: 16 additions & 1 deletion Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -327,7 +327,22 @@

## Gazebo Sensors 3

### Gazebo Sensors 3.X.X (202X-XX-XX)
### Gazebo Sensors 3.4.0 (2022-08-16)

1. Remove redundant namespace references
* [Pull request #258](https://github.com/gazebosim/gz-sensors/pull/258)

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

1. Conform to ros format for header field `frame_id` of sensor msgs
* [Pull request #195](https://github.com/gazebosim/gz-sensors/pull/195)

1. Fix compiler warnings (`CMP0072` and copy elision)
* [Pull request #188](https://github.com/gazebosim/gz-sensors/pull/188)

1. Require ign-transport >= 8.2
* [Pull request #167](https://github.com/gazebosim/gz-sensors/pull/167)

### Gazebo Sensors 3.3.0 (2021-08-26)

Expand Down
16 changes: 8 additions & 8 deletions src/AirPressureSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,14 @@
*
*/

#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#if defined(_MSC_VER)
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <gz/msgs/fluid_pressure.pb.h>
#ifdef _WIN32
#pragma warning(pop)
#if defined(_MSC_VER)
#pragma warning(pop)
#endif
#include <gz/msgs/Utility.hh>

Expand Down Expand Up @@ -114,7 +114,7 @@ bool AirPressureSensor::Load(const sdf::Sensor &_sdf)
this->SetTopic("/air_pressure");

this->dataPtr->pub =
this->dataPtr->node.Advertise<gz::msgs::FluidPressure>(
this->dataPtr->node.Advertise<msgs::FluidPressure>(
this->Topic());

if (!this->dataPtr->pub)
Expand Down Expand Up @@ -194,7 +194,7 @@ bool AirPressureSensor::Update(
NoiseType::GAUSSIAN)
{
GaussianNoiseModelPtr gaussian =
std::dynamic_pointer_cast<sensors::GaussianNoiseModel>(
std::dynamic_pointer_cast<GaussianNoiseModel>(
this->dataPtr->noises[AIR_PRESSURE_NOISE_PASCALS]);
msg.set_variance(sqrt(gaussian->StdDev()));
}
Expand Down
14 changes: 7 additions & 7 deletions src/AltimeterSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,14 @@
*
*/

#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#if defined(_MSC_VER)
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <gz/msgs/altimeter.pb.h>
#ifdef _WIN32
#pragma warning(pop)
#if defined(_MSC_VER)
#pragma warning(pop)
#endif

#include <gz/common/Profiler.hh>
Expand Down Expand Up @@ -103,7 +103,7 @@ bool AltimeterSensor::Load(const sdf::Sensor &_sdf)
this->SetTopic("/altimeter");

this->dataPtr->pub =
this->dataPtr->node.Advertise<gz::msgs::Altimeter>(this->Topic());
this->dataPtr->node.Advertise<msgs::Altimeter>(this->Topic());

if (!this->dataPtr->pub)
{
Expand Down
53 changes: 38 additions & 15 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
set (sources
BrownDistortionModel.cc
Distortion.cc
GaussianNoiseModel.cc
Manager.cc
Sensor.cc
Noise.cc
GaussianNoiseModel.cc
Distortion.cc
BrownDistortionModel.cc
PointCloudUtil.cc
Sensor.cc
SensorFactory.cc
SensorTypes.cc
Util.cc
Expand All @@ -14,10 +14,10 @@ set (sources
set(rendering_sources
RenderingSensor.cc
RenderingEvents.cc
ImageGaussianNoiseModel.cc
ImageNoise.cc
ImageBrownDistortionModel.cc
ImageDistortion.cc
ImageGaussianNoiseModel.cc
ImageNoise.cc
)

set (gtest_sources
Expand Down Expand Up @@ -58,7 +58,11 @@ target_link_libraries(${rendering_target}
)

set(camera_sources CameraSensor.cc)
gz_add_component(camera SOURCES ${camera_sources} GET_TARGET_NAME camera_target)
gz_add_component(camera
SOURCES ${camera_sources}
DEPENDS_ON_COMPONENTS rendering
GET_TARGET_NAME camera_target
)
# custom compile definitions since the one provided automatically is versioned and will
# make the code need to change with every major version
target_compile_definitions(${camera_target} PUBLIC CameraSensor_EXPORTS)
Expand All @@ -71,7 +75,11 @@ target_link_libraries(${camera_target}
)

set(depth_camera_sources DepthCameraSensor.cc)
gz_add_component(depth_camera SOURCES ${depth_camera_sources} GET_TARGET_NAME depth_camera_target)
gz_add_component(depth_camera
SOURCES ${depth_camera_sources}
DEPENDS_ON_COMPONENTS camera
GET_TARGET_NAME depth_camera_target
)
target_compile_definitions(${depth_camera_target} PUBLIC DepthCameraSensor_EXPORTS)
target_link_libraries(${depth_camera_target}
PRIVATE
Expand All @@ -81,7 +89,11 @@ target_link_libraries(${depth_camera_target}
)

set(lidar_sources Lidar.cc)
gz_add_component(lidar SOURCES ${lidar_sources} GET_TARGET_NAME lidar_target)
gz_add_component(lidar
SOURCES ${lidar_sources}
DEPENDS_ON_COMPONENTS rendering
GET_TARGET_NAME lidar_target
)
target_compile_definitions(${lidar_target} PUBLIC Lidar_EXPORTS)
target_link_libraries(${lidar_target}
PUBLIC
Expand All @@ -92,7 +104,11 @@ target_link_libraries(${lidar_target}
)

set(gpu_lidar_sources GpuLidarSensor.cc)
gz_add_component(gpu_lidar SOURCES ${gpu_lidar_sources} GET_TARGET_NAME gpu_lidar_target)
gz_add_component(gpu_lidar
DEPENDS_ON_COMPONENTS lidar
SOURCES ${gpu_lidar_sources}
GET_TARGET_NAME gpu_lidar_target
)
target_compile_definitions(${gpu_lidar_target} PUBLIC GpuLidarSensor_EXPORTS)
target_link_libraries(${gpu_lidar_target}
PRIVATE
Expand All @@ -116,20 +132,23 @@ gz_add_component(magnetometer SOURCES ${magnetometer_sources} GET_TARGET_NAME ma
set(imu_sources ImuSensor.cc)
gz_add_component(imu SOURCES ${imu_sources} GET_TARGET_NAME imu_target)

set(force_torque_sources ForceTorqueSensor.cc)
gz_add_component(force_torque SOURCES ${force_torque_sources} GET_TARGET_NAME force_torque_target)

set(altimeter_sources AltimeterSensor.cc)
gz_add_component(altimeter SOURCES ${altimeter_sources} GET_TARGET_NAME altimeter_target)

set(air_pressure_sources AirPressureSensor.cc)
gz_add_component(air_pressure SOURCES ${air_pressure_sources} GET_TARGET_NAME air_pressure_target)
set(force_torque_sources ForceTorqueSensor.cc)
gz_add_component(force_torque SOURCES ${force_torque_sources} GET_TARGET_NAME force_torque_target)

set(navsat_sources NavSatSensor.cc)
gz_add_component(navsat SOURCES ${navsat_sources} GET_TARGET_NAME navsat_target)

set(rgbd_camera_sources RgbdCameraSensor.cc)
gz_add_component(rgbd_camera SOURCES ${rgbd_camera_sources} GET_TARGET_NAME rgbd_camera_target)
gz_add_component(rgbd_camera
SOURCES ${rgbd_camera_sources}
DEPENDS_ON_COMPONENTS camera
GET_TARGET_NAME rgbd_camera_target
)
target_compile_definitions(${rgbd_camera_target} PUBLIC RgbdCameraSensor_EXPORTS)
target_link_libraries(${rgbd_camera_target}
PRIVATE
Expand All @@ -139,7 +158,11 @@ target_link_libraries(${rgbd_camera_target}
)

set(thermal_camera_sources ThermalCameraSensor.cc)
gz_add_component(thermal_camera SOURCES ${thermal_camera_sources} GET_TARGET_NAME thermal_camera_target)
gz_add_component(thermal_camera
SOURCES ${thermal_camera_sources}
DEPENDS_ON_COMPONENTS camera
GET_TARGET_NAME thermal_camera_target
)
target_link_libraries(${thermal_camera_target}
PRIVATE
${camera_target}
Expand Down
55 changes: 33 additions & 22 deletions src/CameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class gz::sensors::CameraSensorPrivate
{
/// \brief Callback for triggered subscription
/// \param[in] _msg Boolean message
public: void OnTrigger(const gz::msgs::Boolean &_msg);
public: void OnTrigger(const msgs::Boolean &_msg);

/// \brief Save an image
/// \param[in] _data the image data to be saved
Expand Down Expand Up @@ -125,6 +125,9 @@ class gz::sensors::CameraSensorPrivate
/// \brief Camera information message.
public: msgs::CameraInfo infoMsg;

/// \brief The frame this camera uses in its camera_info topic.
public: std::string opticalFrameId{""};

/// \brief Topic for info message.
public: std::string infoTopic{""};

Expand Down Expand Up @@ -208,13 +211,13 @@ bool CameraSensor::CreateCamera()
switch (pixelFormat)
{
case sdf::PixelFormatType::RGB_INT8:
this->dataPtr->camera->SetImageFormat(gz::rendering::PF_R8G8B8);
this->dataPtr->camera->SetImageFormat(rendering::PF_R8G8B8);
break;
case sdf::PixelFormatType::L_INT8:
this->dataPtr->camera->SetImageFormat(gz::rendering::PF_L8);
this->dataPtr->camera->SetImageFormat(rendering::PF_L8);
break;
case sdf::PixelFormatType::L_INT16:
this->dataPtr->camera->SetImageFormat(gz::rendering::PF_L16);
this->dataPtr->camera->SetImageFormat(rendering::PF_L16);
break;
default:
gzerr << "Unsupported pixel format ["
Expand Down Expand Up @@ -435,16 +438,16 @@ bool CameraSensor::Update(const std::chrono::steady_clock::duration &_now)

switch (this->dataPtr->camera->ImageFormat())
{
case gz::rendering::PF_R8G8B8:
format = gz::common::Image::RGB_INT8;
case rendering::PF_R8G8B8:
format = common::Image::RGB_INT8;
msgsPixelFormat = msgs::PixelFormatType::RGB_INT8;
break;
case gz::rendering::PF_L8:
format = gz::common::Image::L_INT8;
case rendering::PF_L8:
format = common::Image::L_INT8;
msgsPixelFormat = msgs::PixelFormatType::L_INT8;
break;
case gz::rendering::PF_L16:
format = gz::common::Image::L_INT16;
case rendering::PF_L16:
format = common::Image::L_INT16;
msgsPixelFormat = msgs::PixelFormatType::L_INT16;
break;
default:
Expand All @@ -454,7 +457,7 @@ bool CameraSensor::Update(const std::chrono::steady_clock::duration &_now)
}

// create message
gz::msgs::Image msg;
msgs::Image msg;
{
GZ_PROFILE("CameraSensor::Update Message");
msg.set_width(width);
Expand All @@ -465,7 +468,7 @@ bool CameraSensor::Update(const std::chrono::steady_clock::duration &_now)
*msg.mutable_header()->mutable_stamp() = msgs::Convert(_now);
auto frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
frame->add_value(this->FrameId());
frame->add_value(this->dataPtr->opticalFrameId);
msg.set_data(data, this->dataPtr->camera->ImageMemorySize());
}

Expand Down Expand Up @@ -645,19 +648,18 @@ void CameraSensor::PopulateInfo(const sdf::Camera *_cameraSdf)
intrinsics->add_k(0.0);
intrinsics->add_k(1.0);

// TODO(anyone) Get tx and ty from SDF
msgs::CameraInfo::Projection *proj =
this->dataPtr->infoMsg.mutable_projection();

proj->add_p(_cameraSdf->LensIntrinsicsFx());
proj->add_p(_cameraSdf->LensProjectionFx());
proj->add_p(0.0);
proj->add_p(_cameraSdf->LensIntrinsicsCx());
proj->add_p(-_cameraSdf->LensIntrinsicsFx() * this->dataPtr->baseline);
proj->add_p(_cameraSdf->LensProjectionCx());
proj->add_p(_cameraSdf->LensProjectionTx());

proj->add_p(0.0);
proj->add_p(_cameraSdf->LensIntrinsicsFy());
proj->add_p(_cameraSdf->LensIntrinsicsCy());
proj->add_p(0.0);
proj->add_p(_cameraSdf->LensProjectionFy());
proj->add_p(_cameraSdf->LensProjectionCy());
proj->add_p(_cameraSdf->LensProjectionTy());

proj->add_p(0.0);
proj->add_p(0.0);
Expand All @@ -679,11 +681,20 @@ void CameraSensor::PopulateInfo(const sdf::Camera *_cameraSdf)

// Note: while Gazebo interprets the camera frame to be looking towards +X,
// other tools, such as ROS, may interpret this frame as looking towards +Z.
// TODO(anyone) Expose the `frame_id` as an SDF parameter so downstream users
// can populate it with arbitrary frames.
// To make this configurable the user has the option to set an optical frame.
// If the user has set <optical_frame_id> in the cameraSdf use it,
// otherwise fall back to the sensor frame.
if (_cameraSdf->OpticalFrameId().empty())
{
this->dataPtr->opticalFrameId = this->FrameId();
}
else
{
this->dataPtr->opticalFrameId = _cameraSdf->OpticalFrameId();
}
auto infoFrame = this->dataPtr->infoMsg.mutable_header()->add_data();
infoFrame->set_key("frame_id");
infoFrame->add_value(this->FrameId());
infoFrame->add_value(this->dataPtr->opticalFrameId);

this->dataPtr->infoMsg.set_width(width);
this->dataPtr->infoMsg.set_height(height);
Expand Down
8 changes: 8 additions & 0 deletions src/Camera_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,14 @@ sdf::ElementPtr CameraToSdf(const std::string &_type,
<< " <cy>124</cy>"
<< " <s>1.2</s>"
<< " </intrinsics>"
<< " <projection>"
<< " <p_fx>282</p_fx>"
<< " <p_fy>283</p_fy>"
<< " <p_cx>163</p_cx>"
<< " <p_cy>125</p_cy>"
<< " <tx>1</tx>"
<< " <ty>2</ty>"
<< " </projection>"
<< " </lens>"
<< " </camera>"
<< " </sensor>"
Expand Down
Loading