|
18 | 18 |
|
19 | 19 | #include "Utils.hh"
|
20 | 20 |
|
21 |
| -#include <ignition/common/MeshManager.hh> |
| 21 | +#include <gz/common/MeshManager.hh> |
22 | 22 |
|
23 |
| -#include <ignition/gazebo/components/Geometry.hh> |
24 |
| -#include <ignition/gazebo/components/Visual.hh> |
25 |
| -#include <ignition/gazebo/System.hh> |
| 23 | +#include <gz/sim/components/Geometry.hh> |
| 24 | +#include <gz/sim/components/Visual.hh> |
| 25 | +#include <gz/sim/System.hh> |
26 | 26 |
|
27 |
| -#include <ignition/transport/Node.hh> |
| 27 | +#include <gz/transport/Node.hh> |
28 | 28 |
|
29 | 29 | namespace rgl
|
30 | 30 | {
|
31 | 31 |
|
32 | 32 | class RGLServerPluginManager :
|
33 |
| - public ignition::gazebo::System, |
34 |
| - public ignition::gazebo::ISystemConfigure, |
35 |
| - public ignition::gazebo::ISystemPostUpdate |
| 33 | + public gz::sim::System, |
| 34 | + public gz::sim::ISystemConfigure, |
| 35 | + public gz::sim::ISystemPostUpdate |
36 | 36 | {
|
37 | 37 | public:
|
38 |
| - using MeshInfo = std::variant<std::monostate, const ignition::common::Mesh*, ignition::common::SubMesh>; |
| 38 | + using MeshInfo = std::variant<std::monostate, const gz::common::Mesh*, gz::common::SubMesh>; |
39 | 39 |
|
40 | 40 | RGLServerPluginManager() = default;
|
41 | 41 | ~RGLServerPluginManager() override = default;
|
42 | 42 |
|
43 | 43 | // only called once, when plugin is being loaded
|
44 | 44 | void Configure(
|
45 |
| - const ignition::gazebo::Entity& entity, |
| 45 | + const gz::sim::Entity& entity, |
46 | 46 | const std::shared_ptr<const sdf::Element>& sdf,
|
47 |
| - ignition::gazebo::EntityComponentManager& ecm, |
48 |
| - ignition::gazebo::EventManager& eventMgr) override; |
| 47 | + gz::sim::EntityComponentManager& ecm, |
| 48 | + gz::sim::EventManager& eventMgr) override; |
49 | 49 |
|
50 | 50 | // called every time after physics runs (can't change entities)
|
51 | 51 | void PostUpdate(
|
52 |
| - const ignition::gazebo::UpdateInfo& info, |
53 |
| - const ignition::gazebo::EntityComponentManager& ecm) override; |
| 52 | + const gz::sim::UpdateInfo& info, |
| 53 | + const gz::sim::EntityComponentManager& ecm) override; |
54 | 54 |
|
55 | 55 | private:
|
56 | 56 | ////////////////////////////////////////////// Variables /////////////////////////////////////////////
|
57 | 57 |
|
58 | 58 | ////////////////////////////// Lidar ////////////////////////////////
|
59 | 59 | // contains pointers to all entities that were loaded to rgl (as well as to their meshes)
|
60 |
| - std::unordered_map<ignition::gazebo::Entity, std::pair<rgl_entity_t, rgl_mesh_t>> entitiesInRgl; |
| 60 | + std::unordered_map<gz::sim::Entity, std::pair<rgl_entity_t, rgl_mesh_t>> entitiesInRgl; |
61 | 61 |
|
62 | 62 | // the entity ids, that the lidars are attached to
|
63 |
| - std::unordered_set<ignition::gazebo::Entity> lidarEntities; |
| 63 | + std::unordered_set<gz::sim::Entity> lidarEntities; |
64 | 64 |
|
65 | 65 | // all entities, that the lidar should ignore
|
66 |
| - std::unordered_set<ignition::gazebo::Entity> entitiesToIgnore; |
| 66 | + std::unordered_set<gz::sim::Entity> entitiesToIgnore; |
67 | 67 |
|
68 | 68 | ////////////////////////////// Mesh /////////////////////////////////
|
69 | 69 |
|
70 |
| - ignition::common::MeshManager* meshManager{ignition::common::MeshManager::Instance()}; |
| 70 | + gz::common::MeshManager* meshManager{gz::common::MeshManager::Instance()}; |
71 | 71 |
|
72 | 72 | ////////////////////////////////////////////// Functions /////////////////////////////////////////////
|
73 | 73 |
|
74 | 74 | ////////////////////////////// Scene ////////////////////////////////
|
75 | 75 |
|
76 | 76 | bool RegisterNewLidarCb(
|
77 |
| - ignition::gazebo::Entity entity, |
78 |
| - const ignition::gazebo::EntityComponentManager& ecm); |
| 77 | + gz::sim::Entity entity, |
| 78 | + const gz::sim::EntityComponentManager& ecm); |
79 | 79 |
|
80 | 80 | bool UnregisterLidarCb(
|
81 |
| - ignition::gazebo::Entity entity, |
82 |
| - const ignition::gazebo::EntityComponentManager& ecm); |
| 81 | + gz::sim::Entity entity, |
| 82 | + const gz::sim::EntityComponentManager& ecm); |
83 | 83 |
|
84 | 84 | bool LoadEntityToRGLCb(
|
85 |
| - const ignition::gazebo::Entity& entity, |
86 |
| - const ignition::gazebo::components::Visual*, |
87 |
| - const ignition::gazebo::components::Geometry* geometry); |
| 85 | + const gz::sim::Entity& entity, |
| 86 | + const gz::sim::components::Visual*, |
| 87 | + const gz::sim::components::Geometry* geometry); |
88 | 88 |
|
89 | 89 | bool RemoveEntityFromRGLCb(
|
90 |
| - const ignition::gazebo::Entity& entity, |
91 |
| - const ignition::gazebo::components::Visual*, |
92 |
| - const ignition::gazebo::components::Geometry*); |
| 90 | + const gz::sim::Entity& entity, |
| 91 | + const gz::sim::components::Visual*, |
| 92 | + const gz::sim::components::Geometry*); |
93 | 93 |
|
94 |
| - void UpdateRGLEntityPoses(const ignition::gazebo::EntityComponentManager& ecm); |
| 94 | + void UpdateRGLEntityPoses(const gz::sim::EntityComponentManager& ecm); |
95 | 95 |
|
96 |
| - std::unordered_set<ignition::gazebo::Entity> GetEntitiesInParentLink( |
97 |
| - ignition::gazebo::Entity entity, |
98 |
| - const ignition::gazebo::EntityComponentManager& ecm); |
| 96 | + std::unordered_set<gz::sim::Entity> GetEntitiesInParentLink( |
| 97 | + gz::sim::Entity entity, |
| 98 | + const gz::sim::EntityComponentManager& ecm); |
99 | 99 |
|
100 | 100 | ////////////////////////////// Mesh /////////////////////////////////
|
101 | 101 |
|
|
0 commit comments