Skip to content

Commit d4fa1de

Browse files
authored
Upgrade to RGL v0.17 (#35)
* Upgrade to RGL v0.17 (#34) * Make it compatible with RGL v17 * Add support for intensity (LaserRerto) * Optimization: prioritize node from which data will be requested first * No need to transfrom points to Lidar frame when publishing LaserScan * Add support for min range * Add acknowledgements * Update RGL download process in CMakeLists * Review changes * Fix README (code snippet for pattern should contain only pattern) * Update README * Use gz{log-level} instead of ign{log-level}
1 parent f8e216b commit d4fa1de

File tree

13 files changed

+273
-170
lines changed

13 files changed

+273
-170
lines changed

README.md

Lines changed: 22 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -19,13 +19,13 @@ Key features:
1919

2020
## Requirements:
2121

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

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

2626
- GPU: CUDA-enabled
2727

28-
- Nvidia Driver: [See RGL requirements](https://github.com/RobotecAI/RobotecGPULidar/tree/v0.11.3#runtime-requirements)
28+
- Nvidia Driver: [See RGL requirements](https://github.com/RobotecAI/RobotecGPULidar/tree/v0.17.0#runtime-requirements)
2929

3030
## Installation:
3131

@@ -53,7 +53,7 @@ Key features:
5353
```shell
5454
mkdir build
5555
cd build
56-
cmake ..
56+
cmake .. # Add `-DRGL_FORCE_DOWNLOAD=ON` to make sure the downloaded RGL will be up-to-date
5757
make -j
5858
make install
5959
cd ..
@@ -97,7 +97,10 @@ Inside the link entity in your model, add a custom sensor:
9797
```xml
9898
<sensor name="UniqueSensorName" type="custom">
9999
<plugin filename="RGLServerPluginInstance" name="rgl::RGLServerPluginInstance">
100-
<range>100</range>
100+
<range>
101+
<min>0</min>
102+
<max>100</max>
103+
</range>
101104
<update_rate>10</update_rate>
102105
<update_on_paused_sim>false</update_on_paused_sim>
103106
<topic>rgl_lidar</topic>
@@ -109,7 +112,7 @@ Inside the link entity in your model, add a custom sensor:
109112
*Note: All entities attached to the same \<link\> as lidar will be ignored from raycasting. This enables an adding visual representation of the sensor.*
110113

111114
### Parameters description:
112-
- **range** - the maximum range that the hits will be registered (in meters).
115+
- **range** - the minimum and maximum range that the hits will be registered (in meters).
113116

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

@@ -190,22 +193,13 @@ Inside the link entity in your model, add a custom sensor:
190193
the `horizontal` element and publishes a
191194
`LaserScan` message instead of a point cloud
192195
```xml
193-
<sensor name="Pattern2DLidar" type="custom">
194-
<plugin filename="RGLServerPluginInstance" name="rgl::RGLServerPluginInstance">
195-
<range>100</range>
196-
<update_rate>10</update_rate>
197-
<update_on_paused_sim>false</update_on_paused_sim>
198-
<topic>rgl_lidar</topic>
199-
<frame>RGLLidar</frame>
200-
<pattern_lidar2d>
201-
<horizontal>
202-
<samples>1800</samples>
203-
<min_angle>-3.14159</min_angle>
204-
<max_angle>3.14159</max_angle>
205-
</horizontal>
206-
</pattern_lidar2d>
207-
</plugin>
208-
</sensor>
196+
<pattern_lidar2d>
197+
<horizontal>
198+
<samples>1800</samples>
199+
<min_angle>-3.14159</min_angle>
200+
<max_angle>3.14159</max_angle>
201+
</horizontal>
202+
</pattern_lidar2d>
209203
```
210204

211205
## How to visualize in Gazebo
@@ -225,4 +219,9 @@ At [Robotec.AI](https://robotec.ai/) we care about every little detail of our pr
225219
## Ray pattern comparison
226220
| **RGL uniform pattern** | **gpu_lidar uniform pattern** |
227221
|---|---|
228-
| ![](docs/images/RGL_uniform.png) | ![](docs/images/GPU_lidar_uniform.png) |
222+
| ![](docs/images/RGL_uniform.png) | ![](docs/images/GPU_lidar_uniform.png) |
223+
224+
## Acknowledgements
225+
226+
The project benefited from significant contributions and support of [Dexory](https://www.dexory.com/).
227+
Features such as LaserScan publishing and Laser Retro as well as update to the newest RGL version were possible thanks to their dedication to the open source community.

RGLServerPlugin/CMakeLists.txt

Lines changed: 27 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -12,22 +12,38 @@ set(GZ_SIM_VER ${gz-sim8_VERSION_MAJOR})
1212

1313
include_directories(include)
1414

15-
set(RGL_VERSION "0.11.3")
15+
# Use this variable to make sure the downloaded RGL will be up-to-date
16+
set(RGL_FORCE_DOWNLOAD OFF BOOL)
17+
18+
set(RGL_TAG "v0.17.0")
19+
1620
set(RGL_PATH "${CMAKE_CURRENT_SOURCE_DIR}/include/rgl")
17-
set(RGL_SO_PATH "${RGL_PATH}/libRobotecGPULidar.so")
18-
set(RGL_API_PATH "${RGL_PATH}/api/core.h")
19-
set(RGL_COMMIT "e5ea8a1a74c253a304f4d1d4652391bca9d448e6")
20-
set(RGL_SO_URL "https://github.com/RobotecAI/RobotecGPULidar/releases/download/v${RGL_VERSION}/libRobotecGPULidar.so")
21-
set(RGL_API_URL "https://raw.githubusercontent.com/RobotecAI/RobotecGPULidar/${RGL_COMMIT}/include/rgl/api/core.h")
22-
23-
# You have to delete old files manually in order to download
24-
# new ones automatically if a new version is available.
21+
set(RGL_SO_FILENAME "libRobotecGPULidar.so")
22+
set(RGL_SO_PATH "${RGL_PATH}/${RGL_SO_FILENAME}")
23+
set(RGL_API_HEADER_PATH "${RGL_PATH}/api/core.h")
24+
25+
set(RGL_SO_ZIP_FILENAME "RGL-core-linux-x64.zip")
26+
set(RGL_SO_ZIP_URL "https://github.com/RobotecAI/RobotecGPULidar/releases/download/${RGL_TAG}/${RGL_SO_ZIP_FILENAME}")
27+
set(RGL_API_HEADER_URL "https://raw.githubusercontent.com/RobotecAI/RobotecGPULidar/${RGL_TAG}/include/rgl/api/core.h")
28+
29+
if (RGL_FORCE_DOWNLOAD)
30+
file(REMOVE_RECURSE ${RGL_PATH})
31+
endif()
32+
33+
# Download RGL library
2534
if(NOT EXISTS ${RGL_SO_PATH})
26-
file(DOWNLOAD ${RGL_SO_URL} ${RGL_SO_PATH})
35+
file(DOWNLOAD ${RGL_SO_ZIP_URL} ${RGL_PATH}/${RGL_SO_ZIP_FILENAME})
36+
file(ARCHIVE_EXTRACT INPUT ${RGL_PATH}/${RGL_SO_ZIP_FILENAME}
37+
DESTINATION ${RGL_PATH}
38+
PATTERNS ${RGL_SO_FILENAME}
39+
VERBOSE
40+
)
41+
file(REMOVE ${RGL_PATH}/${RGL_SO_ZIP_FILENAME})
2742
endif()
2843

44+
# Download RGL API header
2945
if(NOT EXISTS ${RGL_API_PATH})
30-
file(DOWNLOAD ${RGL_API_URL} ${RGL_API_PATH})
46+
file(DOWNLOAD ${RGL_API_HEADER_URL} ${RGL_API_HEADER_PATH})
3147
endif()
3248

3349
set(RobotecGPULidar ${RGL_SO_PATH})

RGLServerPlugin/include/RGLServerPluginInstance.hh

Lines changed: 32 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -71,20 +71,43 @@ private:
7171
bool paused);
7272
void RayTrace(std::chrono::steady_clock::duration sim_time);
7373

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);
74+
bool FetchLaserScanResult();
75+
bool FetchPointCloudResult(rgl_node_t formatNode);
76+
77+
gz::msgs::PointCloudPacked CreatePointCloudMsg(std::chrono::steady_clock::duration sim_time, const std::string& frame);
78+
gz::msgs::LaserScan CreateLaserScanMsg(std::chrono::steady_clock::duration sim_time, const std::string& frame);
7679

7780
void DestroyLidar();
7881

7982
std::string topicName;
8083
std::string frameId;
81-
float lidarRange;
84+
rgl_vec2f lidarMinMaxRange;
8285
gz::math::Angle scanHMin;
8386
gz::math::Angle scanHMax;
8487
int scanHSamples;
8588
std::vector<rgl_mat3x4f> lidarPattern;
86-
std::vector<rgl_vec3f> resultPointCloud;
87-
std::vector<float> resultDistances;
89+
90+
struct ResultPointCloud
91+
{
92+
std::vector<char> data{};
93+
int32_t hitPointCount{};
94+
static constexpr std::size_t pointSize{sizeof(rgl_vec3f) + sizeof(float)}; // Based on rglFields
95+
inline static const std::vector<rgl_field_t> rglFields = {
96+
RGL_FIELD_XYZ_VEC3_F32,
97+
RGL_FIELD_LASER_RETRO_F32
98+
};
99+
} resultPointCloud{};
100+
101+
struct ResultLaserScan
102+
{
103+
std::vector<float> distances{};
104+
std::vector<float> intensities{};
105+
// No hitPointCount needed because LaserScan message contains non-hits also
106+
inline static const std::vector<rgl_field_t> rglFields = {
107+
RGL_FIELD_DISTANCE_F32,
108+
RGL_FIELD_LASER_RETRO_F32
109+
};
110+
} resultLaserScan{};
88111

89112
bool updateOnPausedSim = false;
90113
bool publishLaserScan = false;
@@ -97,9 +120,12 @@ private:
97120

98121
rgl_node_t rglNodeUseRays = nullptr;
99122
rgl_node_t rglNodeLidarPose = nullptr;
123+
rgl_node_t rglNodeSetRange = nullptr;
100124
rgl_node_t rglNodeRaytrace = nullptr;
101125
rgl_node_t rglNodeCompact = nullptr;
102-
rgl_node_t rglNodeYield = nullptr;
126+
rgl_node_t rglNodeYieldLaserScan = nullptr;
127+
rgl_node_t rglNodeFormatPointCloudSensor = nullptr;
128+
rgl_node_t rglNodeFormatPointCloudWorld = nullptr;
103129
rgl_node_t rglNodeToLidarFrame = nullptr;
104130

105131
std::chrono::steady_clock::duration raytraceIntervalTime;

RGLServerPlugin/include/RGLServerPluginManager.hh

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
#include <gz/common/MeshManager.hh>
2222

2323
#include <gz/sim/components/Geometry.hh>
24+
#include <gz/sim/components/LaserRetro.hh>
2425
#include <gz/sim/components/Visual.hh>
2526
#include <gz/sim/System.hh>
2627

@@ -91,6 +92,10 @@ private:
9192
const gz::sim::components::Visual*,
9293
const gz::sim::components::Geometry*);
9394

95+
bool SetLaserRetroCb(
96+
const gz::sim::Entity& entity,
97+
const gz::sim::components::LaserRetro* laser_retro);
98+
9499
void UpdateRGLEntityPoses(const gz::sim::EntityComponentManager& ecm);
95100

96101
std::unordered_set<gz::sim::Entity> GetEntitiesInParentLink(

0 commit comments

Comments
 (0)