Skip to content

Commit 960ce0f

Browse files
committed
Merge remote-tracking branch 'origin/ign-gazebo6' into azeey/6_to_main
2 parents 2e141c2 + b753afe commit 960ce0f

File tree

5 files changed

+174
-1
lines changed

5 files changed

+174
-1
lines changed

src/rendering/RenderUtil.cc

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -214,7 +214,7 @@ class gz::sim::RenderUtilPrivate
214214
/// \brief Scene background color. This is optional because a <scene> is
215215
/// always present, which has a default background color value. This
216216
/// backgroundColor variable is used to override the <scene> value.
217-
public: std::optional<math::Color> backgroundColor = math::Color::Black;
217+
public: std::optional<math::Color> backgroundColor;
218218

219219
/// \brief Ambient color. This is optional because an <scene> is always
220220
/// present, which has a default ambient light value. This ambientLight

src/systems/sensors/Sensors.cc

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -849,6 +849,11 @@ bool SensorsPrivate::HasConnections(sensors::RenderingSensor *_sensor) const
849849

850850
// \todo(iche033) Remove this function once a virtual
851851
// sensors::RenderingSensor::HasConnections function is available
852+
{
853+
auto s = dynamic_cast<sensors::RgbdCameraSensor *>(_sensor);
854+
if (s)
855+
return s->HasConnections();
856+
}
852857
{
853858
auto s = dynamic_cast<sensors::DepthCameraSensor *>(_sensor);
854859
if (s)

test/integration/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -79,6 +79,7 @@ endif()
7979
# Tests that require a valid display
8080
set(tests_needing_display
8181
camera_sensor_background.cc
82+
camera_sensor_background_from_scene.cc
8283
camera_video_record_system.cc
8384
depth_camera.cc
8485
distortion_camera.cc
Lines changed: 109 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,109 @@
1+
/*
2+
* Copyright (C) 2022 Open Source Robotics Foundation
3+
*
4+
* Licensed under the Apache License, Version 2.0 (the "License");
5+
* you may not use this file except in compliance with the License.
6+
* You may obtain a copy of the License at
7+
*
8+
* http://www.apache.org/licenses/LICENSE-2.0
9+
*
10+
* Unless required by applicable law or agreed to in writing, software
11+
* distributed under the License is distributed on an "AS IS" BASIS,
12+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
* See the License for the specific language governing permissions and
14+
* limitations under the License.
15+
*
16+
*/
17+
18+
#include <gtest/gtest.h>
19+
20+
#include <string>
21+
22+
#include <ignition/transport/Node.hh>
23+
#include <ignition/utilities/ExtraTestMacros.hh>
24+
25+
#include "ignition/gazebo/Server.hh"
26+
#include "ignition/gazebo/SystemLoader.hh"
27+
#include "ignition/gazebo/Util.hh"
28+
#include "ignition/gazebo/test_config.hh"
29+
30+
#include "../helpers/EnvTestFixture.hh"
31+
32+
using namespace ignition;
33+
using namespace std::chrono_literals;
34+
35+
std::mutex mutex;
36+
int cbCount = 0;
37+
38+
//////////////////////////////////////////////////
39+
/// Note: This test is almost identical to the test in
40+
/// camera_sensor_scene_background.cc, and the `cameraCb` could have been
41+
/// reused, but loading the world twice in a single processes causes errors with
42+
/// Ogre.
43+
class CameraSensorBackgroundFixture :
44+
public InternalFixture<InternalFixture<::testing::Test>>
45+
{
46+
};
47+
48+
/////////////////////////////////////////////////
49+
void cameraCb(const msgs::Image & _msg)
50+
{
51+
ASSERT_EQ(msgs::PixelFormatType::RGB_INT8,
52+
_msg.pixel_format_type());
53+
54+
for (unsigned int y = 0; y < _msg.height(); ++y)
55+
{
56+
for (unsigned int x = 0; x < _msg.width(); ++x)
57+
{
58+
// The "/test/worlds/camera_sensor_scene_background.sdf" world has set a
59+
// background color of 1,0,0,1. So, all the pixels returned by the
60+
// camera should be red.
61+
unsigned char r = _msg.data()[y * _msg.step() + x*3];
62+
ASSERT_EQ(255, static_cast<int>(r));
63+
64+
unsigned char g = _msg.data()[y * _msg.step() + x*3+1];
65+
ASSERT_EQ(0, static_cast<int>(g));
66+
67+
unsigned char b = _msg.data()[y * _msg.step() + x*3+2];
68+
ASSERT_EQ(0, static_cast<int>(b));
69+
}
70+
}
71+
std::lock_guard<std::mutex> lock(mutex);
72+
cbCount++;
73+
}
74+
75+
/////////////////////////////////////////////////
76+
// Test sensors use the background color of <scene> by default
77+
TEST_F(CameraSensorBackgroundFixture,
78+
IGN_UTILS_TEST_DISABLED_ON_MAC(RedBackgroundFromScene))
79+
{
80+
const auto sdfFile = common::joinPaths(std::string(PROJECT_SOURCE_PATH),
81+
"test", "worlds", "camera_sensor_scene_background.sdf");
82+
// Start server
83+
gazebo::ServerConfig serverConfig;
84+
serverConfig.SetSdfFile(sdfFile);
85+
86+
gazebo::Server server(serverConfig);
87+
EXPECT_FALSE(server.Running());
88+
EXPECT_FALSE(*server.Running(0));
89+
90+
// subscribe to the camera topic
91+
transport::Node node;
92+
cbCount = 0;
93+
node.Subscribe("/camera", &cameraCb);
94+
95+
// Run server and verify that we are receiving a message
96+
// from the depth camera
97+
server.Run(true, 100, false);
98+
99+
int i = 0;
100+
while (i < 100 && cbCount <= 0)
101+
{
102+
std::this_thread::sleep_for(std::chrono::milliseconds(100));
103+
i++;
104+
}
105+
106+
std::lock_guard<std::mutex> lock(mutex);
107+
EXPECT_GE(cbCount, 1);
108+
109+
}
Lines changed: 58 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
<?xml version="1.0" ?>
2+
<sdf version="1.6">
3+
<world name="sensors">
4+
<physics name="1ms" type="ignored">
5+
<max_step_size>.001</max_step_size>
6+
<real_time_factor>0</real_time_factor>
7+
</physics>
8+
<plugin
9+
filename="ignition-gazebo-physics-system"
10+
name="ignition::gazebo::systems::Physics">
11+
</plugin>
12+
<plugin
13+
filename="ignition-gazebo-sensors-system"
14+
name="ignition::gazebo::systems::Sensors">
15+
<render_engine>ogre2</render_engine>
16+
</plugin>
17+
18+
<scene>
19+
<background>1 0 0</background>
20+
</scene>
21+
22+
<model name="camera">
23+
<static>true</static>
24+
<pose>0 0 1.0 0 0 0</pose>
25+
<link name="link">
26+
<collision name="collision">
27+
<geometry>
28+
<box>
29+
<size>0.1 0.1 0.1</size>
30+
</box>
31+
</geometry>
32+
</collision>
33+
<visual name="visual">
34+
<geometry>
35+
<box>
36+
<size>0.1 0.1 0.1</size>
37+
</box>
38+
</geometry>
39+
</visual>
40+
<sensor name="camera" type="camera">
41+
<camera>
42+
<horizontal_fov>1.047</horizontal_fov>
43+
<image>
44+
<width>320</width>
45+
<height>240</height>
46+
</image>
47+
<clip>
48+
<near>0.1</near>
49+
<far>100</far>
50+
</clip>
51+
</camera>
52+
<update_rate>30</update_rate>
53+
<topic>camera</topic>
54+
</sensor>
55+
</link>
56+
</model>
57+
</world>
58+
</sdf>

0 commit comments

Comments
 (0)