Skip to content

Commit

Permalink
Final polish before open source (#36)
Browse files Browse the repository at this point in the history
* updated readme

* updated usage.md and readmeExample

* fixed indexing mistake in Usage.md

* fixed indexing mistake again in Usage.md

* deleted old unused pipeline files

* renamed experimental.h to core.h, LICENSE fix, unification of int and size_t types to uint32_t in API
  • Loading branch information
Jakub-Krakowiak authored and prybicki committed Nov 22, 2022
1 parent dc83da1 commit b30eb9a
Show file tree
Hide file tree
Showing 29 changed files with 177 additions and 483 deletions.
39 changes: 14 additions & 25 deletions LICENSE
Original file line number Diff line number Diff line change
@@ -1,3 +1,17 @@
Copyright 2022 ROBOTEC.AI

Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at

http://www.apache.org/licenses/LICENSE-2.0

Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.

Apache License
Version 2.0, January 2004
http://www.apache.org/licenses/
Expand Down Expand Up @@ -174,28 +188,3 @@
of your accepting any such warranty or additional liability.

END OF TERMS AND CONDITIONS

APPENDIX: How to apply the Apache License to your work.

To apply the Apache License to your work, attach the following
boilerplate notice, with the fields enclosed by brackets "{}"
replaced with your own identifying information. (Don't include
the brackets!) The text should be enclosed in the appropriate
comment syntax for the file format. We also recommend that a
file or class name and description of purpose be included on the
same "printed page" as the copyright notice for easier
identification within third-party archives.

Copyright 2019 Ingo Wald

Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at

http://www.apache.org/licenses/LICENSE-2.0

Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
60 changes: 25 additions & 35 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,13 +7,13 @@
## About the project

Robotec GPU Lidar (RGL) is a cross-platform (Windows and Linux), C/C++ library developed by [Robotec.AI](https://robotec.ai/)
for simulating LiDARs (computing a point cloud) on CUDA-enabled GPUs, accelerated by RTX cores if available.
for simulating [LiDARs](https://en.wikipedia.org/wiki/Lidar) on CUDA-enabled GPUs, accelerated by RTX cores if available.

One of the use-cases of RGL is implementing Lidar sensor in simulation engines.
We are working on integrations to some of the popular game / simulation engines:
- Unity (coming summer 2022)
- Gazebo (coming late summer 2022)
- O3DE (coming fall 2022)
One of the use-cases of RGL is implementing Lidar sensors in simulation engines.
We are working on integrations with popular game / simulation engines:
- [Unity](https://unity.com/)
- [O3DE](https://www.o3de.org/)
- [Gazebo](https://gazebosim.org/home)


If you would like to have a custom integration, feel free to [contact us](https://robotec.ai/contact/).
Expand All @@ -29,41 +29,31 @@ If you would like to have a custom integration, feel free to [contact us](https:

An introduction to the RGL API along with an example can be found [here](docs/Usage.md).

## Building in Docker (Linux)

1. Download [NVidia OptiX](https://developer.nvidia.com/designworks/optix/download) 7.2
2. `export OptiX_INSTALL_DIR=<Path to OptiX>`
3. `docker build . --tag rgl`
4. `docker run --net=host --gpus all -v $(pwd):/code -v ${OptiX_INSTALL_DIR}:/optix -e OptiX_INSTALL_DIR=/optix -e NVIDIA_DRIVER_CAPABILITIES=all -it rgl /bin/bash`
5. `mkdir build && cd build && cmake ../ && make`

## Building manually

**Note: you can use a pre-built binary version available on GitHub.**

1. Install [CUDA Toolkit](https://developer.nvidia.com/cuda-downloads) 11.2+.
2. Download [NVidia OptiX](https://developer.nvidia.com/designworks/optix/download) 7.2
1. You may be asked to create Nvidia account to download
2. Download [NVidia OptiX](https://developer.nvidia.com/designworks/optix/downloads/legacy) 7.2
1. You may be asked to create Nvidia account to download
3. If you are on Linux or you have chosen non-standard location on Windows when installing OptiX, you need to export environment variable `OptiX_INSTALL_DIR`.
4. Install [PCL](https://pointclouds.org/) 1.12 on Windows (on Linux this will be done automatically by using a prepared script).
1. Get [vcpkg](https://vcpkg.io/en/index.html):\
`git clone -b 2022.08.15 --single-branch --depth 1 https://github.com/microsoft/vcpkg`
2. Bootstrap `vcpkg`:\
`.\vcpkg\bootstrap-vcpkg.bat`
3. Install PCL:\
`.\vcpkg\vcpkg.exe install pcl[core,visualization]:x64-windows`
4. In order to use vcpkg with Visual Studio, run the following command (may require administrator elevation):\
`.\vcpkg\vcpkg.exe integrate install`
5. In order to use vcpkg with CMake, you can use the toolchain file:\
`cmake -B [build directory] -S . "-DCMAKE_TOOLCHAIN_FILE=[path to vcpkg]/scripts/buildsystems/vcpkg.cmake"`\
`cmake --build [build directory]`
1. Get [vcpkg](https://vcpkg.io/en/index.html):\
`git clone -b 2022.08.15 --single-branch --depth 1 https://github.com/microsoft/vcpkg`
2. Bootstrap `vcpkg`:\
`.\vcpkg\bootstrap-vcpkg.bat`
3. Install PCL:\
`.\vcpkg\vcpkg.exe install pcl[core,visualization]:x64-windows`
4. In order to use vcpkg with Visual Studio, run the following command (may require administrator elevation):\
`.\vcpkg\vcpkg.exe integrate install`
5. In order to use vcpkg with CMake, you can use the toolchain file:\
`cmake -B [build directory] -S . "-DCMAKE_TOOLCHAIN_FILE=[path to vcpkg]/scripts/buildsystems/vcpkg.cmake"`\
`cmake --build [build directory]`
5. Build the project:
- Linux:
- Use prepared `setup.bash` script for additional dependencies installation. You can run cmake and make at once by passing extra arguments:\
`./setup.bash --cmake {OPTIONAL_CMAKE_ARGS} --make {OPTIONAL_MAKE_ARGS}`
- On Windows
- You can use [CLion IDE](https://www.jetbrains.com/clion/) (recommended)
- Alternatively - [cmake-gui](https://cmake.org/download/) and Microsoft Visual Studio
- Linux:
- Use prepared `setup.bash` script for additional dependencies installation. You can run cmake and make at once by passing extra arguments:\
`./setup.bash --cmake {OPTIONAL_CMAKE_ARGS} --make {OPTIONAL_MAKE_ARGS}`
- On Windows
- You can use [CLion IDE](https://www.jetbrains.com/clion/) (recommended)
- Alternatively - [cmake-gui](https://cmake.org/download/) and Microsoft Visual Studio

## Troubleshooting

Expand Down
123 changes: 64 additions & 59 deletions docs/Usage.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,15 +6,9 @@ The C API is built around several concepts that are introduced in the following

## API concepts

### Scene

Scene represents 'a place' where the raytracing occurs.
User is expected to fill a scene with entities before performing ray-tracing.
Internally it is used to build hardware raytracing acceleration structures.
Most of the time, a single scene will be sufficient, therefore RGL automatically instantiates the default scene.
The default scene can be referenced by passing null pointer where scene handle is expected.
### Mesh

Note: using multiple scenes is not yet implemented.
Mesh is a handle to the on-GPU data of a 3D model provided by user.

### Entity

Expand All @@ -25,33 +19,49 @@ When created, entity is bound to a scene. Entity cannot be unbound from a scene
To create an Entity it is required to provide a Mesh, which must be created first.
Entities can share the same mesh.

### Mesh
### Scene

Mesh is a handle to the on-GPU data of a 3D model provided by user.
Scene represents 'a place' where the raytracing occurs.
User is expected to fill a scene with entities before performing ray-tracing.
Internally it is used to build hardware raytracing acceleration structures.
Most of the time, a single scene will be sufficient, therefore RGL automatically instantiates the default scene.
The default scene can be referenced by passing null pointer where scene handle is expected.

Note: using multiple scenes is not yet implemented.

### Lidar
### Node

Lidar represents properties of a Lidar such as:
- laser firing pattern
- range (may depend on angle)
- its pose in the scene
Performs a single operation, for example:
- set rays for raytracing from transforms
- transform rays
- set the desired output format
- compact result (remove non-hits)
- downsample result (merge points that are very close to each other)
- perform raytracing

Internally it is also associated with a number of GPU resources, which makes its creation/destruction cost significant.
Operations involving different Lidars are done in parallel on the GPU.
It has to be connected to other Nodes in order to function properly.
If a node is active, it is executed while running the Graph.
Nodes are active by default, but can be deactivated.
Children of deactivated Nodes are also not executed while running the Graph.

### Graph

Connected Nodes create a Graph. The Graph can be run to calculate the result for each node.
Using the graph concept the end user can easily tailor the functionality and output format to their needs by adding / removing certain Nodes.
The typical use-case is simulating a Lidar.

## General approach

Usually, using the library will consist of the following steps:

1. Create Meshes (e.g. use an external tool to read them from a file)
2. Create Entities on the scene
3. Create one or more Lidars
4. Set Entities' poses
5. Set Lidars' poses + configure other properties (e.g. range)
6. Schedule raycasting.
7. Get results
3. Create Nodes
4. Connect Nodes into Graph(s)
5. Set Entities' poses
6. Run Graph(s)

RGL is optimized to be used in ever-changing scenes, therefore it is possible to repeat steps 4-7 dozens of times per second (may vary depending on the number of entites and total number of rays).
RGL is optimized to be used in ever-changing scenes, therefore it is possible to repeat steps 5 and 6 dozens of times per second (may vary depending on the number of entites, rays and nodes).

## Minimal example

Expand All @@ -62,56 +72,51 @@ Full source code can be found [here](../test/src/apiReadmeExample.cpp)

```c
// Create a mesh
rgl_mesh_t mesh = 0;
RGL_CHECK(rgl_mesh_create(/*arguments omitted for brevity*/));
rgl_mesh_t cube_mesh = rgl_mesh_create(/* arguments skipped for the sake of brevity */);

// Put an entity on the default scene
rgl_entity_t entity = 0;
RGL_CHECK(rgl_entity_create(&entity, NULL, mesh));
rgl_entity_t cube_entity = 0;
EXPECT_RGL_SUCCESS(rgl_entity_create(&cube_entity, NULL, cube_mesh));

// Set position of the cube entity to (0, 0, 5)
rgl_mat3x4f entity_tf = {
.value = {
{1, 0, 0, 0},
{0, 1, 0, 0},
{0, 0, 1, 5}
}
.value = {
{ 1, 0, 0, 0 },
{ 0, 1, 0, 0 },
{ 0, 0, 1, 5 } }
};
RGL_CHECK(rgl_entity_set_pose(entity, &entity_tf));
EXPECT_RGL_SUCCESS(rgl_entity_set_pose(cube_entity, &entity_tf));

// Create a description of lidar that sends 1 ray
// By default, lidar will have infinite ray range
// and will be placed in (0, 0, 0), facing positive Z
rgl_lidar_t lidar = 0;
// Create a graph representation of a lidar that sends 1 ray and is situated at (x,y,z) = (0, 0, 0), facing positive Z
rgl_mat3x4f ray_tf = {
.value = {
{1, 0, 0, 0},
{0, 1, 0, 0},
{0, 0, 1, 0},
}
.value = {
{ 1, 0, 0, 0 },
{ 0, 1, 0, 0 },
{ 0, 0, 1, 0 },}
};
RGL_CHECK(rgl_lidar_create(&lidar, &ray_tf, 1));

// Start raytracing on the default scene
RGL_CHECK(rgl_lidar_raytrace_async(NULL, lidar));
rgl_node_t useRays = nullptr, raytrace = nullptr;

EXPECT_RGL_SUCCESS(rgl_node_rays_from_mat3x4f(&useRays, &ray_tf, 1));
EXPECT_RGL_SUCCESS(rgl_node_raytrace(&raytrace, nullptr, 1000));
EXPECT_RGL_SUCCESS(rgl_graph_node_add_child(useRays, raytrace));

// Wait for raytracing (if needed) and collect results
int hitpointCount = 0;
rgl_vec3f results[1] = {0};
RGL_CHECK(rgl_lidar_get_output_size(lidar, &hitpointCount));
RGL_CHECK(rgl_lidar_get_output_data(lidar, RGL_FORMAT_XYZ, results));
// you can run the graph using any one of its nodes
EXPECT_RGL_SUCCESS(rgl_graph_run(raytrace));

printf("Got %d hitpoint(s)\n", hitpointCount);
for (int i = 0; i < hitpointCount; ++i) {
printf("- (%.2f, %.2f, %.2f)\n", results[i].value[0], results[i].value[1], results[i].value[2]);
// Wait for the Graph to run (if needed) and collect results
int32_t hitpoint_count = 0;
int32_t size;
rgl_vec3f results[1] = { 0 };
EXPECT_RGL_SUCCESS(rgl_graph_get_result_size(raytrace, RGL_FIELD_XYZ_F32, &hitpoint_count, &size));
EXPECT_RGL_SUCCESS(rgl_graph_get_result_data(raytrace, RGL_FIELD_XYZ_F32, &results));

printf("Got %d hitpoint(s)\n", hitpoint_count);
for (int i = 0; i < hitpoint_count; ++i) {
printf("- (%.2f, %.2f, %.2f)\n", results[i].value[0], results[i].value[1], results[i].value[2]);
}
```
### API documentation
More details can be found [here](../include/rgl/api/experimental.h).
### API stability
Currently, the API is experimental - no ground-breaking changes are planned, however minor breaking changes may occur.
API stabilization is planned for the second half of 2022.
More details can be found [here](../include/rgl/api/core.h).
2 changes: 1 addition & 1 deletion include/Lidar.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
#include <scene/Scene.hpp>
#include <gpu/Optix.hpp>

#include <rgl/api/experimental.h>
#include <rgl/api/core.h>

// Currently there is no explicit (documented) model of API / GPU synchronization
// Getting correct results is dependent on calling API calls in right order
Expand Down
2 changes: 1 addition & 1 deletion include/Logger.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#include <spdlog/sinks/stdout_color_sinks.h>
#include <spdlog/sinks/basic_file_sink.h>

#include <rgl/api/experimental.h>
#include <rgl/api/core.h>


template <typename... Args>
Expand Down
2 changes: 1 addition & 1 deletion include/RGLFields.hpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#pragma once

#include <set>
#include <rgl/api/experimental.h>
#include <rgl/api/core.h>
#include <VArray.hpp>

/*
Expand Down
2 changes: 1 addition & 1 deletion include/VArray.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
#include <macros/cuda.hpp>

#include <Logger.hpp>
#include <rgl/api/experimental.h>
#include <rgl/api/core.h>
#include <math/Vector.hpp>
#include <typingUtils.hpp>

Expand Down
2 changes: 1 addition & 1 deletion include/gpu/nodeKernels.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#include <unordered_map>
#include <memory>

#include <rgl/api/experimental.h>
#include <rgl/api/core.h>
#include <gpu/GPUFieldDesc.hpp>
#include <math/Mat3x4f.hpp>
#include <RGLFields.hpp>
Expand Down
2 changes: 1 addition & 1 deletion include/graph/Interfaces.hpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#pragma once

#include <rgl/api/experimental.h>
#include <rgl/api/core.h>
#include <math/Mat3x4f.hpp>
#include <VArray.hpp>
#include <VArrayProxy.hpp>
Expand Down
2 changes: 1 addition & 1 deletion include/graph/Node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <vector>

#include <VArray.hpp>
#include <rgl/api/experimental.h>
#include <rgl/api/core.h>
#include <APIObject.hpp>
#include <RGLFields.hpp>

Expand Down
2 changes: 1 addition & 1 deletion include/math/Mat3x4f.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
#endif

#include <math/floatComparison.hpp>
#include <rgl/api/experimental.h>
#include <rgl/api/core.h>
#include <math/Vector.hpp>

#ifndef __CUDACC__
Expand Down
2 changes: 1 addition & 1 deletion include/repr.hpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#pragma once

#include <rgl/api/experimental.h>
#include <rgl/api/core.h>
#include <spdlog/fmt/fmt.h>

template<>
Expand Down
Loading

0 comments on commit b30eb9a

Please sign in to comment.