From 68dcf5dca8588890b64089e1be1871839397f559 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Tue, 14 Sep 2021 16:30:49 -0500 Subject: [PATCH 1/6] Remove unused ignition gui header (#1026) Signed-off-by: Michael Carroll --- src/ServerPrivate.cc | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/ServerPrivate.cc b/src/ServerPrivate.cc index 2498630072..e0c7dd047e 100644 --- a/src/ServerPrivate.cc +++ b/src/ServerPrivate.cc @@ -26,8 +26,6 @@ #include -#include - #include "ignition/gazebo/Util.hh" #include "SimulationRunner.hh" From 6d1b4e65f79356fb0dff4e6014bfc22d085425ff Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Wed, 15 Sep 2021 15:48:01 -0700 Subject: [PATCH 2/6] bump version and update changelog (#1029) Signed-off-by: Ian Chen --- CMakeLists.txt | 2 +- Changelog.md | 38 ++++++++++++++++++++++++++++++++++++++ 2 files changed, 39 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 322646018d..f177053877 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) #============================================================================ # Initialize the project #============================================================================ -project(ignition-gazebo4 VERSION 4.9.1) +project(ignition-gazebo4 VERSION 4.10.0) #============================================================================ # Find ignition-cmake diff --git a/Changelog.md b/Changelog.md index 6c493720f7..2022393eb9 100644 --- a/Changelog.md +++ b/Changelog.md @@ -2,6 +2,44 @@ ### Ignition Gazebo 4.x.x (202x-xx-xx) +### Ignition Gazebo 4.x.x (2021-09-15) + +1. Fixed GUI's ComponentInspector light parameter + * [Pull Request 1018](https://github.com/ignitionrobotics/ign-gazebo/pull/1018) + +1. Fix msg in entity_creation example + * [Pull Request 972](https://github.com/ignitionrobotics/ign-gazebo/pull/972) + +1. Fix selection buffer crash on resize + * [Pull Request 969](https://github.com/ignitionrobotics/ign-gazebo/pull/969) + +1. Fix crash in the follow_actor example + * [Pull Request 958](https://github.com/ignitionrobotics/ign-gazebo/pull/958) + +1. Fix joint controller with empty joint velocity data + * [Pull Request 937](https://github.com/ignitionrobotics/ign-gazebo/pull/937) + +1. Scale mode - Part2 + * [Pull Request 881](https://github.com/ignitionrobotics/ign-gazebo/pull/881) + +1. Physics system: update link poses if the canonical link pose has been updated + * [Pull Request 876](https://github.com/ignitionrobotics/ign-gazebo/pull/876) + +1. Add Particle Emitter tutorial + * [Pull Request 860](https://github.com/ignitionrobotics/ign-gazebo/pull/860) + +1. Refactor RenderUtil::Update with helper functions + * [Pull Request 858](https://github.com/ignitionrobotics/ign-gazebo/pull/858) + +1. Remove unneeded camera follow offset checks + * [Pull Request 857](https://github.com/ignitionrobotics/ign-gazebo/pull/857) + +1. Added service to set camera's follow offset + * [Pull Request 855](https://github.com/ignitionrobotics/ign-gazebo/pull/855) + +1. Using math::SpeedLimiter on the ackermann_steering controller. + * [Pull Request 837](https://github.com/ignitionrobotics/ign-gazebo/pull/837) + ### Ignition Gazebo 4.9.1 (2021-05-24) 1. Make halt motion act like a brake. From 8ab51a33e7ddf67fb126df01ea7a2a59aca13023 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Wed, 15 Sep 2021 16:55:56 -0700 Subject: [PATCH 3/6] Update ign-gazebo4 changelog (#1031) Signed-off-by: Ian Chen --- Changelog.md | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/Changelog.md b/Changelog.md index 2022393eb9..e27c54dad2 100644 --- a/Changelog.md +++ b/Changelog.md @@ -40,6 +40,14 @@ 1. Using math::SpeedLimiter on the ackermann_steering controller. * [Pull Request 837](https://github.com/ignitionrobotics/ign-gazebo/pull/837) +1. All changes merged forward from ign-gazebo3 + * [Pull Request 866](https://github.com/ignitionrobotics/ign-gazebo/pull/866) + * [Pull Request 916](https://github.com/ignitionrobotics/ign-gazebo/pull/916) + * [Pull Request 933](https://github.com/ignitionrobotics/ign-gazebo/pull/933) + * [Pull Request 946](https://github.com/ignitionrobotics/ign-gazebo/pull/946) + * [Pull Request 973](https://github.com/ignitionrobotics/ign-gazebo/pull/973) + * [Pull Request 1017](https://github.com/ignitionrobotics/ign-gazebo/pull/1017) + ### Ignition Gazebo 4.9.1 (2021-05-24) 1. Make halt motion act like a brake. From a6d1c6a6f1c19561a4b8d7bb3760bd63cc43ef4f Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Thu, 23 Sep 2021 11:30:03 -0700 Subject: [PATCH 4/6] Support locked entities, and headless video recording using sim time (#862) * Support locked entities, and headless video recording using sim time Signed-off-by: Nate Koenig * Spelling Signed-off-by: Nate Koenig * Add bitrate (#864) Signed-off-by: Ian Chen * Changing Locked name and adding fps Signed-off-by: Nate Koenig * Rename to unpin Signed-off-by: Nate Koenig * Fix codecheck Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig Co-authored-by: Ian Chen --- .../ignition/gazebo/EntityComponentManager.hh | 29 +++++ src/EntityComponentManager.cc | 108 +++++++++++++++++- src/EntityComponentManager_TEST.cc | 58 ++++++++++ src/gui/plugins/scene3d/Scene3D.cc | 4 +- .../CameraVideoRecorder.cc | 77 ++++++++++++- .../CameraVideoRecorder.hh | 19 ++- 6 files changed, 282 insertions(+), 13 deletions(-) diff --git a/include/ignition/gazebo/EntityComponentManager.hh b/include/ignition/gazebo/EntityComponentManager.hh index 2df7fc4369..d02cda0fd6 100644 --- a/include/ignition/gazebo/EntityComponentManager.hh +++ b/include/ignition/gazebo/EntityComponentManager.hh @@ -91,6 +91,35 @@ namespace ignition public: void RequestRemoveEntity(const Entity _entity, bool _recursive = true); + /// \brief Prevent an entity and optionally its children from + /// being removed. + /// + /// This function can be useful when seek operations during log + /// playback are used in conjunciton with spawned entities. For + /// example, you may want to record a video based on a log file + /// using a headless simulation instance. This requires a + /// camera sensor which would be spawned during log playback. If + /// a seek backward in time is performed during log playback, then the + /// spawned camera would be removed. Use this function to prevent the + /// camera from automatic removal. + /// + /// \param[in] _entity Entity to be pinned. + /// \param[in] _recursive Whether to recursively pin all child + /// entities. True by default. + public: void PinEntity(const Entity _entity, bool _recursive = true); + + /// \brief Allow an entity, and optionally its children, previously + /// marked as pinned to be removed. + /// \param[in] _entity Entity to be unpinned. + /// \param[in] _recursive Whether to recursively unpin all child + /// entities. True by default. + /// \sa void PinEntity(const Entity, bool) + public: void UnpinEntity(const Entity _entity, bool _recursive = true); + + /// \brief Allow all previously pinned entities to be removed. + /// \sa void PinEntity(const Entity, bool) + public: void UnpinAllEntities(); + /// \brief Request to remove all entities. This will insert the request /// into a queue. The queue is processed toward the end of a simulation /// update step. diff --git a/src/EntityComponentManager.cc b/src/EntityComponentManager.cc index 5c469916b9..f14d2665a4 100644 --- a/src/EntityComponentManager.cc +++ b/src/EntityComponentManager.cc @@ -45,6 +45,13 @@ class ignition::gazebo::EntityComponentManagerPrivate public: void InsertEntityRecursive(Entity _entity, std::unordered_set &_set); + /// \brief Recursively erase an entity and all its descendants from a given + /// set. + /// \param[in] _entity Entity to be erased. + /// \param[in, out] _set Set to erase from. + public: void EraseEntityRecursive(Entity _entity, + std::unordered_set &_set); + /// \brief Register a new component type. /// \param[in] _typeId Type if of the new component. /// \return True if created successfully. @@ -156,6 +163,9 @@ class ignition::gazebo::EntityComponentManagerPrivate /// which belongs the component, and the value is the component being /// removed. std::unordered_multimap removedComponents; + + /// \brief Set of entities that are prevented from removal. + public: std::unordered_set pinnedEntities; }; ////////////////////////////////////////////////// @@ -236,6 +246,17 @@ void EntityComponentManagerPrivate::InsertEntityRecursive(Entity _entity, _set.insert(_entity); } +///////////////////////////////////////////////// +void EntityComponentManagerPrivate::EraseEntityRecursive(Entity _entity, + std::unordered_set &_set) +{ + for (const auto &vertex : this->entities.AdjacentsFrom(_entity)) + { + this->EraseEntityRecursive(vertex.first, _set); + } + _set.erase(_entity); +} + ///////////////////////////////////////////////// void EntityComponentManager::RequestRemoveEntity(Entity _entity, bool _recursive) @@ -252,6 +273,23 @@ void EntityComponentManager::RequestRemoveEntity(Entity _entity, this->dataPtr->InsertEntityRecursive(_entity, tmpToRemoveEntities); } + // Remove entities from tmpToRemoveEntities that are marked as + // unremovable. + for (auto iter = tmpToRemoveEntities.begin(); + iter != tmpToRemoveEntities.end();) + { + if (std::find(this->dataPtr->pinnedEntities.begin(), + this->dataPtr->pinnedEntities.end(), *iter) != + this->dataPtr->pinnedEntities.end()) + { + iter = tmpToRemoveEntities.erase(iter); + } + else + { + ++iter; + } + } + { std::lock_guard lock(this->dataPtr->entityRemoveMutex); this->dataPtr->toRemoveEntities.insert(tmpToRemoveEntities.begin(), @@ -267,11 +305,41 @@ void EntityComponentManager::RequestRemoveEntity(Entity _entity, ///////////////////////////////////////////////// void EntityComponentManager::RequestRemoveEntities() { + if (this->dataPtr->pinnedEntities.empty()) { - std::lock_guard lock(this->dataPtr->entityRemoveMutex); - this->dataPtr->removeAllEntities = true; + { + std::lock_guard lock(this->dataPtr->entityRemoveMutex); + this->dataPtr->removeAllEntities = true; + } + this->RebuildViews(); + } + else + { + std::unordered_set tmpToRemoveEntities; + + // Store the to-be-removed entities in a temporary set so we can call + // UpdateViews on each of them + for (const auto &vertex : this->dataPtr->entities.Vertices()) + { + if (std::find(this->dataPtr->pinnedEntities.begin(), + this->dataPtr->pinnedEntities.end(), vertex.first) == + this->dataPtr->pinnedEntities.end()) + { + tmpToRemoveEntities.insert(vertex.first); + } + } + + { + std::lock_guard lock(this->dataPtr->entityRemoveMutex); + this->dataPtr->toRemoveEntities.insert(tmpToRemoveEntities.begin(), + tmpToRemoveEntities.end()); + } + + for (const auto &removedEntity : tmpToRemoveEntities) + { + this->UpdateViews(removedEntity); + } } - this->RebuildViews(); } ///////////////////////////////////////////////// @@ -1514,3 +1582,37 @@ void EntityComponentManagerPrivate::AddModifiedComponent(const Entity &_entity) this->modifiedComponents.insert(_entity); } + +///////////////////////////////////////////////// +void EntityComponentManager::PinEntity(const Entity _entity, bool _recursive) +{ + if (_recursive) + { + this->dataPtr->InsertEntityRecursive(_entity, + this->dataPtr->pinnedEntities); + } + else + { + this->dataPtr->pinnedEntities.insert(_entity); + } +} + +///////////////////////////////////////////////// +void EntityComponentManager::UnpinEntity(const Entity _entity, bool _recursive) +{ + if (_recursive) + { + this->dataPtr->EraseEntityRecursive(_entity, + this->dataPtr->pinnedEntities); + } + else + { + this->dataPtr->pinnedEntities.erase(_entity); + } +} + +///////////////////////////////////////////////// +void EntityComponentManager::UnpinAllEntities() +{ + this->dataPtr->pinnedEntities.clear(); +} diff --git a/src/EntityComponentManager_TEST.cc b/src/EntityComponentManager_TEST.cc index b1e0dd79de..badfd70a0a 100644 --- a/src/EntityComponentManager_TEST.cc +++ b/src/EntityComponentManager_TEST.cc @@ -2571,6 +2571,64 @@ TEST_P(EntityComponentManagerFixture, RemovedComponentsSyncBetweenServerAndGUI) } } +////////////////////////////////////////////////// +TEST_P(EntityComponentManagerFixture, PinnedEntity) +{ + // Create some entities + auto e1 = manager.CreateEntity(); + EXPECT_EQ(1u, e1); + EXPECT_TRUE(manager.HasEntity(e1)); + + auto e2 = manager.CreateEntity(); + EXPECT_TRUE(manager.SetParentEntity(e2, e1)); + EXPECT_EQ(2u, e2); + EXPECT_TRUE(manager.HasEntity(e2)); + + auto e3 = manager.CreateEntity(); + EXPECT_EQ(3u, e3); + EXPECT_TRUE(manager.HasEntity(e3)); + + EXPECT_EQ(3u, manager.EntityCount()); + + // Mark e1 as unremovable, which should also lock its child entity e2 + manager.PinEntity(e1); + + // Try to remove e1, which is locked entity + manager.RequestRemoveEntity(e1); + EXPECT_EQ(3u, manager.EntityCount()); + EXPECT_FALSE(manager.HasEntitiesMarkedForRemoval()); + manager.ProcessEntityRemovals(); + EXPECT_EQ(3u, manager.EntityCount()); + + // Try to remove e2, which has been locked recursively + manager.RequestRemoveEntity(e2); + EXPECT_EQ(3u, manager.EntityCount()); + EXPECT_FALSE(manager.HasEntitiesMarkedForRemoval()); + manager.ProcessEntityRemovals(); + EXPECT_EQ(3u, manager.EntityCount()); + + // Try to remove all entities, which should leave just e1 and e2 + manager.RequestRemoveEntities(); + EXPECT_TRUE(manager.HasEntitiesMarkedForRemoval()); + manager.ProcessEntityRemovals(); + EXPECT_EQ(2u, manager.EntityCount()); + + // Unmark e2, and now it should be removable. + manager.UnpinEntity(e2); + manager.RequestRemoveEntity(e2); + EXPECT_EQ(2u, manager.EntityCount()); + EXPECT_TRUE(manager.HasEntitiesMarkedForRemoval()); + manager.ProcessEntityRemovals(); + EXPECT_EQ(1u, manager.EntityCount()); + + // Unmark all entities, and now it should be removable. + manager.UnpinAllEntities(); + manager.RequestRemoveEntities(); + EXPECT_TRUE(manager.HasEntitiesMarkedForRemoval()); + manager.ProcessEntityRemovals(); + EXPECT_EQ(0u, manager.EntityCount()); +} + // Run multiple times. We want to make sure that static globals don't cause // problems. INSTANTIATE_TEST_SUITE_P(EntityComponentManagerRepeat, diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 95fb924e46..eb7756f52e 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -157,10 +157,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// only used in lockstep mode and recording in sim time. public: std::chrono::steady_clock::time_point recordVideoUpdateTime; - /// \brief Start tiem of video recording + /// \brief Start time of video recording public: std::chrono::steady_clock::time_point recordStartTime; - /// \brief Camera pose publisher + /// \brief Video recording statistics publisher public: transport::Node::Publisher recorderStatsPub; /// \brief Target to move the user camera to diff --git a/src/systems/camera_video_recorder/CameraVideoRecorder.cc b/src/systems/camera_video_recorder/CameraVideoRecorder.cc index 26d8d178a4..521d69807f 100644 --- a/src/systems/camera_video_recorder/CameraVideoRecorder.cc +++ b/src/systems/camera_video_recorder/CameraVideoRecorder.cc @@ -108,6 +108,25 @@ class ignition::gazebo::systems::CameraVideoRecorderPrivate /// \brief Topic that the sensor publishes to public: std::string sensorTopic; + + /// \brief Video recording statistics publisher + public: transport::Node::Publisher recorderStatsPub; + + /// \brief Start time of video recording. + public: std::chrono::steady_clock::time_point recordStartTime; + + /// \brief Current simulation time. + public: std::chrono::steady_clock::duration simTime{0}; + + /// \brief Use sim time as timestamp during video recording + /// By default (false), video encoding is done using real time. + public: bool recordVideoUseSimTime = false; + + /// \brief Video recorder bitrate (bps) + public: unsigned int recordVideoBitrate = 2070000; + + /// \brief Recording frames per second. + public: unsigned int fps = 25; }; ////////////////////////////////////////////////// @@ -224,6 +243,23 @@ void CameraVideoRecorder::Configure( } } this->dataPtr->sensorTopic = topic; + + // Get whether sim time should be used for recording. + this->dataPtr->recordVideoUseSimTime = _sdf->Get("use_sim_time", + this->dataPtr->recordVideoUseSimTime).first; + + // Get video recoder bitrate param + this->dataPtr->recordVideoBitrate = _sdf->Get("bitrate", + this->dataPtr->recordVideoBitrate).first; + + this->dataPtr->fps = _sdf->Get("fps", this->dataPtr->fps).first; + + // recorder stats topic + std::string recorderStatsTopic = this->dataPtr->sensorTopic + "/stats"; + this->dataPtr->recorderStatsPub = + this->dataPtr->node.Advertise(recorderStatsTopic); + ignmsg << "Camera Video recorder stats topic advertised on [" + << recorderStatsTopic << "]" << std::endl; } ////////////////////////////////////////////////// @@ -281,8 +317,36 @@ void CameraVideoRecorderPrivate::OnPostRender() if (this->videoEncoder.IsEncoding()) { this->camera->Copy(this->cameraImage); - this->videoEncoder.AddFrame( - this->cameraImage.Data(), width, height); + std::chrono::steady_clock::time_point t; + std::chrono::steady_clock::now(); + if (this->recordVideoUseSimTime) + t = std::chrono::steady_clock::time_point(this->simTime); + else + t = std::chrono::steady_clock::now(); + + bool frameAdded = this->videoEncoder.AddFrame( + this->cameraImage.Data(), width, height, t); + + if (frameAdded) + { + // publish recorder stats + if (this->recordStartTime == + std::chrono::steady_clock::time_point( + std::chrono::duration(std::chrono::seconds(0)))) + { + // start time, i.e. time when first frame is added + this->recordStartTime = t; + } + + std::chrono::steady_clock::duration dt; + dt = t - this->recordStartTime; + int64_t sec, nsec; + std::tie(sec, nsec) = ignition::math::durationToSecNsec(dt); + msgs::Time msg; + msg.set_sec(sec); + msg.set_nsec(nsec); + this->recorderStatsPub.Publish(msg); + } } // Video recorder is idle. Start recording. else @@ -296,7 +360,11 @@ void CameraVideoRecorderPrivate::OnPostRender() &CameraVideoRecorderPrivate::OnImage, this); this->videoEncoder.Start(this->recordVideoFormat, - this->tmpVideoFilename, width, height); + this->tmpVideoFilename, width, height, this->fps, + this->recordVideoBitrate); + + this->recordStartTime = std::chrono::steady_clock::time_point( + std::chrono::duration(std::chrono::seconds(0))); ignmsg << "Start video recording on [" << this->service << "]. " << "Encoding to tmp file: [" @@ -331,9 +399,10 @@ void CameraVideoRecorderPrivate::OnPostRender() } ////////////////////////////////////////////////// -void CameraVideoRecorder::PostUpdate(const UpdateInfo &, +void CameraVideoRecorder::PostUpdate(const UpdateInfo &_info, const EntityComponentManager &_ecm) { + this->dataPtr->simTime = _info.simTime; if (!this->dataPtr->cameraName.empty()) return; diff --git a/src/systems/camera_video_recorder/CameraVideoRecorder.hh b/src/systems/camera_video_recorder/CameraVideoRecorder.hh index 90c4dfdb06..f5f3dc02c1 100644 --- a/src/systems/camera_video_recorder/CameraVideoRecorder.hh +++ b/src/systems/camera_video_recorder/CameraVideoRecorder.hh @@ -36,10 +36,21 @@ namespace systems **/ /// \brief Record video from a camera sensor /// The system takes in the following parameter: - /// - `` Name of topic for the video recorder service. If this is - /// not specified, the topic defaults to:
- /// `/world//link//` - /// `sensor//record_video` + /// Name of topic for the video recorder service. If this is + /// not specified, the topic defaults to: + /// /world//link// + /// sensor//record_video + /// + /// True/false value that specifies if the video should + /// be recorded using simulation time or real time. The + /// default is false, which indicates the use of real + /// time. + /// + /// Video recorder frames per second. The default value is 25, and + /// the support type is unsigned int. + /// + /// Video recorder bitrate (bps). The default value is + /// 2070000 bps, and the supported type is unsigned int. class CameraVideoRecorder: public System, public ISystemConfigure, From 51315800dee1216433e25803ca348391366e395e Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Thu, 23 Sep 2021 11:46:59 -0700 Subject: [PATCH 5/6] 4 11 0 prep (#1044) * 4.11.0 release prep Signed-off-by: Nate Koenig * Update Changelog.md Co-authored-by: Nate Koenig --- CMakeLists.txt | 2 +- Changelog.md | 7 +++++-- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index f177053877..aceb261bd4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) #============================================================================ # Initialize the project #============================================================================ -project(ignition-gazebo4 VERSION 4.10.0) +project(ignition-gazebo4 VERSION 4.11.0) #============================================================================ # Find ignition-cmake diff --git a/Changelog.md b/Changelog.md index e27c54dad2..365587f6ed 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,8 +1,11 @@ ## Ignition Gazebo 4.x -### Ignition Gazebo 4.x.x (202x-xx-xx) +### Ignition Gazebo 4.11.x (2021-09-23) -### Ignition Gazebo 4.x.x (2021-09-15) +1. Support locked entities, and headless video recording using sim time. + * [Pull Request 862](https://github.com/ignitionrobotics/ign-gazebo/pull/862) + +### Ignition Gazebo 4.10.x (2021-09-15) 1. Fixed GUI's ComponentInspector light parameter * [Pull Request 1018](https://github.com/ignitionrobotics/ign-gazebo/pull/1018) From 3fbddd120547b0fcdc8475dab924e9607bcbb4a4 Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Fri, 24 Sep 2021 16:14:36 -0500 Subject: [PATCH 6/6] Fix performance issue with contact data and AABB updates (#1048) `ComponentState::OneTimeChange` was used when updating the `AxisAlignedBox` and `ContactSensorData` components which causes all components to be serialized and sent over to state subscribers. Signed-off-by: Addisu Z. Taddese --- src/systems/physics/Physics.cc | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index f9bc84c890..38c2b285f7 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -1808,7 +1808,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm) math::AxisAlignedBox bbox = math::eigen3::convert(bbModel->GetAxisAlignedBoundingBox()); auto state = _bbox->SetData(bbox, this->axisAlignedBoxEql) ? - ComponentState::OneTimeChange : + ComponentState::PeriodicChange : ComponentState::NoChange; _ecm.SetChanged(_entity, components::AxisAlignedBox::typeId, state); @@ -2465,7 +2465,7 @@ void PhysicsPrivate::UpdateCollisions(EntityComponentManager &_ecm) // Clear the last contact data auto state = _contacts->SetData(contactsComp, this->contactsEql) ? - ComponentState::OneTimeChange : + ComponentState::PeriodicChange : ComponentState::NoChange; _ecm.SetChanged( _collEntity1, components::ContactSensorData::typeId, state); @@ -2490,7 +2490,7 @@ void PhysicsPrivate::UpdateCollisions(EntityComponentManager &_ecm) auto state = _contacts->SetData(contactsComp, this->contactsEql) ? - ComponentState::OneTimeChange : + ComponentState::PeriodicChange : ComponentState::NoChange; _ecm.SetChanged( _collEntity1, components::ContactSensorData::typeId, state);