Skip to content

Merge ign-gazebo6 ➡️ main #1519

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

Merged
merged 4 commits into from
Jun 8, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion src/rendering/RenderUtil.cc
Original file line number Diff line number Diff line change
Expand Up @@ -214,7 +214,7 @@ class gz::sim::RenderUtilPrivate
/// \brief Scene background color. This is optional because a <scene> is
/// always present, which has a default background color value. This
/// backgroundColor variable is used to override the <scene> value.
public: std::optional<math::Color> backgroundColor = math::Color::Black;
public: std::optional<math::Color> backgroundColor;

/// \brief Ambient color. This is optional because an <scene> is always
/// present, which has a default ambient light value. This ambientLight
Expand Down
5 changes: 5 additions & 0 deletions src/systems/sensors/Sensors.cc
Original file line number Diff line number Diff line change
Expand Up @@ -849,6 +849,11 @@ bool SensorsPrivate::HasConnections(sensors::RenderingSensor *_sensor) const

// \todo(iche033) Remove this function once a virtual
// sensors::RenderingSensor::HasConnections function is available
{
auto s = dynamic_cast<sensors::RgbdCameraSensor *>(_sensor);
if (s)
return s->HasConnections();
}
{
auto s = dynamic_cast<sensors::DepthCameraSensor *>(_sensor);
if (s)
Expand Down
1 change: 1 addition & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,7 @@ endif()
# Tests that require a valid display
set(tests_needing_display
camera_sensor_background.cc
camera_sensor_background_from_scene.cc
camera_video_record_system.cc
depth_camera.cc
distortion_camera.cc
Expand Down
109 changes: 109 additions & 0 deletions test/integration/camera_sensor_background_from_scene.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,109 @@
/*
* Copyright (C) 2022 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include <gtest/gtest.h>

#include <string>

#include <gz/transport/Node.hh>
#include <gz/utils/ExtraTestMacros.hh>

#include "gz/sim/Server.hh"
#include "gz/sim/SystemLoader.hh"
#include "gz/sim/Util.hh"
#include "gz/sim/test_config.hh"

#include "../helpers/EnvTestFixture.hh"

using namespace gz;
using namespace std::chrono_literals;

std::mutex mutex;
int cbCount = 0;

//////////////////////////////////////////////////
/// Note: This test is almost identical to the test in
/// camera_sensor_scene_background.cc, and the `cameraCb` could have been
/// reused, but loading the world twice in a single processes causes errors with
/// Ogre.
class CameraSensorBackgroundFixture :
public InternalFixture<InternalFixture<::testing::Test>>
{
};

/////////////////////////////////////////////////
void cameraCb(const msgs::Image & _msg)
{
ASSERT_EQ(msgs::PixelFormatType::RGB_INT8,
_msg.pixel_format_type());

for (unsigned int y = 0; y < _msg.height(); ++y)
{
for (unsigned int x = 0; x < _msg.width(); ++x)
{
// The "/test/worlds/camera_sensor_scene_background.sdf" world has set a
// background color of 1,0,0,1. So, all the pixels returned by the
// camera should be red.
unsigned char r = _msg.data()[y * _msg.step() + x*3];
ASSERT_EQ(255, static_cast<int>(r));

unsigned char g = _msg.data()[y * _msg.step() + x*3+1];
ASSERT_EQ(0, static_cast<int>(g));

unsigned char b = _msg.data()[y * _msg.step() + x*3+2];
ASSERT_EQ(0, static_cast<int>(b));
}
}
std::lock_guard<std::mutex> lock(mutex);
cbCount++;
}

/////////////////////////////////////////////////
// Test sensors use the background color of <scene> by default
TEST_F(CameraSensorBackgroundFixture,
IGN_UTILS_TEST_DISABLED_ON_MAC(RedBackgroundFromScene))
{
const auto sdfFile = common::joinPaths(std::string(PROJECT_SOURCE_PATH),
"test", "worlds", "camera_sensor_scene_background.sdf");
// Start server
sim::ServerConfig serverConfig;
serverConfig.SetSdfFile(sdfFile);

sim::Server server(serverConfig);
EXPECT_FALSE(server.Running());
EXPECT_FALSE(*server.Running(0));

// subscribe to the camera topic
transport::Node node;
cbCount = 0;
node.Subscribe("/camera", &cameraCb);

// Run server and verify that we are receiving a message
// from the depth camera
server.Run(true, 100, false);

int i = 0;
while (i < 100 && cbCount <= 0)
{
std::this_thread::sleep_for(std::chrono::milliseconds(100));
i++;
}

std::lock_guard<std::mutex> lock(mutex);
EXPECT_GE(cbCount, 1);

}
58 changes: 58 additions & 0 deletions test/worlds/camera_sensor_scene_background.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="sensors">
<physics name="1ms" type="ignored">
<max_step_size>.001</max_step_size>
<real_time_factor>0</real_time_factor>
</physics>
<plugin
filename="ignition-gazebo-physics-system"
name="gz::sim::systems::Physics">
</plugin>
<plugin
filename="ignition-gazebo-sensors-system"
name="gz::sim::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>

<scene>
<background>1 0 0</background>
</scene>

<model name="camera">
<static>true</static>
<pose>0 0 1.0 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</visual>
<sensor name="camera" type="camera">
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<update_rate>30</update_rate>
<topic>camera</topic>
</sensor>
</link>
</model>
</world>
</sdf>