diff --git a/Changelog.md b/Changelog.md index de89e01b82..67303f56cb 100644 --- a/Changelog.md +++ b/Changelog.md @@ -573,6 +573,41 @@ ## Ignition Gazebo 4.x +### Ignition Gazebo 4.13.0 (2021-11-15) + +1. Prevent creation of spurious `` elements when saving worlds + * [Pull request #1192](https://github.com/ignitionrobotics/ign-gazebo/pull/1192) + +1. Add support for tracked vehicles + * [Pull request #869](https://github.com/ignitionrobotics/ign-gazebo/pull/869) + +1. Add components to dynamically set joint limits + * [Pull request #847](https://github.com/ignitionrobotics/ign-gazebo/pull/847) + +1. Fix updating component from state + * [Pull request #1181](https://github.com/ignitionrobotics/ign-gazebo/pull/1181) + +1. Fix updating a component's data via SerializedState msg + * [Pull request #1149](https://github.com/ignitionrobotics/ign-gazebo/pull/1149) + +1. Sensor systems work if loaded after sensors + * [Pull request #1104](https://github.com/ignitionrobotics/ign-gazebo/pull/1104) + +1. Fix generation of systems library symlinks in build directory + * [Pull request #1160](https://github.com/ignitionrobotics/ign-gazebo/pull/1160) + +1. Edit material colors in component inspector + * [Pull request #1123](https://github.com/ignitionrobotics/ign-gazebo/pull/1123) + +1. Support setting the background color for sensors + * [Pull request #1147](https://github.com/ignitionrobotics/ign-gazebo/pull/1147) + +1. Use uint64_t for ComponentInspector Entity IDs + * [Pull request #1144](https://github.com/ignitionrobotics/ign-gazebo/pull/1144) + +1. Fix integers and floats on component inspector + * [Pull request #1143](https://github.com/ignitionrobotics/ign-gazebo/pull/1143) + ### Ignition Gazebo 4.12.0 (2021-10-22) 1. Fix performance issue with contact data and AABB updates. diff --git a/src/SdfEntityCreator_TEST.cc b/src/SdfEntityCreator_TEST.cc index eac28eef0c..12554dbf7e 100644 --- a/src/SdfEntityCreator_TEST.cc +++ b/src/SdfEntityCreator_TEST.cc @@ -127,7 +127,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) EXPECT_EQ("default", _name->Data()); EXPECT_DOUBLE_EQ(0.001, _physics->Data().MaxStepSize()); - EXPECT_DOUBLE_EQ(1.0, _physics->Data().RealTimeFactor()); + EXPECT_DOUBLE_EQ(0.0, _physics->Data().RealTimeFactor()); worldCount++; diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc index ecdd6eb7f9..41b89ed5eb 100644 --- a/src/SimulationRunner.cc +++ b/src/SimulationRunner.cc @@ -103,8 +103,15 @@ SimulationRunner::SimulationRunner(const sdf::World *_world, // So to get a given RTF, our desired period is: // // period = step_size / RTF - this->updatePeriod = std::chrono::nanoseconds( - static_cast(this->stepSize.count() / this->desiredRtf)); + if (this->desiredRtf < 1e-9) + { + this->updatePeriod = 0ms; + } + else + { + this->updatePeriod = std::chrono::nanoseconds( + static_cast(this->stepSize.count() / this->desiredRtf)); + } this->pauseConn = this->eventMgr.Connect( std::bind(&SimulationRunner::SetPaused, this, std::placeholders::_1)); diff --git a/src/SimulationRunner_TEST.cc b/src/SimulationRunner_TEST.cc index 2e5b49d2b4..a881e7d06f 100644 --- a/src/SimulationRunner_TEST.cc +++ b/src/SimulationRunner_TEST.cc @@ -1073,7 +1073,7 @@ TEST_P(SimulationRunnerTest, Time) EXPECT_EQ(0u, runner.CurrentInfo().iterations); EXPECT_EQ(0ms, runner.CurrentInfo().simTime); EXPECT_EQ(0ms, runner.CurrentInfo().dt); - EXPECT_EQ(1ms, runner.UpdatePeriod()); + EXPECT_EQ(0ms, runner.UpdatePeriod()); EXPECT_EQ(1ms, runner.StepSize()); runner.SetPaused(false); @@ -1086,7 +1086,7 @@ TEST_P(SimulationRunnerTest, Time) EXPECT_EQ(100u, runner.CurrentInfo().iterations); EXPECT_EQ(100ms, runner.CurrentInfo().simTime); EXPECT_EQ(1ms, runner.CurrentInfo().dt); - EXPECT_EQ(1ms, runner.UpdatePeriod()); + EXPECT_EQ(0ms, runner.UpdatePeriod()); EXPECT_EQ(1ms, runner.StepSize()); int sleep = 0; @@ -1107,7 +1107,7 @@ TEST_P(SimulationRunnerTest, Time) EXPECT_EQ(200u, runner.CurrentInfo().iterations); EXPECT_EQ(300ms, runner.CurrentInfo().simTime); EXPECT_EQ(2ms, runner.CurrentInfo().dt); - EXPECT_EQ(1ms, runner.UpdatePeriod()); + EXPECT_EQ(0ms, runner.UpdatePeriod()); EXPECT_EQ(2ms, runner.StepSize()); sleep = 0; @@ -1127,7 +1127,7 @@ TEST_P(SimulationRunnerTest, Time) EXPECT_EQ(200u, runner.CurrentInfo().iterations); EXPECT_EQ(300ms, runner.CurrentInfo().simTime); EXPECT_EQ(2ms, runner.CurrentInfo().dt); - EXPECT_EQ(1ms, runner.UpdatePeriod()); + EXPECT_EQ(0ms, runner.UpdatePeriod()); EXPECT_EQ(2ms, runner.StepSize()); // Verify info published to /clock topic @@ -1145,7 +1145,7 @@ TEST_P(SimulationRunnerTest, Time) EXPECT_EQ(500ms, runner.CurrentInfo().simTime) << runner.CurrentInfo().simTime.count(); EXPECT_EQ(2ms, runner.CurrentInfo().dt); - EXPECT_EQ(1ms, runner.UpdatePeriod()); + EXPECT_EQ(0ms, runner.UpdatePeriod()); EXPECT_EQ(2ms, runner.StepSize()); sleep = 0; diff --git a/src/gui/plugins/visualize_lidar/VisualizeLidar.cc b/src/gui/plugins/visualize_lidar/VisualizeLidar.cc index aed80f1a06..a8f4c26665 100644 --- a/src/gui/plugins/visualize_lidar/VisualizeLidar.cc +++ b/src/gui/plugins/visualize_lidar/VisualizeLidar.cc @@ -291,8 +291,13 @@ void VisualizeLidar::Update(const UpdateInfo &, for (auto child : children) { std::string nextstring = lidarURIVec[i+1]; + auto comp = _ecm.Component(child); + if (!comp) + { + continue; + } std::string childname = std::string( - _ecm.Component(child)->Data()); + comp->Data()); if (nextstring.compare(childname) == 0) { parent = child; diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.cc b/src/systems/battery_plugin/LinearBatteryPlugin.cc index 8c8f94b32d..1b484783cf 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.cc +++ b/src/systems/battery_plugin/LinearBatteryPlugin.cc @@ -69,6 +69,15 @@ class ignition::gazebo::systems::LinearBatteryPluginPrivate /// \param[in] _req This value should be true. public: void OnDisableRecharge(const ignition::msgs::Boolean &_req); + /// \brief Callback connected to additional topics that can start battery + /// draining. + /// \param[in] _data Message data. + /// \param[in] _size Message data size. + /// \param[in] _info Information about the message. + public: void OnBatteryDrainingMsg( + const char *_data, const size_t _size, + const ignition::transport::MessageInfo &_info); + /// \brief Name of model, only used for printing warning when battery drains. public: std::string modelName; @@ -153,6 +162,9 @@ class ignition::gazebo::systems::LinearBatteryPluginPrivate /// \brief Battery state of charge message publisher public: transport::Node::Publisher statePub; + + /// \brief Whether a topic has received any battery-draining command. + public: bool startDrainingFromTopics = false; }; ///////////////////////////////////////////////// @@ -340,6 +352,23 @@ void LinearBatteryPlugin::Configure(const Entity &_entity, << "in LinearBatteryPlugin SDF" << std::endl; } + // Subscribe to power draining topics, if any. + if (_sdf->HasElement("power_draining_topic")) + { + sdf::ElementConstPtr sdfElem = _sdf->FindElement("power_draining_topic"); + while (sdfElem) + { + const auto &topic = sdfElem->Get(); + this->dataPtr->node.SubscribeRaw(topic, + std::bind(&LinearBatteryPluginPrivate::OnBatteryDrainingMsg, + this->dataPtr.get(), std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3)); + ignmsg << "LinearBatteryPlugin subscribes to power draining topic [" + << topic << "]." << std::endl; + sdfElem = sdfElem->GetNextElement("power_draining_topic"); + } + } + ignmsg << "LinearBatteryPlugin configured. Battery name: " << this->dataPtr->battery->Name() << std::endl; igndbg << "Battery initial voltage: " << this->dataPtr->battery->InitVoltage() @@ -371,6 +400,7 @@ void LinearBatteryPluginPrivate::Reset() this->iraw = 0.0; this->ismooth = 0.0; this->q = this->q0; + this->startDrainingFromTopics = false; } ///////////////////////////////////////////////// @@ -395,13 +425,24 @@ void LinearBatteryPluginPrivate::OnDisableRecharge( this->startCharging = false; } +////////////////////////////////////////////////// +void LinearBatteryPluginPrivate::OnBatteryDrainingMsg( + const char *, const size_t, const ignition::transport::MessageInfo &) +{ + this->startDrainingFromTopics = true; +} + ////////////////////////////////////////////////// void LinearBatteryPlugin::PreUpdate( const ignition::gazebo::UpdateInfo &/*_info*/, ignition::gazebo::EntityComponentManager &_ecm) { IGN_PROFILE("LinearBatteryPlugin::PreUpdate"); - this->dataPtr->startDraining = false; + + // \todo(anyone) Add in the ability to stop the battery from draining + // after it has been started by a topic. See this comment: + // https://github.com/ignitionrobotics/ign-gazebo/pull/1255#discussion_r770223092 + this->dataPtr->startDraining = this->dataPtr->startDrainingFromTopics; // Start draining the battery if the robot has started moving if (!this->dataPtr->startDraining) { diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.hh b/src/systems/battery_plugin/LinearBatteryPlugin.hh index 75149eef0f..e98460a15b 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.hh +++ b/src/systems/battery_plugin/LinearBatteryPlugin.hh @@ -58,6 +58,11 @@ namespace systems /// (Required if `` is set to true) /// - `` True to change the battery behavior to fix some issues /// described in https://github.com/ignitionrobotics/ign-gazebo/issues/225. + /// - `` A topic that is used to start battery + /// discharge. Any message on the specified topic will cause the batter to + /// start draining. This element can be specified multiple times if + /// multiple topics should be monitored. Note that this mechanism will + /// start the battery draining, and once started will keep drainig. class LinearBatteryPlugin : public System, public ISystemConfigure, diff --git a/test/integration/battery_plugin.cc b/test/integration/battery_plugin.cc index 34fed41f79..78d6ba6e77 100644 --- a/test/integration/battery_plugin.cc +++ b/test/integration/battery_plugin.cc @@ -23,6 +23,7 @@ #include #include #include +#include #include #include @@ -136,20 +137,107 @@ TEST_F(BatteryPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SingleBattery)) EXPECT_LT(batComp->Data(), 12.592); // Check there is a single battery matching exactly the one specified - int batCount = 0; + int linearBatCount = 0; + int totalBatCount = 0; ecm->Each( [&](const Entity &_batEntity, components::BatterySoC *_batComp, components::Name *_nameComp) -> bool { - batCount++; + totalBatCount++; + if (_nameComp->Data() == "linear_battery") + { + linearBatCount++; - EXPECT_NE(kNullEntity, _batEntity); - EXPECT_EQ(_nameComp->Data(), "linear_battery"); + EXPECT_NE(kNullEntity, _batEntity); + EXPECT_EQ(_nameComp->Data(), "linear_battery"); - // Check battery component voltage data is lower than initial voltage - EXPECT_LT(_batComp->Data(), 12.592); + // Check battery component voltage data is lower than initial voltage + EXPECT_LT(_batComp->Data(), 12.592); + } return true; }); - EXPECT_EQ(batCount, 1); + EXPECT_EQ(linearBatCount, 1); + EXPECT_EQ(totalBatCount, 2); +} + +///////////////////////////////////////////////// +// Battery with power draining topics +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(BatteryPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PowerDrainTopic)) +{ + const auto sdfPath = common::joinPaths(std::string(PROJECT_SOURCE_PATH), + "test", "worlds", "battery.sdf"); + sdf::Root root; + EXPECT_EQ(root.Load(sdfPath).size(), 0lu); + EXPECT_GT(root.WorldCount(), 0lu); + + ServerConfig serverConfig; + serverConfig.SetSdfFile(sdfPath); + + // A pointer to the ecm. This will be valid once we run the mock system + gazebo::EntityComponentManager *ecm = nullptr; + this->mockSystem->preUpdateCallback = + [&ecm](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + { + ecm = &_ecm; + + // Check a battery exists + EXPECT_TRUE(ecm->HasComponentType(components::BatterySoC::typeId)); + + // Find the battery entity + Entity batEntity = ecm->EntityByComponents(components::Name( + "linear_battery_topics")); + EXPECT_NE(kNullEntity, batEntity); + + // Find the battery component + EXPECT_TRUE(ecm->EntityHasComponentType(batEntity, + components::BatterySoC::typeId)); + auto batComp = ecm->Component(batEntity); + + // Check voltage is never zero. + // This check is here to guarantee that components::BatterySoC in + // the LinearBatteryPlugin is not zero when created. If + // components::BatterySoC is zero on start, then the Physics plugin + // can disable a joint. This in turn can prevent the joint from + // rotating. See https://github.com/ignitionrobotics/ign-gazebo/issues/55 + EXPECT_GT(batComp->Data(), 0); + }; + + // Start server + Server server(serverConfig); + server.AddSystem(this->systemPtr); + server.Run(true, 100, false); + EXPECT_NE(nullptr, ecm); + + // Check a battery exists + EXPECT_TRUE(ecm->HasComponentType(components::BatterySoC::typeId)); + + // Find the battery entity + Entity batEntity = ecm->EntityByComponents(components::Name( + "linear_battery_topics")); + EXPECT_NE(kNullEntity, batEntity); + + // Find the battery component + EXPECT_TRUE(ecm->EntityHasComponentType(batEntity, + components::BatterySoC::typeId)); + auto batComp = ecm->Component(batEntity); + + // Check state of charge should be 1, since the batery has not drained + // and the is equivalent ot the . + EXPECT_DOUBLE_EQ(batComp->Data(), 1.0); + + // Send a message on one of the topics, which will + // start the battery draining when the server starts again. + ignition::transport::Node node; + auto pub = node.Advertise("/battery/discharge2"); + msgs::StringMsg msg; + pub.Publish(msg); + + // Run the server again. + server.Run(true, 100, false); + + // The state of charge should be <1, since the batery has started + // draining. + EXPECT_LT(batComp->Data(), 1.0); } diff --git a/test/integration/imu_system.cc b/test/integration/imu_system.cc index 9eb0083a37..388da45bae 100644 --- a/test/integration/imu_system.cc +++ b/test/integration/imu_system.cc @@ -225,8 +225,6 @@ TEST_F(ImuTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(OrientationDisabled)) EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); - const std::string sensorName = "imu_sensor"; - auto topic = "world/imu_sensor/model/imu_model/link/link/sensor/imu_sensor/imu"; diff --git a/test/integration/scene_broadcaster_system.cc b/test/integration/scene_broadcaster_system.cc index d8cfadf1d1..aa5edc0a8d 100644 --- a/test/integration/scene_broadcaster_system.cc +++ b/test/integration/scene_broadcaster_system.cc @@ -518,7 +518,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StateStatic)) // Start server ignition::gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + - "/examples/worlds/empty.sdf"); + "/test/worlds/empty.sdf"); gazebo::Server server(serverConfig); EXPECT_FALSE(server.Running()); diff --git a/test/integration/sensors_system.cc b/test/integration/sensors_system.cc index 661a92819e..6165ee9620 100644 --- a/test/integration/sensors_system.cc +++ b/test/integration/sensors_system.cc @@ -87,6 +87,17 @@ void testDefaultTopics() std::vector publishers; transport::Node node; + // Sensors are created in a separate thread, so we sleep here to give them + // time + int sleep{0}; + int maxSleep{30}; + for (; sleep < maxSleep && !node.TopicInfo(topics.front(), publishers); + ++sleep) + { + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + ASSERT_LT(sleep, maxSleep); + for (const std::string &topic : topics) { bool result = node.TopicInfo(topic, publishers); diff --git a/test/integration/touch_plugin.cc b/test/integration/touch_plugin.cc index 1c376022ba..60813c9a8a 100644 --- a/test/integration/touch_plugin.cc +++ b/test/integration/touch_plugin.cc @@ -298,7 +298,7 @@ TEST_F(TouchPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SpawnedEntities)) auto testFunc = [&](const std::string &_box1, const std::string &_box2) { this->server.reset(); - this->StartServer("/examples/worlds/empty.sdf"); + this->StartServer("/test/worlds/empty.sdf"); whiteTouched = false; req.set_sdf(_box1); diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index ca74b42607..4011cfaccf 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -56,7 +56,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Create)) // Start server ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + - "/examples/worlds/empty.sdf"; + "/test/worlds/empty.sdf"; serverConfig.SetSdfFile(sdfFile); Server server(serverConfig); @@ -693,7 +693,8 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Pose)) } ///////////////////////////////////////////////// -TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Light)) +// https://github.com/ignitionrobotics/ign-gazebo/issues/634 +TEST_F(UserCommandsTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Light)) { // Start server ServerConfig serverConfig; @@ -960,7 +961,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Physics)) auto physicsComp = ecm->Component(worldEntity); ASSERT_NE(nullptr, physicsComp); EXPECT_DOUBLE_EQ(0.001, physicsComp->Data().MaxStepSize()); - EXPECT_DOUBLE_EQ(1.0, physicsComp->Data().RealTimeFactor()); + EXPECT_DOUBLE_EQ(0.0, physicsComp->Data().RealTimeFactor()); // Set physics properties msgs::Physics req; diff --git a/test/worlds/ackermann_steering.sdf b/test/worlds/ackermann_steering.sdf index 28a3b3d432..fbc52aacbe 100644 --- a/test/worlds/ackermann_steering.sdf +++ b/test/worlds/ackermann_steering.sdf @@ -4,7 +4,7 @@ 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/altimeter.sdf b/test/worlds/altimeter.sdf index 7b8c209632..7e93238220 100644 --- a/test/worlds/altimeter.sdf +++ b/test/worlds/altimeter.sdf @@ -3,7 +3,7 @@ 0.001 - 1.0 + 0 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/battery.sdf b/test/worlds/battery.sdf index bc5f91d44d..9078867090 100644 --- a/test/worlds/battery.sdf +++ b/test/worlds/battery.sdf @@ -3,7 +3,7 @@ 0.001 - 1.0 + 0 + + 1 0 0 0 0 0 + false + + 0 0 0.5 0 0 0 + + + + 1 1 1 + + + + + + + linear_battery_topics + 12.592 + 12.694 + -3.1424 + 1.2009 + 1.2009 + 0.061523 + 1.9499 + + 500 + /battery/discharge1 + /battery/discharge2 + + + + diff --git a/test/worlds/breadcrumbs.sdf b/test/worlds/breadcrumbs.sdf index fae8d86898..a8b75f9899 100644 --- a/test/worlds/breadcrumbs.sdf +++ b/test/worlds/breadcrumbs.sdf @@ -4,7 +4,7 @@ 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 .001 - 1.0 + 0 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/collada_world_exporter.sdf b/test/worlds/collada_world_exporter.sdf index b65709b628..01f7ea7da4 100644 --- a/test/worlds/collada_world_exporter.sdf +++ b/test/worlds/collada_world_exporter.sdf @@ -1,6 +1,10 @@ + + 0 + + + + 0 + + + 0 + + diff --git a/test/worlds/contact.sdf b/test/worlds/contact.sdf index 395e450dcc..10c4afb1da 100644 --- a/test/worlds/contact.sdf +++ b/test/worlds/contact.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/conveyor.sdf b/test/worlds/conveyor.sdf index f4cd000ad8..f33ba10c3f 100644 --- a/test/worlds/conveyor.sdf +++ b/test/worlds/conveyor.sdf @@ -6,7 +6,7 @@ --> 0.001 - 10.0 + 0 + + 0 + + diff --git a/test/worlds/depth_camera_sensor.sdf b/test/worlds/depth_camera_sensor.sdf index f6fd16a163..7791ad3dbc 100644 --- a/test/worlds/depth_camera_sensor.sdf +++ b/test/worlds/depth_camera_sensor.sdf @@ -7,7 +7,7 @@ 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/diff_drive.sdf b/test/worlds/diff_drive.sdf index dcb6a1fc2e..bfd7352a00 100644 --- a/test/worlds/diff_drive.sdf +++ b/test/worlds/diff_drive.sdf @@ -2,9 +2,9 @@ - + 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 + + + + 0.001 + 0 + + + + + + + + + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + diff --git a/test/worlds/event_trigger.sdf b/test/worlds/event_trigger.sdf index 2ccc046837..a0f4aa5e40 100644 --- a/test/worlds/event_trigger.sdf +++ b/test/worlds/event_trigger.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/falling.sdf b/test/worlds/falling.sdf index 9e69c968e6..cc09166afb 100644 --- a/test/worlds/falling.sdf +++ b/test/worlds/falling.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/follow_actor.sdf b/test/worlds/follow_actor.sdf index a02a444fc6..c1ac2046fe 100644 --- a/test/worlds/follow_actor.sdf +++ b/test/worlds/follow_actor.sdf @@ -1,6 +1,9 @@ + + 0 + diff --git a/test/worlds/friction.sdf b/test/worlds/friction.sdf index f4ce49cf4d..42f4c6da26 100644 --- a/test/worlds/friction.sdf +++ b/test/worlds/friction.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/gpu_lidar_sensor.sdf b/test/worlds/gpu_lidar_sensor.sdf index a8748e419b..463314ebf0 100644 --- a/test/worlds/gpu_lidar_sensor.sdf +++ b/test/worlds/gpu_lidar_sensor.sdf @@ -7,7 +7,7 @@ 0.001 - 1.0 + 0 + + 0 + true diff --git a/test/worlds/imu.sdf b/test/worlds/imu.sdf index 4bd476afa6..e2983ccb31 100644 --- a/test/worlds/imu.sdf +++ b/test/worlds/imu.sdf @@ -4,7 +4,7 @@ 0 0 -5 0.001 - 1.0 + 0 0 0 -5 0.001 - 1.0 + 0 + + 0 + + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/ground plane/1 diff --git a/test/worlds/include_connected_nested_models.sdf b/test/worlds/include_connected_nested_models.sdf index f579ad30f1..3e03aa35eb 100644 --- a/test/worlds/include_connected_nested_models.sdf +++ b/test/worlds/include_connected_nested_models.sdf @@ -3,7 +3,7 @@ 0.001 - 1.0 + 0 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/joint_controller_invalid.sdf b/test/worlds/joint_controller_invalid.sdf index 4621474f99..45a8494ca4 100644 --- a/test/worlds/joint_controller_invalid.sdf +++ b/test/worlds/joint_controller_invalid.sdf @@ -1,6 +1,9 @@ + + 0 + diff --git a/test/worlds/joint_position_controller.sdf b/test/worlds/joint_position_controller.sdf index 906521db60..cc52a7cea7 100644 --- a/test/worlds/joint_position_controller.sdf +++ b/test/worlds/joint_position_controller.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/joint_trajectory_controller.sdf b/test/worlds/joint_trajectory_controller.sdf index 4aaee68ca5..16ca6785b8 100644 --- a/test/worlds/joint_trajectory_controller.sdf +++ b/test/worlds/joint_trajectory_controller.sdf @@ -2,6 +2,9 @@ + + 0 + @@ -402,7 +405,7 @@ test_custom_topic/velocity_control - 0.6 175 diff --git a/test/worlds/level_performance.sdf b/test/worlds/level_performance.sdf index febf0168e6..2ba3d61de0 100644 --- a/test/worlds/level_performance.sdf +++ b/test/worlds/level_performance.sdf @@ -7,6 +7,10 @@ --> + + 0 + + diff --git a/test/worlds/levels.sdf b/test/worlds/levels.sdf index f0724beedb..ce2568ec70 100644 --- a/test/worlds/levels.sdf +++ b/test/worlds/levels.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/levels_no_performers.sdf b/test/worlds/levels_no_performers.sdf index 2332f0d329..a83859439d 100644 --- a/test/worlds/levels_no_performers.sdf +++ b/test/worlds/levels_no_performers.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/lift_drag.sdf b/test/worlds/lift_drag.sdf index 4926c4d9a8..2ee782834c 100644 --- a/test/worlds/lift_drag.sdf +++ b/test/worlds/lift_drag.sdf @@ -2,6 +2,10 @@ + + 0 + + + + 0 + 0.001 - 1.0 + 0 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/log_record_dbl_pendulum.sdf b/test/worlds/log_record_dbl_pendulum.sdf index 6b79cc1a43..6aa86c0955 100644 --- a/test/worlds/log_record_dbl_pendulum.sdf +++ b/test/worlds/log_record_dbl_pendulum.sdf @@ -10,7 +10,7 @@ 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/logical_audio_sensor_plugin.sdf b/test/worlds/logical_audio_sensor_plugin.sdf index acd2318c7e..4bc8537dba 100644 --- a/test/worlds/logical_audio_sensor_plugin.sdf +++ b/test/worlds/logical_audio_sensor_plugin.sdf @@ -1,6 +1,10 @@ + + 0 + + 0 0 0 0 0 0 diff --git a/test/worlds/logical_audio_sensor_plugin_services.sdf b/test/worlds/logical_audio_sensor_plugin_services.sdf index 5722016b69..47b4ec6fc3 100644 --- a/test/worlds/logical_audio_sensor_plugin_services.sdf +++ b/test/worlds/logical_audio_sensor_plugin_services.sdf @@ -1,6 +1,10 @@ + + 0 + + 0 0 0 0 0 0 diff --git a/test/worlds/logical_camera_sensor.sdf b/test/worlds/logical_camera_sensor.sdf index 96623b7d8e..9ec9feeaed 100644 --- a/test/worlds/logical_camera_sensor.sdf +++ b/test/worlds/logical_camera_sensor.sdf @@ -4,7 +4,7 @@ 0.001 - 1.0 + 0 0.94 0.76 -0.12 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.005 - 1.0 + 0 diff --git a/test/worlds/nested_model.sdf b/test/worlds/nested_model.sdf index b22c0dd17d..06063d67eb 100644 --- a/test/worlds/nested_model.sdf +++ b/test/worlds/nested_model.sdf @@ -3,7 +3,7 @@ 0.001 - 1.0 + 0 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/odometry_publisher.sdf b/test/worlds/odometry_publisher.sdf index e572a8cc88..ccda8141bd 100644 --- a/test/worlds/odometry_publisher.sdf +++ b/test/worlds/odometry_publisher.sdf @@ -4,7 +4,7 @@ 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.01 - 1.0 + 0 diff --git a/test/worlds/only_canonical_link_moves.sdf b/test/worlds/only_canonical_link_moves.sdf index 4afef7d849..5649e3facc 100644 --- a/test/worlds/only_canonical_link_moves.sdf +++ b/test/worlds/only_canonical_link_moves.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/optical_tactile_plugin.sdf b/test/worlds/optical_tactile_plugin.sdf index 8c8a5770b5..253a94b3ed 100644 --- a/test/worlds/optical_tactile_plugin.sdf +++ b/test/worlds/optical_tactile_plugin.sdf @@ -2,6 +2,10 @@ + + 0 + + diff --git a/test/worlds/particle_emitter.sdf b/test/worlds/particle_emitter.sdf index 12912e5f5b..18509d10ff 100644 --- a/test/worlds/particle_emitter.sdf +++ b/test/worlds/particle_emitter.sdf @@ -4,7 +4,7 @@ 0.001 - 1.0 + 0 diff --git a/test/worlds/particle_emitter2.sdf b/test/worlds/particle_emitter2.sdf index 0fcf08df97..e9ff514141 100644 --- a/test/worlds/particle_emitter2.sdf +++ b/test/worlds/particle_emitter2.sdf @@ -4,7 +4,7 @@ 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/performers.sdf b/test/worlds/performers.sdf index de0f736973..ec194696e9 100644 --- a/test/worlds/performers.sdf +++ b/test/worlds/performers.sdf @@ -1,6 +1,10 @@ + + 0 + + true diff --git a/test/worlds/physics_options.sdf b/test/worlds/physics_options.sdf index d4fcae60e1..0351a2495e 100644 --- a/test/worlds/physics_options.sdf +++ b/test/worlds/physics_options.sdf @@ -8,6 +8,7 @@ pgs + 0 + + 0 + + diff --git a/test/worlds/plugins_empty.sdf b/test/worlds/plugins_empty.sdf index ac6128380c..6061dfccde 100644 --- a/test/worlds/plugins_empty.sdf +++ b/test/worlds/plugins_empty.sdf @@ -2,6 +2,10 @@ + + 0 + + diff --git a/test/worlds/pose_publisher.sdf b/test/worlds/pose_publisher.sdf index fadf485754..2bacec9d5d 100644 --- a/test/worlds/pose_publisher.sdf +++ b/test/worlds/pose_publisher.sdf @@ -4,7 +4,7 @@ 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/quadcopter_velocity_control.sdf b/test/worlds/quadcopter_velocity_control.sdf index fc8adea119..6a4d08b813 100644 --- a/test/worlds/quadcopter_velocity_control.sdf +++ b/test/worlds/quadcopter_velocity_control.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/resource_paths.sdf b/test/worlds/resource_paths.sdf index ff5c5910f4..84f44e79ab 100644 --- a/test/worlds/resource_paths.sdf +++ b/test/worlds/resource_paths.sdf @@ -1,6 +1,10 @@ + + 0 + + + + 0 + + diff --git a/test/worlds/revolute_joint_equilibrium.sdf b/test/worlds/revolute_joint_equilibrium.sdf index cf967f17b3..1af50f31cc 100644 --- a/test/worlds/revolute_joint_equilibrium.sdf +++ b/test/worlds/revolute_joint_equilibrium.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/rgbd_camera_sensor.sdf b/test/worlds/rgbd_camera_sensor.sdf index 5759741e11..6aee476435 100644 --- a/test/worlds/rgbd_camera_sensor.sdf +++ b/test/worlds/rgbd_camera_sensor.sdf @@ -3,7 +3,7 @@ 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/sensor.sdf b/test/worlds/sensor.sdf index aebb32104c..68ccfcd989 100644 --- a/test/worlds/sensor.sdf +++ b/test/worlds/sensor.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/shapes.sdf b/test/worlds/shapes.sdf index 90c7b82a87..345d0a2732 100644 --- a/test/worlds/shapes.sdf +++ b/test/worlds/shapes.sdf @@ -3,7 +3,7 @@ 0.001 - 1.0 + 0 diff --git a/test/worlds/static_diff_drive_vehicle.sdf b/test/worlds/static_diff_drive_vehicle.sdf index 179a11ef20..ddadbde39c 100644 --- a/test/worlds/static_diff_drive_vehicle.sdf +++ b/test/worlds/static_diff_drive_vehicle.sdf @@ -5,7 +5,7 @@ 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 1.0 + 0 - - 0 0 0.5 0 0 0 @@ -222,7 +221,7 @@ - + 0 0 -4.0 1.5707963267948966 0 0 diff --git a/test/worlds/touch_plugin.sdf b/test/worlds/touch_plugin.sdf index 4ff260b7f3..d108699e92 100644 --- a/test/worlds/touch_plugin.sdf +++ b/test/worlds/touch_plugin.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/tracked_vehicle_simple.sdf b/test/worlds/tracked_vehicle_simple.sdf index 5a54f56958..cbe39175b6 100644 --- a/test/worlds/tracked_vehicle_simple.sdf +++ b/test/worlds/tracked_vehicle_simple.sdf @@ -6,7 +6,7 @@ --> 0.001 - 1.0 + 0 1000 diff --git a/test/worlds/triball_drift.sdf b/test/worlds/triball_drift.sdf index d574e2a2b6..831c82a0a3 100644 --- a/test/worlds/triball_drift.sdf +++ b/test/worlds/triball_drift.sdf @@ -2,6 +2,9 @@ + + 0 + 1 0 -9.8 + + 0 + + diff --git a/test/worlds/trisphere_cycle_wheel_slip.sdf b/test/worlds/trisphere_cycle_wheel_slip.sdf index b086b05a0f..3e1f44bfe2 100644 --- a/test/worlds/trisphere_cycle_wheel_slip.sdf +++ b/test/worlds/trisphere_cycle_wheel_slip.sdf @@ -2,6 +2,9 @@ + + 0 + -2 0 -9.8 0.001 - 1.0 + 0 0 0 0 + + 0 + +