Skip to content

Commit f8e216b

Browse files
authored
Migration to Gazebo Harmonic (#32)
* Migrate CMakeLists to work with gz harmonic * Migrate source code to work with gz harmonic * Update test worlds * Aling readme to gz harmonic * Aling readme to gz harmonic, fix link to gz * Fix warnings about deprecated functions calls.
1 parent c106bd8 commit f8e216b

19 files changed

+277
-260
lines changed

README.md

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -14,14 +14,14 @@ RGL Gazebo Plugin has been created by [Robotec.AI](https://robotec.ai/) to bring
1414
Key features:
1515
- Point cloud computation using hardware-accelerated raytracing (Nvidia OptiX)
1616
- High performance (~4x improvement over `gpu_lidar` sensor from Gazebo)
17-
- Multiple LiDAR pattern configuration methods, including importing a pattern from a binary file
17+
- Multiple LiDAR pattern configuration methods, including importing a pattern from a binary file
1818
- Realistic presets of the most popular LiDARs
1919

2020
## Requirements:
2121

2222
- OS: [Ubuntu 20.04](https://releases.ubuntu.com/focal/) or [Ubuntu 22.04](https://releases.ubuntu.com/jammy/)
2323

24-
- Gazebo: [Fortress 6.14](https://gazebosim.org/docs/fortress/install)
24+
- Gazebo: [Fortress 8.3](https://gazebosim.org/docs/harmonic/installl)
2525

2626
- GPU: CUDA-enabled
2727

@@ -46,8 +46,8 @@ Key features:
4646
# libRGLServerPluginInstance.so, libRGLServerPluginManager.so and libRobotecGPULidar.so
4747
# are located in RGLServerPlugin directory,
4848
# and libRGLVisualize.so in RGLGuiPlugin.
49-
export IGN_GAZEBO_SYSTEM_PLUGIN_PATH=`pwd`/RGLServerPlugin:$IGN_GAZEBO_SYSTEM_PLUGIN_PATH
50-
export IGN_GUI_PLUGIN_PATH=`pwd`/RGLGuiPlugin:$IGN_GUI_PLUGIN_PATH
49+
export GZ_SIM_SYSTEM_PLUGIN_PATH=`pwd`/RGLServerPlugin:$GZ_SIM_SYSTEM_PLUGIN_PATH
50+
export GZ_GUI_PLUGIN_PATH=`pwd`/RGLGuiPlugin:$GZ_GUI_PLUGIN_PATH
5151
```
5252
### Building from source
5353
```shell
@@ -57,16 +57,16 @@ cmake ..
5757
make -j
5858
make install
5959
cd ..
60-
export IGN_GAZEBO_SYSTEM_PLUGIN_PATH=`pwd`/install/RGLServerPlugin:$IGN_GAZEBO_SYSTEM_PLUGIN_PATH
61-
export IGN_GUI_PLUGIN_PATH=`pwd`/install/RGLVisualize:$IGN_GUI_PLUGIN_PATH
60+
export GZ_SIM_SYSTEM_PLUGIN_PATH=`pwd`/install/RGLServerPlugin:$GZ_SIM_SYSTEM_PLUGIN_PATH
61+
export GZ_GUI_PLUGIN_PATH=`pwd`/install/RGLVisualize:$GZ_GUI_PLUGIN_PATH
6262
```
6363
## Demo:
6464

6565
![](docs/videos/prius.gif)
6666

6767
Launch the prepared simulation from `test_world` directory:
6868
```shell
69-
ign gazebo sonoma_with_rgl.sdf
69+
gz sim sonoma_with_rgl.sdf
7070
```
7171

7272
1. Start the simulation by pressing play
@@ -77,7 +77,7 @@ The second sample world (rgl_playground.sdf) contains all supported object types
7777
```shell
7878
# From the top-level directory of this repository
7979
export RGL_PATTERNS_DIR=`pwd`/lidar_patterns
80-
ign gazebo test_world/rgl_playground.sdf
80+
gz sim test_world/rgl_playground.sdf
8181
```
8282

8383
## Using the plugin:
@@ -113,7 +113,7 @@ Inside the link entity in your model, add a custom sensor:
113113

114114
- **update_rate** - the frequency at which the lidar will perform raycasting (in Hz).
115115

116-
- **topic** - topic on which pointcloud message (ignition::msgs::PointCloudPacked) will be published. A second topic with the `/world` postfix will also be created for visualization purposes.
116+
- **topic** - topic on which pointcloud message (gz::msgs::PointCloudPacked) will be published. A second topic with the `/world` postfix will also be created for visualization purposes.
117117

118118
- **frame** - frame_id for point cloud message header.
119119

@@ -153,7 +153,7 @@ Inside the link entity in your model, add a custom sensor:
153153
```
154154

155155
- **pattern_preset**\
156-
We have prepared several lidar presets. You can type in the name of a LiDAR to use its pattern (all available patterns are shown below).
156+
We have prepared several lidar presets. You can type in the name of a LiDAR to use its pattern (all available patterns are shown below).
157157
```xml
158158
<pattern_preset>Alpha Prime</pattern_preset>
159159
<pattern_preset>Puck</pattern_preset>
@@ -186,8 +186,8 @@ Inside the link entity in your model, add a custom sensor:
186186
```
187187

188188
- **pattern_lidar2d**\
189-
Almost the same as `pattern_uniform` but only has
190-
the `horizontal` element and publishes a
189+
Almost the same as `pattern_uniform` but only has
190+
the `horizontal` element and publishes a
191191
`LaserScan` message instead of a point cloud
192192
```xml
193193
<sensor name="Pattern2DLidar" type="custom">

RGLServerPlugin/CMakeLists.txt

Lines changed: 11 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -2,8 +2,13 @@ cmake_minimum_required(VERSION 3.16)
22
project(RGLServerPlugin)
33
set(CMAKE_CXX_STANDARD 20)
44

5-
find_package(ignition-gazebo6 REQUIRED)
6-
find_package(ignition-plugin1 REQUIRED)
5+
find_package(gz-cmake3 REQUIRED)
6+
gz_find_package(gz-plugin2 REQUIRED COMPONENTS register)
7+
set(GZ_PLUGIN_VER ${gz-plugin2_VERSION_MAJOR})
8+
9+
gz_find_package(gz-sim8 REQUIRED)
10+
set(GZ_SIM_VER ${gz-sim8_VERSION_MAJOR})
11+
712

813
include_directories(include)
914

@@ -29,16 +34,16 @@ set(RobotecGPULidar ${RGL_SO_PATH})
2934

3035
add_library(RGLServerPluginManager SHARED src/RGLServerPluginManager.cc src/Mesh.cc src/Utils.cc src/Scene.cc)
3136
target_link_libraries(RGLServerPluginManager
32-
ignition-gazebo6::ignition-gazebo6
33-
ignition-plugin1::ignition-plugin1
37+
PRIVATE gz-plugin${GZ_PLUGIN_VER}::gz-plugin${GZ_PLUGIN_VER}
38+
PRIVATE gz-sim${GZ_SIM_VER}::gz-sim${GZ_SIM_VER}
3439
${RobotecGPULidar}
3540
)
3641
set_target_properties(RGLServerPluginManager PROPERTIES INSTALL_RPATH "$ORIGIN")
3742

3843
add_library(RGLServerPluginInstance SHARED src/RGLServerPluginInstance.cc src/Lidar.cc src/Utils.cc src/LidarPatternLoader.cc)
3944
target_link_libraries(RGLServerPluginInstance
40-
ignition-gazebo6::ignition-gazebo6
41-
ignition-plugin1::ignition-plugin1
45+
PRIVATE gz-plugin${GZ_PLUGIN_VER}::gz-plugin${GZ_PLUGIN_VER}
46+
PRIVATE gz-sim${GZ_SIM_VER}::gz-sim${GZ_SIM_VER}
4247
${RobotecGPULidar}
4348
)
4449
set_target_properties(RGLServerPluginInstance PROPERTIES INSTALL_RPATH "$ORIGIN")

RGLServerPlugin/include/LidarPatternLoader.hh

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -19,8 +19,7 @@
1919

2020
#include <rgl/api/core.h>
2121

22-
#include <ignition/gazebo/System.hh>
23-
22+
#include <gz/sim/System.hh>
2423
namespace rgl
2524
{
2625

@@ -35,7 +34,7 @@ private:
3534
LidarPatternLoader() {};
3635

3736
static bool LoadAnglesAndSamplesElement(const sdf::ElementConstPtr& sdf,
38-
ignition::math::Angle& angleMin, ignition::math::Angle& angleMax,
37+
gz::math::Angle& angleMin, gz::math::Angle& angleMax,
3938
int& samples);
4039

4140
static bool LoadPatternFromUniform(const sdf::ElementConstPtr& sdf, std::vector<rgl_mat3x4f>& outPattern);
@@ -44,9 +43,9 @@ private:
4443
static bool LoadPatternFromPresetPath(const sdf::ElementConstPtr& sdf, std::vector<rgl_mat3x4f>& outPattern);
4544
static bool LoadPatternFromLidar2d(const sdf::ElementConstPtr& sdf, std::vector<rgl_mat3x4f>& outPattern);
4645

47-
static rgl_mat3x4f AnglesToRglMat3x4f(const ignition::math::Angle& roll,
48-
const ignition::math::Angle& pitch,
49-
const ignition::math::Angle& yaw);
46+
static rgl_mat3x4f AnglesToRglMat3x4f(const gz::math::Angle& roll,
47+
const gz::math::Angle& pitch,
48+
const gz::math::Angle& yaw);
5049

5150
template<typename T>
5251
static std::vector<T> LoadVector(const std::filesystem::path& path);

RGLServerPlugin/include/RGLServerPluginInstance.hh

Lines changed: 30 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -19,22 +19,24 @@
1919
#include "rgl/api/core.h"
2020
#include "LidarPatternLoader.hh"
2121

22-
#include <ignition/common/MeshManager.hh>
22+
#include <gz/common/MeshManager.hh>
2323

24-
#include <ignition/gazebo/components/Geometry.hh>
25-
#include <ignition/gazebo/components/Visual.hh>
26-
#include <ignition/gazebo/System.hh>
24+
#include <gz/sim/components/Geometry.hh>
25+
#include <gz/sim/components/Visual.hh>
26+
#include <gz/sim/System.hh>
27+
28+
#include <gz/transport/Node.hh>
29+
#include <gz/msgs/details/laserscan.pb.h>
2730

28-
#include <ignition/transport/Node.hh>
2931

3032
namespace rgl
3133
{
3234

3335
class RGLServerPluginInstance :
34-
public ignition::gazebo::System,
35-
public ignition::gazebo::ISystemConfigure,
36-
public ignition::gazebo::ISystemPreUpdate,
37-
public ignition::gazebo::ISystemPostUpdate
36+
public gz::sim::System,
37+
public gz::sim::ISystemConfigure,
38+
public gz::sim::ISystemPreUpdate,
39+
public gz::sim::ISystemPostUpdate
3840
{
3941
public:
4042
RGLServerPluginInstance() = default;
@@ -43,42 +45,42 @@ public:
4345

4446
// only called once, when plugin is being loaded
4547
void Configure(
46-
const ignition::gazebo::Entity& entity,
48+
const gz::sim::Entity& entity,
4749
const std::shared_ptr<const sdf::Element>& sdf,
48-
ignition::gazebo::EntityComponentManager& ecm,
49-
ignition::gazebo::EventManager& eventMgr) override;
50+
gz::sim::EntityComponentManager& ecm,
51+
gz::sim::EventManager& eventMgr) override;
5052

5153
// called every time before physics update runs (can change entities)
5254
void PreUpdate(
53-
const ignition::gazebo::UpdateInfo& info,
54-
ignition::gazebo::EntityComponentManager& ecm) override;
55+
const gz::sim::UpdateInfo& info,
56+
gz::sim::EntityComponentManager& ecm) override;
5557

5658
// called every time after physics runs (can't change entities)
5759
void PostUpdate(
58-
const ignition::gazebo::UpdateInfo& info,
59-
const ignition::gazebo::EntityComponentManager& ecm) override;
60+
const gz::sim::UpdateInfo& info,
61+
const gz::sim::EntityComponentManager& ecm) override;
6062

6163
private:
6264
bool LoadConfiguration(const std::shared_ptr<const sdf::Element>& sdf);
63-
void CreateLidar(ignition::gazebo::Entity entity,
64-
ignition::gazebo::EntityComponentManager& ecm);
65+
void CreateLidar(gz::sim::Entity entity,
66+
gz::sim::EntityComponentManager& ecm);
6567

66-
void UpdateLidarPose(const ignition::gazebo::EntityComponentManager& ecm);
68+
void UpdateLidarPose(const gz::sim::EntityComponentManager& ecm);
6769

6870
bool ShouldRayTrace(std::chrono::steady_clock::duration sim_time,
6971
bool paused);
7072
void RayTrace(std::chrono::steady_clock::duration sim_time);
7173

72-
ignition::msgs::PointCloudPacked CreatePointCloudMsg(std::chrono::steady_clock::duration sim_time, std::string frame, int hitpointCount);
73-
ignition::msgs::LaserScan CreateLaserScanMsg(std::chrono::steady_clock::duration sim_time, std::string frame, int hitpointCount);
74+
gz::msgs::PointCloudPacked CreatePointCloudMsg(std::chrono::steady_clock::duration sim_time, std::string frame, int hitpointCount);
75+
gz::msgs::LaserScan CreateLaserScanMsg(std::chrono::steady_clock::duration sim_time, std::string frame, int hitpointCount);
7476

7577
void DestroyLidar();
7678

7779
std::string topicName;
7880
std::string frameId;
7981
float lidarRange;
80-
ignition::math::Angle scanHMin;
81-
ignition::math::Angle scanHMax;
82+
gz::math::Angle scanHMin;
83+
gz::math::Angle scanHMax;
8284
int scanHSamples;
8385
std::vector<rgl_mat3x4f> lidarPattern;
8486
std::vector<rgl_vec3f> resultPointCloud;
@@ -87,11 +89,11 @@ private:
8789
bool updateOnPausedSim = false;
8890
bool publishLaserScan = false;
8991

90-
ignition::gazebo::Entity thisLidarEntity;
91-
ignition::transport::Node::Publisher pointCloudPublisher;
92-
ignition::transport::Node::Publisher laserScanPublisher;
93-
ignition::transport::Node::Publisher pointCloudWorldPublisher;
94-
ignition::transport::Node gazeboNode;
92+
gz::sim::Entity thisLidarEntity;
93+
gz::transport::Node::Publisher pointCloudPublisher;
94+
gz::transport::Node::Publisher laserScanPublisher;
95+
gz::transport::Node::Publisher pointCloudWorldPublisher;
96+
gz::transport::Node gazeboNode;
9597

9698
rgl_node_t rglNodeUseRays = nullptr;
9799
rgl_node_t rglNodeLidarPose = nullptr;

RGLServerPlugin/include/RGLServerPluginManager.hh

Lines changed: 32 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -18,84 +18,84 @@
1818

1919
#include "Utils.hh"
2020

21-
#include <ignition/common/MeshManager.hh>
21+
#include <gz/common/MeshManager.hh>
2222

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>
2626

27-
#include <ignition/transport/Node.hh>
27+
#include <gz/transport/Node.hh>
2828

2929
namespace rgl
3030
{
3131

3232
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
3636
{
3737
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>;
3939

4040
RGLServerPluginManager() = default;
4141
~RGLServerPluginManager() override = default;
4242

4343
// only called once, when plugin is being loaded
4444
void Configure(
45-
const ignition::gazebo::Entity& entity,
45+
const gz::sim::Entity& entity,
4646
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;
4949

5050
// called every time after physics runs (can't change entities)
5151
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;
5454

5555
private:
5656
////////////////////////////////////////////// Variables /////////////////////////////////////////////
5757

5858
////////////////////////////// Lidar ////////////////////////////////
5959
// 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;
6161

6262
// 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;
6464

6565
// all entities, that the lidar should ignore
66-
std::unordered_set<ignition::gazebo::Entity> entitiesToIgnore;
66+
std::unordered_set<gz::sim::Entity> entitiesToIgnore;
6767

6868
////////////////////////////// Mesh /////////////////////////////////
6969

70-
ignition::common::MeshManager* meshManager{ignition::common::MeshManager::Instance()};
70+
gz::common::MeshManager* meshManager{gz::common::MeshManager::Instance()};
7171

7272
////////////////////////////////////////////// Functions /////////////////////////////////////////////
7373

7474
////////////////////////////// Scene ////////////////////////////////
7575

7676
bool RegisterNewLidarCb(
77-
ignition::gazebo::Entity entity,
78-
const ignition::gazebo::EntityComponentManager& ecm);
77+
gz::sim::Entity entity,
78+
const gz::sim::EntityComponentManager& ecm);
7979

8080
bool UnregisterLidarCb(
81-
ignition::gazebo::Entity entity,
82-
const ignition::gazebo::EntityComponentManager& ecm);
81+
gz::sim::Entity entity,
82+
const gz::sim::EntityComponentManager& ecm);
8383

8484
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);
8888

8989
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*);
9393

94-
void UpdateRGLEntityPoses(const ignition::gazebo::EntityComponentManager& ecm);
94+
void UpdateRGLEntityPoses(const gz::sim::EntityComponentManager& ecm);
9595

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);
9999

100100
////////////////////////////// Mesh /////////////////////////////////
101101

0 commit comments

Comments
 (0)