diff --git a/.gitignore b/.gitignore index 40d7c0f5e3..1c6c5461d5 100644 --- a/.gitignore +++ b/.gitignore @@ -15,3 +15,8 @@ build_* # clangd index .cache + + +# Python cache +__pycache__ +*.pyc diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index dcee71604b..bd025f0959 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -28,6 +28,7 @@ else() set(GZ_PYTHON_INSTALL_PATH ${GZ_LIB_INSTALL_DIR}/python) endif() +set(GZ_PYTHON_EXECUTABLE ${Python3_EXECUTABLE}) set(GZ_PYTHON_INSTALL_PATH "${GZ_PYTHON_INSTALL_PATH}/gz") # Set the build location and install location for a CPython extension @@ -88,7 +89,7 @@ if (BUILD_TESTING) testFixture_TEST ) - execute_process(COMMAND "${PYTHON_EXECUTABLE}" -m pytest --version + execute_process(COMMAND "${GZ_PYTHON_EXECUTABLE}" -m pytest --version OUTPUT_VARIABLE PYTEST_output ERROR_VARIABLE PYTEST_error RESULT_VARIABLE PYTEST_result) @@ -101,17 +102,17 @@ if (BUILD_TESTING) foreach (test ${python_tests}) if (pytest_FOUND) - add_test(NAME ${test}.py COMMAND - "${PYTHON_EXECUTABLE}" -m pytest "${CMAKE_SOURCE_DIR}/python/test/${test}.py" --junitxml "${CMAKE_BINARY_DIR}/test_results/UNIT_${test}.xml") + add_test(NAME ${test} COMMAND + "${GZ_PYTHON_EXECUTABLE}" -m pytest "${CMAKE_SOURCE_DIR}/python/test/${test}.py" --junitxml "${CMAKE_BINARY_DIR}/test_results/UNIT_${test}.xml") else() - add_test(NAME ${test}.py COMMAND - "${PYTHON_EXECUTABLE}" "${CMAKE_SOURCE_DIR}/python/test/${test}.py") + add_test(NAME ${test} COMMAND + "${GZ_PYTHON_EXECUTABLE}" "${CMAKE_SOURCE_DIR}/python/test/${test}.py") endif() set(_env_vars) list(APPEND _env_vars "PYTHONPATH=${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_LIBDIR}/python/") list(APPEND _env_vars "LD_LIBRARY_PATH=${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_LIBDIR}:$ENV{LD_LIBRARY_PATH}") - set_tests_properties(${test}.py PROPERTIES + set_tests_properties(${test} PROPERTIES ENVIRONMENT "${_env_vars}") endforeach() endif() diff --git a/python/test/testFixture_TEST.py b/python/test/testFixture_TEST.py old mode 100644 new mode 100755 diff --git a/src/Conversions_TEST.cc b/src/Conversions_TEST.cc index 76b2f77eb3..c0934944e9 100644 --- a/src/Conversions_TEST.cc +++ b/src/Conversions_TEST.cc @@ -1032,9 +1032,10 @@ TEST(Conversions, ParticleEmitter) EXPECT_NEAR(0.2, emitterMsg.max_velocity().data(), 1e-3); EXPECT_EQ(math::Vector3d(1, 2, 3), msgs::Convert(emitterMsg.size())); EXPECT_EQ(math::Vector3d(4, 5, 6), msgs::Convert(emitterMsg.particle_size())); - EXPECT_EQ(math::Color(0.1, 0.2, 0.3), + EXPECT_EQ(math::Color(0.1f, 0.2f, 0.3f), msgs::Convert(emitterMsg.color_start())); - EXPECT_EQ(math::Color(0.4, 0.5, 0.6), msgs::Convert(emitterMsg.color_end())); + EXPECT_EQ(math::Color(0.4f, 0.5f, 0.6f), + msgs::Convert(emitterMsg.color_end())); EXPECT_EQ("range_image", emitterMsg.color_range_image().data()); auto header = emitterMsg.header().data(0); diff --git a/src/SdfGenerator_TEST.cc b/src/SdfGenerator_TEST.cc index a189b315bc..1c76cef68e 100644 --- a/src/SdfGenerator_TEST.cc +++ b/src/SdfGenerator_TEST.cc @@ -348,7 +348,7 @@ class ModelElementFixture : public ElementUpdateFixture ///////////////////////////////////////////////// TEST_F(ModelElementFixture, ModelsInline) { - this->LoadWorld("test/worlds/shapes.sdf"); + this->LoadWorld(common::joinPaths("test", "worlds", "shapes.sdf")); this->TestModel("box"); this->TestModel("capsule"); this->TestModel("cylinder"); @@ -359,7 +359,7 @@ TEST_F(ModelElementFixture, ModelsInline) ///////////////////////////////////////////////// TEST_F(ModelElementFixture, ModelIncluded) { - this->LoadWorld("test/worlds/save_world.sdf"); + this->LoadWorld(common::joinPaths("test", "worlds", "save_world.sdf")); this->TestModel("backpack1"); this->TestModel("backpack2"); } @@ -367,7 +367,7 @@ TEST_F(ModelElementFixture, ModelIncluded) ///////////////////////////////////////////////// TEST_F(ModelElementFixture, ModelComponentUpdate) { - this->LoadWorld("test/worlds/shapes.sdf"); + this->LoadWorld(common::joinPaths("test", "worlds", "shapes.sdf")); std::string modelName = "box"; Entity modelEntity = this->ecm.EntityByComponents( components::Model(), components::Name(modelName)); @@ -461,8 +461,7 @@ TEST_F(ElementUpdateFixture, ConfigOverrideCopyOrMerge) ///////////////////////////////////////////////// TEST_F(ElementUpdateFixture, ConfigOverride) { - const std::string worldFile{"test/worlds/save_world.sdf"}; - this->LoadWorld(worldFile); + this->LoadWorld(common::joinPaths("test", "worlds", "save_world.sdf")); Entity worldEntity = this->ecm.EntityByComponents(components::World()); { this->sdfGenConfig.mutable_global_entity_gen_config() @@ -522,8 +521,7 @@ TEST_F(ElementUpdateFixture, ConfigOverride) ///////////////////////////////////////////////// TEST_F(ElementUpdateFixture, WorldWithModelsInline) { - const std::string worldFile{"test/worlds/shapes.sdf"}; - this->LoadWorld(worldFile); + this->LoadWorld(common::joinPaths("test", "worlds", "shapes.sdf")); Entity worldEntity = this->ecm.EntityByComponents(components::World()); auto elem = std::make_shared(); sdf::initFile("world.sdf", elem); @@ -535,7 +533,7 @@ TEST_F(ElementUpdateFixture, WorldWithModelsInline) ///////////////////////////////////////////////// TEST_F(ElementUpdateFixture, WorldWithModelsIncludedExpanded) { - this->LoadWorld("test/worlds/save_world.sdf"); + this->LoadWorld(common::joinPaths("test", "worlds", "save_world.sdf")); Entity worldEntity = this->ecm.EntityByComponents(components::World()); auto elem = std::make_shared(); sdf::initFile("world.sdf", elem); @@ -586,7 +584,7 @@ TEST_F(ElementUpdateFixture, WorldComponentUpdate) ///////////////////////////////////////////////// TEST_F(ElementUpdateFixture, WorldWithModelsIncludedNotExpanded) { - const std::string worldFile{"test/worlds/save_world.sdf"}; + const auto worldFile = common::joinPaths("test", "worlds", "save_world.sdf"); this->LoadWorld(worldFile); Entity worldEntity = this->ecm.EntityByComponents(components::World()); auto elem = std::make_shared(); @@ -644,17 +642,17 @@ TEST_F(ElementUpdateFixture, WorldWithModelsIncludedNotExpanded) TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithInvalidUris) { const std::string goodUri = - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/2"; + "https://fuel.gazebosim.org/1.0/openroboticstest/models/backpack/2"; // These are URIs that are potentially problematic. const std::vector fuelUris = { // Thes following two URIs are valid, but have a trailing '/' - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/", - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/2/", + "https://fuel.gazebosim.org/1.0/openroboticstest/models/backpack/", + "https://fuel.gazebosim.org/1.0/openroboticstest/models/backpack/2/", // Thes following two URIs are invalid, and will not be saved - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/" + "https://fuel.gazebosim.org/1.0/openroboticstest/models/backpack/" "notInt", - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/" + "https://fuel.gazebosim.org/1.0/openroboticstest/models/backpack/" "notInt/", }; @@ -709,7 +707,7 @@ TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithInvalidUris) TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithNonFuelUris) { const std::vector includeUris = { - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack", + "https://fuel.gazebosim.org/1.0/openroboticstest/models/backpack", std::string("file://") + PROJECT_SOURCE_PATH + "/test/worlds/models/sphere"}; @@ -768,7 +766,7 @@ TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithNonFuelUris) ///////////////////////////////////////////////// TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithOneExpanded) { - const std::string worldFile{"test/worlds/save_world.sdf"}; + const auto worldFile = common::joinPaths("test", "worlds", "save_world.sdf"); this->LoadWorld(worldFile); Entity worldEntity = this->ecm.EntityByComponents(components::World()); auto elem = std::make_shared(); @@ -947,8 +945,7 @@ using GenerateWorldFixture = ElementUpdateFixture; ///////////////////////////////////////////////// TEST_F(GenerateWorldFixture, ModelsInline) { - const std::string worldFile{"test/worlds/save_world.sdf"}; - this->LoadWorld(worldFile); + this->LoadWorld(common::joinPaths("test", "worlds", "save_world.sdf")); Entity worldEntity = this->ecm.EntityByComponents(components::World()); // Check with expandIncludeTags = true { diff --git a/src/Server.cc b/src/Server.cc index fe610681c7..ea0c7b5bbf 100644 --- a/src/Server.cc +++ b/src/Server.cc @@ -202,7 +202,7 @@ bool Server::Run(const bool _blocking, const uint64_t _iterations, // running variable gets updated before this function returns. With // a small number of iterations it is possible that the run thread // successfuly completes before this function returns. - cond.wait(lock); + cond.wait(lock, [this]() -> bool {return this->dataPtr->running;}); return true; } diff --git a/src/ServerPrivate.cc b/src/ServerPrivate.cc index debfb7afce..d5418728ca 100644 --- a/src/ServerPrivate.cc +++ b/src/ServerPrivate.cc @@ -227,9 +227,8 @@ void ServerPrivate::AddRecordPlugin(const ServerConfig &_config) { auto topic = recordTopicElem->Get(); sdfRecordTopics.push_back(topic); + recordTopicElem = recordTopicElem->GetNextElement(); } - - recordTopicElem = recordTopicElem->GetNextElement(); } // Remove the plugin, which will be added back in by ServerConfig. diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc index 48559728cc..ff80cd09fe 100644 --- a/src/Server_TEST.cc +++ b/src/Server_TEST.cc @@ -1217,14 +1217,31 @@ TEST_P(ServerFixture, Stop) sim::Server server(serverConfig); + std::mutex testMutex; + std::condition_variable testCv; + test::Relay testSystem; + unsigned int preUpdates{0}; + testSystem.OnPreUpdate( + [&](const sim::UpdateInfo &, + sim::EntityComponentManager &) + { + std::scoped_lock localLock(testMutex); + ++preUpdates; + testCv.notify_one(); + return true; + }); + + server.AddSystem(testSystem.systemPtr); // The simulation runner should not be running. EXPECT_FALSE(*server.Running(0)); EXPECT_FALSE(server.Running()); // Run the server. + std::unique_lock testLock(testMutex); EXPECT_TRUE(server.Run(false, 0, false)); - EXPECT_TRUE(*server.Running(0)); EXPECT_TRUE(server.Running()); + testCv.wait(testLock, [&]() -> bool {return preUpdates > 0;}); + EXPECT_TRUE(*server.Running(0)); // Stop the server server.Stop(); diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc index fbfeff6d73..afb3909147 100644 --- a/src/SimulationRunner.cc +++ b/src/SimulationRunner.cc @@ -502,7 +502,8 @@ void SimulationRunner::ProcessSystemQueue() this->systemMgr->ActivatePendingSystems(); - auto threadCount = this->systemMgr->SystemsPostUpdate().size() + 1u; + unsigned int threadCount = + static_cast(this->systemMgr->SystemsPostUpdate().size() + 1u); gzdbg << "Creating PostUpdate worker threads: " << threadCount << std::endl; diff --git a/src/gz_TEST.cc b/src/gz_TEST.cc index 5d066343b5..02f211d097 100644 --- a/src/gz_TEST.cc +++ b/src/gz_TEST.cc @@ -101,7 +101,7 @@ TEST(CmdLine, GZ_UTILS_TEST_DISABLED_ON_WIN32(CachedFuelWorld)) std::string projectPath = std::string(PROJECT_SOURCE_PATH) + "/test/worlds"; gz::common::setenv("GZ_FUEL_CACHE_PATH", projectPath.c_str()); std::string cmd = kGzCommand + " -r -v 4 --iterations 5" + - " https://fuel.ignitionrobotics.org/1.0/OpenRobotics/worlds/Test%20world"; + " https://fuel.gazebosim.org/1.0/openroboticstest/worlds/test%20world"; std::cout << "Running command [" << cmd << "]" << std::endl; std::string output = customExecStr(cmd); diff --git a/src/systems/acoustic_comms/AcousticComms.cc b/src/systems/acoustic_comms/AcousticComms.cc index bab0c84781..cfb4863c89 100644 --- a/src/systems/acoustic_comms/AcousticComms.cc +++ b/src/systems/acoustic_comms/AcousticComms.cc @@ -57,10 +57,10 @@ AcousticComms::AcousticComms() ////////////////////////////////////////////////// void AcousticComms::Load( - const Entity &_entity, + const Entity &/*_entity*/, std::shared_ptr _sdf, - EntityComponentManager &_ecm, - EventManager &_eventMgr) + EntityComponentManager &/*_ecm*/, + EventManager &/*_eventMgr*/) { if (_sdf->HasElement("max_range")) { diff --git a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc index 728c844f5a..99e7485185 100644 --- a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc +++ b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc @@ -767,8 +767,7 @@ void OpticalTactilePluginPrivate::ComputeNormalForces( normalsMsg.set_step(3 * sizeof(float) * _msg.width()); normalsMsg.set_pixel_format_type(gz::msgs::PixelFormatType::R_FLOAT32); - uint32_t bufferSize = 3 * sizeof(float) * _msg.width() * _msg.height(); - std::shared_ptr normalForcesBuffer(new char[bufferSize]); + std::vector normalForcesBuffer(3 * _msg.width() * _msg.height()); uint32_t bufferIndex; // Marker messages representing the normal forces @@ -804,11 +803,10 @@ void OpticalTactilePluginPrivate::ComputeNormalForces( // Add force to buffer // Forces buffer is composed of XYZ coordinates, while _msg buffer is // made up of XYZRGB values - bufferIndex = j * (_msg.row_step() / 2) + i * (_msg.point_step() / 2); - normalForcesBuffer.get()[bufferIndex] = normalForce.X(); - normalForcesBuffer.get()[bufferIndex + sizeof(float)] = normalForce.Y(); - normalForcesBuffer.get()[bufferIndex + 2 * sizeof(float)] = - normalForce.Z(); + bufferIndex = j * (_msg.width() * 3) + i * 3; + normalForcesBuffer[bufferIndex] = normalForce.X(); + normalForcesBuffer[bufferIndex+1] = normalForce.Y(); + normalForcesBuffer[bufferIndex+2] = normalForce.Z(); if (!_visualizeForces) continue; @@ -820,9 +818,10 @@ void OpticalTactilePluginPrivate::ComputeNormalForces( } } + std::string *dataStr = normalsMsg.mutable_data(); + dataStr->resize(sizeof(float) * normalForcesBuffer.size()); + memcpy(&((*dataStr)[0]), normalForcesBuffer.data(), dataStr->size()); // Publish message - normalsMsg.set_data(normalForcesBuffer.get(), - 3 * sizeof(float) * _msg.width() * _msg.height()); this->normalForcesPub.Publish(normalsMsg); if (_visualizeForces) diff --git a/src/systems/rf_comms/RFComms.cc b/src/systems/rf_comms/RFComms.cc index be4c7682d5..7beae440c8 100644 --- a/src/systems/rf_comms/RFComms.cc +++ b/src/systems/rf_comms/RFComms.cc @@ -257,7 +257,8 @@ std::tuple RFComms::Implementation::AttemptSend( // Compute prospective accumulated bits along with time window // (including this packet). - double bitsSent = (_txState.bytesSentThisEpoch + _numBytes) * 8; + auto bitsSent = + static_cast((_txState.bytesSentThisEpoch + _numBytes) * 8); // Check current epoch bitrate vs capacity and fail to send accordingly if (bitsSent > this->radioConfig.capacity * this->epochDuration) @@ -286,8 +287,9 @@ std::tuple RFComms::Implementation::AttemptSend( // error rate (BER). double ber = this->QPSKPowerToBER( this->DbmToPow(rxPower), this->DbmToPow(this->radioConfig.noiseFloor)); + double packetDropProb = - double packetDropProb = 1.0 - exp(_numBytes * log(1 - ber)); + 1.0 - exp(static_cast(_numBytes) * log(1 - ber)); // gzdbg << "TX power (dBm): " << this->radioConfig.txPower << "\n" << // "RX power (dBm): " << rxPower << "\n" << @@ -315,7 +317,8 @@ std::tuple RFComms::Implementation::AttemptSend( // Compute prospective accumulated bits along with time window // (including this packet). - double bitsReceived = (_rxState.bytesReceivedThisEpoch + _numBytes) * 8; + auto bitsReceived = + static_cast((_rxState.bytesReceivedThisEpoch + _numBytes) * 8); // Check current epoch bitrate vs capacity and fail to send accordingly. if (bitsReceived > this->radioConfig.capacity * this->epochDuration) diff --git a/src/systems/shader_param/ShaderParam.cc b/src/systems/shader_param/ShaderParam.cc index a91a0b4f7d..d0324031b4 100644 --- a/src/systems/shader_param/ShaderParam.cc +++ b/src/systems/shader_param/ShaderParam.cc @@ -441,7 +441,7 @@ void ShaderParamPrivate::OnUpdate() if (!spv.type.empty() && spv.type == "int_array") { for (const auto &v : values) - floatArrayValue.push_back(std::stoi(v)); + floatArrayValue.push_back(std::stof(v)); paramType = rendering::ShaderParam::PARAM_INT_BUFFER; } // treat everything else as float_array diff --git a/src/systems/track_controller/TrackController.cc b/src/systems/track_controller/TrackController.cc index f5e668b404..0fdcc8fc9a 100644 --- a/src/systems/track_controller/TrackController.cc +++ b/src/systems/track_controller/TrackController.cc @@ -533,7 +533,7 @@ void TrackControllerPrivate::ComputeSurfaceProperties( gz::msgs::Set(this->debugMarker.mutable_pose(), math::Pose3d( p.X(), p.Y(), p.Z(), rot.Roll(), rot.Pitch(), rot.Yaw())); this->debugMarker.mutable_material()->mutable_diffuse()->set_r( - surfaceMotion >= 0 ? 0 : 1); + surfaceMotion >= 0 ? 0.0f : 1.0f); this->node.Request("/marker", this->debugMarker); } diff --git a/src/systems/trajectory_follower/TrajectoryFollower.cc b/src/systems/trajectory_follower/TrajectoryFollower.cc index 3d0c377d31..300832d510 100644 --- a/src/systems/trajectory_follower/TrajectoryFollower.cc +++ b/src/systems/trajectory_follower/TrajectoryFollower.cc @@ -421,7 +421,7 @@ void TrajectoryFollower::PreUpdate( } } - int sign = std::abs(bearing.Degree()) / bearing.Degree(); + int sign = static_cast(std::abs(bearing.Degree()) / bearing.Degree()); torqueWorld = (*comPose).Rot().RotateVector( gz::math::Vector3d(0, 0, sign * this->dataPtr->torqueToApply)); } diff --git a/test/integration/breadcrumbs.cc b/test/integration/breadcrumbs.cc index 485d6e82cc..c846289377 100644 --- a/test/integration/breadcrumbs.cc +++ b/test/integration/breadcrumbs.cc @@ -80,7 +80,7 @@ void remainingCb(const msgs::Int32 &_msg) TEST_F(BreadcrumbsTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(Remaining)) { // Start server - this->LoadWorld("test/worlds/breadcrumbs.sdf"); + this->LoadWorld(common::joinPaths("test", "worlds", "breadcrumbs.sdf")); kRemaining = 0; test::Relay testSystem; @@ -138,7 +138,7 @@ TEST_F(BreadcrumbsTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(Remaining)) TEST_F(BreadcrumbsTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(DeployAtOffset)) { // Start server - this->LoadWorld("test/worlds/breadcrumbs.sdf"); + this->LoadWorld(common::joinPaths("test", "worlds", "breadcrumbs.sdf")); test::Relay testSystem; transport::Node node; @@ -203,7 +203,7 @@ TEST_F(BreadcrumbsTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(DeployAtOffset)) TEST_F(BreadcrumbsTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(MaxDeployments)) { // Start server - this->LoadWorld("test/worlds/breadcrumbs.sdf"); + this->LoadWorld(common::joinPaths("test", "worlds", "breadcrumbs.sdf")); test::Relay testSystem; transport::Node node; @@ -259,7 +259,7 @@ TEST_F(BreadcrumbsTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(MaxDeployments)) TEST_F(BreadcrumbsTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(FuelDeploy)) { // Start server - this->LoadWorld("test/worlds/breadcrumbs.sdf"); + this->LoadWorld(common::joinPaths("test", "worlds", "breadcrumbs.sdf")); test::Relay testSystem; transport::Node node; @@ -312,7 +312,7 @@ TEST_F(BreadcrumbsTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(FuelDeploy)) TEST_F(BreadcrumbsTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(Performer)) { // Start server - this->LoadWorld("test/worlds/breadcrumbs.sdf"); + this->LoadWorld(common::joinPaths("test", "worlds", "breadcrumbs.sdf")); test::Relay testSystem; transport::Node node; @@ -386,7 +386,7 @@ TEST_F(BreadcrumbsTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(Performer)) TEST_F(BreadcrumbsTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(PerformerSetVolume)) { // Start server - this->LoadWorld("test/worlds/breadcrumbs.sdf", true); + this->LoadWorld(common::joinPaths("test", "worlds", "breadcrumbs.sdf"), true); test::Relay testSystem; transport::Node node; @@ -440,7 +440,7 @@ TEST_F(BreadcrumbsTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(PerformerSetVolume)) TEST_F(BreadcrumbsTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(DeployDisablePhysics)) { // Start server - this->LoadWorld("test/worlds/breadcrumbs.sdf"); + this->LoadWorld(common::joinPaths("test", "worlds", "breadcrumbs.sdf")); test::Relay testSystem; transport::Node node; @@ -572,7 +572,8 @@ std::vector ModelsByNameRegex( TEST_F(BreadcrumbsTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(LevelLoadUnload)) { // Start server - this->LoadWorld("test/worlds/breadcrumbs_levels.sdf", true); + this->LoadWorld( + common::joinPaths("test", "worlds", "breadcrumbs_levels.sdf"), true); test::Relay testSystem; transport::Node node; diff --git a/test/integration/fuel_cached_server.cc b/test/integration/fuel_cached_server.cc index 83970e2c15..1b9cc16bd5 100644 --- a/test/integration/fuel_cached_server.cc +++ b/test/integration/fuel_cached_server.cc @@ -41,7 +41,7 @@ TEST_P(FuelCachedServer, CachedFuelWorld) ServerConfig serverConfig; auto fuelWorldURL = - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/worlds/Test%20world"; + "https://fuel.gazebosim.org/1.0/OpenRobotics/worlds/Test%20world"; EXPECT_TRUE(serverConfig.SetSdfFile(fuelWorldURL)); EXPECT_EQ(fuelWorldURL, serverConfig.SdfFile()); diff --git a/test/integration/hydrodynamics.cc b/test/integration/hydrodynamics.cc index 97627b2e9f..54ebf0cb7f 100644 --- a/test/integration/hydrodynamics.cc +++ b/test/integration/hydrodynamics.cc @@ -112,7 +112,7 @@ std::vector HydrodynamicsTest::TestWorld( ///////////////////////////////////////////////// /// This test evaluates whether the hydrodynamic plugin affects the motion /// of the body when a force is applied. -TEST_F(HydrodynamicsTest, VelocityTestinOil) +TEST_F(HydrodynamicsTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(VelocityTestinOil)) { auto world = common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds", "hydrodynamics.sdf"); diff --git a/test/integration/odometry_publisher.cc b/test/integration/odometry_publisher.cc index 5ad89520fb..dace4d208c 100644 --- a/test/integration/odometry_publisher.cc +++ b/test/integration/odometry_publisher.cc @@ -539,13 +539,13 @@ class OdometryPublisherTest } // Check that the mean values are close to zero. - EXPECT_NEAR(linVelSumX/n, 0, 0.3); - EXPECT_NEAR(linVelSumY/n, 0, 0.3); - EXPECT_NEAR(linVelSumZ/n, 0, 0.3); + EXPECT_NEAR(linVelSumX/n, 0, 0.5); + EXPECT_NEAR(linVelSumY/n, 0, 0.5); + EXPECT_NEAR(linVelSumZ/n, 0, 0.5); - EXPECT_NEAR(angVelSumX/n, 0, 0.3); - EXPECT_NEAR(angVelSumY/n, 0, 0.3); - EXPECT_NEAR(angVelSumZ/n, 0, 0.3); + EXPECT_NEAR(angVelSumX/n, 0, 0.5); + EXPECT_NEAR(angVelSumY/n, 0, 0.5); + EXPECT_NEAR(angVelSumZ/n, 0, 0.5); // Calculate the variation (sigma^2). double linVelSqSumX = 0, linVelSqSumY = 0, linVelSqSumZ = 0; @@ -562,13 +562,13 @@ class OdometryPublisherTest } // Verify the variance values. - EXPECT_NEAR(linVelSqSumX/n, 1, 0.3); - EXPECT_NEAR(linVelSqSumY/n, 1, 0.3); - EXPECT_NEAR(linVelSqSumZ/n, 1, 0.3); + EXPECT_NEAR(linVelSqSumX/n, 1, 0.5); + EXPECT_NEAR(linVelSqSumY/n, 1, 0.5); + EXPECT_NEAR(linVelSqSumZ/n, 1, 0.5); - EXPECT_NEAR(angVelSqSumX/n, 1, 0.3); - EXPECT_NEAR(angVelSqSumY/n, 1, 0.3); - EXPECT_NEAR(angVelSqSumZ/n, 1, 0.3); + EXPECT_NEAR(angVelSqSumX/n, 1, 0.5); + EXPECT_NEAR(angVelSqSumY/n, 1, 0.5); + EXPECT_NEAR(angVelSqSumZ/n, 1, 0.5); // Check the covariance matrix. EXPECT_EQ(odomTwistCovariance.size(), 36); diff --git a/test/integration/optical_tactile_plugin.cc b/test/integration/optical_tactile_plugin.cc index 9ddec559a6..7f98aa1760 100644 --- a/test/integration/optical_tactile_plugin.cc +++ b/test/integration/optical_tactile_plugin.cc @@ -67,14 +67,14 @@ class OpticalTactilePluginTest : public InternalFixture<::testing::Test> uint32_t msgBufferIndex = _j * this->normalForces.step() + _i * 3 * sizeof(float); - measuredPoint.X() = static_cast( - msgBuffer[msgBufferIndex]); + measuredPoint.X() = *reinterpret_cast( + &msgBuffer[msgBufferIndex]); - measuredPoint.Y() = static_cast( - msgBuffer[msgBufferIndex + sizeof(float)]); + measuredPoint.Y() = *reinterpret_cast( + &msgBuffer[msgBufferIndex + sizeof(float)]); - measuredPoint.Z() = static_cast( - msgBuffer[msgBufferIndex + 2*sizeof(float)]); + measuredPoint.Z() = *reinterpret_cast( + &msgBuffer[msgBufferIndex + 2*sizeof(float)]); return measuredPoint; } diff --git a/test/integration/save_world.cc b/test/integration/save_world.cc index 5a5a7d6024..d2f9fa013d 100644 --- a/test/integration/save_world.cc +++ b/test/integration/save_world.cc @@ -118,7 +118,7 @@ TEST_F(SdfGeneratorFixture, // This has to be different from the backpack in order to test SDFormat // generation for a Fuel URI that was not known when simulation started. const std::string groundPlaneUri = - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/ground plane"; + "https://fuel.gazebosim.org/1.0/openrobotics/models/ground plane"; transport::Node node; { @@ -422,7 +422,7 @@ TEST_F(SdfGeneratorFixture, ModelWithNestedIncludes) ASSERT_NE(nullptr, uri); ASSERT_NE(nullptr, uri->GetText()); EXPECT_EQ( - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Coke Can/2", + "https://fuel.gazebosim.org/1.0/openrobotics/models/coke can/2", std::string(uri->GetText())); name = include->FirstChildElement("name"); diff --git a/test/integration/scene_broadcaster_system.cc b/test/integration/scene_broadcaster_system.cc index 5eeda9711a..bc080ce69b 100644 --- a/test/integration/scene_broadcaster_system.cc +++ b/test/integration/scene_broadcaster_system.cc @@ -960,10 +960,12 @@ TEST_P(SceneBroadcasterTest, EXPECT_TRUE(result); ASSERT_TRUE(res.has_ambient()); - EXPECT_EQ(math::Color(1.0, 1.0, 1.0, 1.0), msgs::Convert(res.ambient())); + EXPECT_EQ(math::Color(1.0f, 1.0f, 1.0f, 1.0f), + msgs::Convert(res.ambient())); ASSERT_TRUE(res.has_background()); - EXPECT_EQ(math::Color(0.8, 0.8, 0.8, 1.0), msgs::Convert(res.background())); + EXPECT_EQ(math::Color(0.8f, 0.8f, 0.8f, 1.0f), + msgs::Convert(res.background())); EXPECT_TRUE(res.shadows()); EXPECT_FALSE(res.grid()); diff --git a/test/media/RescueRandy_Thermal.png b/test/media/RescueRandy_Thermal.png new file mode 100644 index 0000000000..a5304bb2cd Binary files /dev/null and b/test/media/RescueRandy_Thermal.png differ diff --git a/test/worlds/breadcrumbs.sdf b/test/worlds/breadcrumbs.sdf index 9690718f2f..7790557dba 100644 --- a/test/worlds/breadcrumbs.sdf +++ b/test/worlds/breadcrumbs.sdf @@ -481,7 +481,7 @@ -2.2 0 5 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Cardboard box + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Cardboard box diff --git a/test/worlds/breadcrumbs_levels.sdf b/test/worlds/breadcrumbs_levels.sdf index 901aee2328..8be524b613 100644 --- a/test/worlds/breadcrumbs_levels.sdf +++ b/test/worlds/breadcrumbs_levels.sdf @@ -116,5 +116,3 @@ - - diff --git a/test/worlds/follow_actor.sdf b/test/worlds/follow_actor.sdf index f778df03c0..c31da2348d 100644 --- a/test/worlds/follow_actor.sdf +++ b/test/worlds/follow_actor.sdf @@ -86,7 +86,7 @@ walker 0 -2 1.0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/chapulina/models/Walking actor + https://fuel.gazebosim.org/1.0/chapulina/models/Walking actor box diff --git a/test/worlds/fuel.ignitionrobotics.org/OpenRobotics/worlds/Test%20world/2/test.sdf b/test/worlds/fuel.gazebosim.org/openroboticstest/worlds/test%20world/2/test.sdf similarity index 100% rename from test/worlds/fuel.ignitionrobotics.org/OpenRobotics/worlds/Test%20world/2/test.sdf rename to test/worlds/fuel.gazebosim.org/openroboticstest/worlds/test%20world/2/test.sdf diff --git a/test/worlds/fuel.ignitionrobotics.org/OpenRobotics/worlds/Test%20world/2/thumbnails/1.png b/test/worlds/fuel.gazebosim.org/openroboticstest/worlds/test%20world/2/thumbnails/1.png similarity index 100% rename from test/worlds/fuel.ignitionrobotics.org/OpenRobotics/worlds/Test%20world/2/thumbnails/1.png rename to test/worlds/fuel.gazebosim.org/openroboticstest/worlds/test%20world/2/thumbnails/1.png diff --git a/test/worlds/model_nested_include.sdf b/test/worlds/model_nested_include.sdf index 75aecd48da..354b5ad9a6 100644 --- a/test/worlds/model_nested_include.sdf +++ b/test/worlds/model_nested_include.sdf @@ -62,7 +62,7 @@ coke - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Coke Can + https://fuel.gazebosim.org/1.0/openrobotics/models/coke can 2 2 2 0 0 0 diff --git a/test/worlds/model_photo_shoot_random_joints.sdf b/test/worlds/model_photo_shoot_random_joints.sdf index a27708da35..11a38b73df 100644 --- a/test/worlds/model_photo_shoot_random_joints.sdf +++ b/test/worlds/model_photo_shoot_random_joints.sdf @@ -20,7 +20,7 @@ 1, 1, 1 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Robonaut + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Robonaut diff --git a/test/worlds/save_world.sdf b/test/worlds/save_world.sdf index 0d02c412a1..dd231b7575 100644 --- a/test/worlds/save_world.sdf +++ b/test/worlds/save_world.sdf @@ -39,17 +39,17 @@ - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack backpack1 1 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack backpack2 1 2 3 0.1 0.2 0.3 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/2 backpack3 2 0 0 0.1 0.2 0.3 diff --git a/test/worlds/thermal.sdf b/test/worlds/thermal.sdf index 41cadd6921..5cb3adf13f 100644 --- a/test/worlds/thermal.sdf +++ b/test/worlds/thermal.sdf @@ -302,12 +302,27 @@ - - - 0 0 0 0 0 1.570796 - rescue_randy - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Rescue Randy - + + true + + + + + 0.5 + + + + 1.0 1.0 1.0 + 1.0 1.0 1.0 + + + ../media/RescueRandy_Thermal.png + 310 + + + + 4.5 0 0.5 0.0 0.0 3.14