|
| 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 | +} |
0 commit comments