Skip to content

Commit

Permalink
Polish before 0.11.0 release (#56)
Browse files Browse the repository at this point in the history
* Polish before 0.11.0 release

* Update src/api/api.cpp

Co-authored-by: Piotr Rybicki <[email protected]>
  • Loading branch information
msz-rai and prybicki committed Nov 22, 2022
1 parent 2d4055b commit 06b6e02
Show file tree
Hide file tree
Showing 23 changed files with 25 additions and 139 deletions.
3 changes: 1 addition & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,6 @@ And more:
- Converting to custom binary output
- Downsampling
- Writing to PCD file
- Optional Gaussian noise (see [documentation](docs/GaussianNoise.md))

## Usage

Expand Down Expand Up @@ -68,7 +67,7 @@ Build instructions:

## Building on Windows

1. Install [CUDA Toolkit](https://developer.nvidia.com/cuda-downloads) 11.2+.
1. Install [CUDA Toolkit](https://developer.nvidia.com/cuda-downloads) 11.4.4+.
2. Download [NVidia OptiX](https://developer.nvidia.com/designworks/optix/downloads/legacy) 7.2.
- use the default location or set environment variable `OptiX_INSTALL_DIR`
3. Install [PCL](https://pointclouds.org/) 1.12:
Expand Down
116 changes: 0 additions & 116 deletions docs/GaussianNoise.md

This file was deleted.

31 changes: 16 additions & 15 deletions docs/Usage.md
Original file line number Diff line number Diff line change
Expand Up @@ -72,44 +72,45 @@ Full source code can be found [here](../test/src/apiReadmeExample.cpp)

```c
// Create a mesh
rgl_mesh_t cube_mesh = rgl_mesh_create(/* arguments skipped for the sake of brevity */);
rgl_mesh_t cube_mesh = nullptr;
rgl_mesh_create(&cube_mesh, /* remaining arguments skipped for the sake of brevity */);

// Put an entity on the default scene
rgl_entity_t cube_entity = 0;
EXPECT_RGL_SUCCESS(rgl_entity_create(&cube_entity, NULL, cube_mesh));
rgl_entity_t cube_entity = nullptr;
rgl_entity_create(&cube_entity, nullptr, 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 } }
{ 0, 0, 1, 5 }}
};
EXPECT_RGL_SUCCESS(rgl_entity_set_pose(cube_entity, &entity_tf));
rgl_entity_set_pose(cube_entity, &entity_tf);

// 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 },}
{ 0, 0, 1, 0 }}
};

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));
rgl_node_rays_from_mat3x4f(&useRays, &ray_tf, 1);
rgl_node_raytrace(&raytrace, nullptr, 1000);
rgl_graph_node_add_child(useRays, raytrace);

// you can run the graph using any one of its nodes
EXPECT_RGL_SUCCESS(rgl_graph_run(raytrace));
rgl_graph_run(raytrace);

// 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));
int32_t hitpoint_count;
int32_t point_size;
rgl_vec3f results[1];
rgl_graph_get_result_size(raytrace, RGL_FIELD_XYZ_F32, &hitpoint_count, &point_size);
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) {
Expand Down
Binary file removed docs/image/Angular_hitpoint_1.png
Binary file not shown.
Binary file removed docs/image/Angular_hitpoint_2.png
Binary file not shown.
Binary file removed docs/image/Angular_hitpoint_3.png
Binary file not shown.
Binary file removed docs/image/Angular_hitpoint_4.png
Binary file not shown.
Binary file removed docs/image/Angular_ray_1.png
Binary file not shown.
Binary file removed docs/image/Angular_ray_2.png
Binary file not shown.
Binary file removed docs/image/Angular_ray_3.png
Binary file not shown.
Binary file removed docs/image/Angular_ray_4.png
Binary file not shown.
Binary file removed docs/image/Distance_1.png
Binary file not shown.
Binary file removed docs/image/Distance_2.png
Binary file not shown.
Binary file removed docs/image/Distance_3.png
Binary file not shown.
Binary file removed docs/image/Distance_4.png
Binary file not shown.
Binary file removed docs/image/distance_noise_d.gif
Binary file not shown.
Binary file removed docs/image/distance_noise_sigma_base.gif
Binary file not shown.
Binary file removed docs/image/distance_noise_sigma_distance.gif
Binary file not shown.
Binary file removed docs/image/distance_noise_sigma_slope.gif
Binary file not shown.
Binary file removed docs/image/distance_stdev.gif
Binary file not shown.
Binary file removed docs/image/gaussian_noise.gif
Binary file not shown.
1 change: 1 addition & 0 deletions src/api/api.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -154,6 +154,7 @@ rgl_get_version_info(int32_t* out_major, int32_t* out_minor, int32_t* out_patch)
// 0.10.0: entities can now share meshes
// 0.10.1: API const correctness, added INVALID_OBJECT error, minor internal changes
// 0.10.2: Fixed Lidar::getResults writing too many bytes
// 0.11.0: implement Graph API (Gaussian noise temporarily removed)
auto status = rglSafeCall([&]() {
RGL_DEBUG("rgl_get_version_info(out_major={}, out_minor={}, out_patch={})", (void*) out_major,
(void*) out_minor, (void*) out_patch);
Expand Down
13 changes: 7 additions & 6 deletions test/src/apiReadmeExample.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,11 +8,12 @@ TEST(EndToEnd, ReadmeExample)
EXPECT_RGL_SUCCESS(rgl_get_version_info(&major, &minor, &patch));
printf("RGL version: %d.%d.%d\n", major, minor, patch);

// Create a mesh by using helper function from test/include/scenes.hpp
rgl_mesh_t cube_mesh = makeCubeMesh();

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

// Set position of the cube entity to (0, 0, 5)
rgl_mat3x4f entity_tf = {
Expand Down Expand Up @@ -42,10 +43,10 @@ TEST(EndToEnd, ReadmeExample)
EXPECT_RGL_SUCCESS(rgl_graph_run(raytrace));

// 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));
int32_t hitpoint_count;
int32_t point_size;
rgl_vec3f results[1];
EXPECT_RGL_SUCCESS(rgl_graph_get_result_size(raytrace, RGL_FIELD_XYZ_F32, &hitpoint_count, &point_size));
EXPECT_RGL_SUCCESS(rgl_graph_get_result_data(raytrace, RGL_FIELD_XYZ_F32, &results));

printf("Got %d hitpoint(s)\n", hitpoint_count);
Expand Down

0 comments on commit 06b6e02

Please sign in to comment.