Skip to content

Commit

Permalink
feat(autoware_probabilistic_occupancy_grid_map): cuda accelerated imp…
Browse files Browse the repository at this point in the history
…lementation (#9542)

* feat: implemented a cuda accelerated ogm

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* chore: fixed cspells

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* chore: unused header and variable names

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* chore: cspell fixes

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* chore: cppcheck fix attempt

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* fix: attempting to fix ci/cd regarding the cuda library

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* chore: fixed the order of the cuda check in the cmakelist

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* fix: removed cuda as a required dep for cpu only builds

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* fix: missing cuda linking (?)

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* feat: fixed single mode, added streams, and added the restrict keyword

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* chore: replaced a potential indetermination using an epsilon

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* Update perception/autoware_probabilistic_occupancy_grid_map/lib/updater/log_odds_bayes_filter_updater_kernel.cu

Co-authored-by: Yoshi Ri <[email protected]>

* Update perception/autoware_probabilistic_occupancy_grid_map/lib/updater/log_odds_bayes_filter_updater_kernel.cu

Co-authored-by: Yoshi Ri <[email protected]>

* style(pre-commit): autofix

* chore: added bound checkings in the update origin kernel

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* chore: disabled tests since universe does not support cuda in ci/cd

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* chore: added me as a maintainer

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* fix: missedn the end in the cmake

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* chore: moved the boudnary checks to only the cuda version since the cpu version uses the upstream logic

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

---------

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>
Co-authored-by: Yoshi Ri <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
3 people authored Jan 28, 2025
1 parent 874dbdd commit 165be35
Show file tree
Hide file tree
Showing 33 changed files with 2,288 additions and 901 deletions.
87 changes: 62 additions & 25 deletions perception/autoware_probabilistic_occupancy_grid_map/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,34 +4,62 @@ project(autoware_probabilistic_occupancy_grid_map)
find_package(autoware_cmake REQUIRED)
autoware_package()

find_package(CUDA)
find_package(eigen3_cmake_module REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(PCL REQUIRED)

if(NOT ${CUDA_FOUND})
message(WARNING "cuda was not found, so the autoware_probabilistic_occupancy_grid_map package will not be built.")
return()
endif()

include_directories(
include
SYSTEM
${CUDA_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIR}
${grid_map_ros_INCLUDE_DIRS}
)

# cSpell: ignore expt
list(APPEND CUDA_NVCC_FLAGS --expt-relaxed-constexpr -diag-suppress 20012 --compiler-options -fPIC)
set(CUDA_SEPARABLE_COMPILATION ON)
set(CMAKE_POSITION_INDEPENDENT_CODE ON)

cuda_add_library(${PROJECT_NAME}_cuda SHARED
lib/costmap_2d/occupancy_grid_map_fixed_kernel.cu
lib/costmap_2d/occupancy_grid_map_projective_kernel.cu
lib/updater/binary_bayes_filter_updater_kernel.cu
lib/updater/log_odds_bayes_filter_updater_kernel.cu
lib/utils/utils_kernel.cu
)

target_link_libraries(${PROJECT_NAME}_cuda
${CUDA_LIBRARIES}
)

ament_auto_add_library(${PROJECT_NAME}_common SHARED
lib/costmap_2d/occupancy_grid_map_base.cpp
lib/updater/binary_bayes_filter_updater.cpp
lib/utils/utils.cpp
)
target_link_libraries(${PROJECT_NAME}_common
${PCL_LIBRARIES}
${PROJECT_NAME}_cuda
)

# PointcloudBasedOccupancyGridMap
ament_auto_add_library(pointcloud_based_occupancy_grid_map SHARED
src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp
lib/costmap_2d/occupancy_grid_map_base.cpp
lib/costmap_2d/occupancy_grid_map_fixed.cpp
lib/costmap_2d/occupancy_grid_map_projective.cpp
)

target_link_libraries(pointcloud_based_occupancy_grid_map
${PCL_LIBRARIES}
${PROJECT_NAME}_common
${PROJECT_NAME}_cuda
)

rclcpp_components_register_node(pointcloud_based_occupancy_grid_map
Expand Down Expand Up @@ -73,34 +101,43 @@ rclcpp_components_register_node(synchronized_grid_map_fusion
EXECUTABLE synchronized_grid_map_fusion_node
)

install(
TARGETS ${PROJECT_NAME}_cuda
DESTINATION lib
)

ament_auto_package(
INSTALL_TO_SHARE
launch
config
)

# test
if(BUILD_TESTING)
# launch_testing
find_package(launch_testing_ament_cmake REQUIRED)
add_launch_test(test/test_pointcloud_based_method.py)
add_launch_test(test/test_synchronized_grid_map_fusion_node.py)

# gtest
ament_add_gtest(test_utils
test/test_utils.cpp
)
ament_add_gtest(costmap_unit_tests
test/cost_value_test.cpp
)
ament_add_gtest(fusion_policy_unit_tests
test/fusion_policy_test.cpp
lib/fusion_policy/fusion_policy.cpp
)
target_link_libraries(test_utils
${PCL_LIBRARIES}
${PROJECT_NAME}_common
)
target_include_directories(costmap_unit_tests PRIVATE "include")
target_include_directories(fusion_policy_unit_tests PRIVATE "include")
endif()
# Temporary disabled, tracked by:
# https://github.com/autowarefoundation/autoware.universe/issues/7724
#if(BUILD_TESTING)
# # launch_testing
# find_package(launch_testing_ament_cmake REQUIRED)
# add_launch_test(test/test_pointcloud_based_method.py)
# add_launch_test(test/test_synchronized_grid_map_fusion_node.py)
#
# # gtest
# ament_add_gtest(test_utils
# test/test_utils.cpp
# )
# ament_add_gtest(costmap_unit_tests
# test/cost_value_test.cpp
# )
# ament_add_gtest(fusion_policy_unit_tests
# test/fusion_policy_test.cpp
# lib/fusion_policy/fusion_policy.cpp
# )
# target_link_libraries(test_utils
# ${CUDA_LIBRARIES}
# ${PCL_LIBRARIES}
# ${PROJECT_NAME}_common
# ${PROJECT_NAME}_cuda
# )
# target_include_directories(costmap_unit_tests PRIVATE "include")
# target_include_directories(fusion_policy_unit_tests PRIVATE "include")
#endif()
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,8 @@
#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_HPP_
#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_HPP_

#include <nav2_costmap_2d/costmap_2d.hpp>
#include "autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_base.hpp"

#include <rclcpp/rclcpp.hpp>

#include <nav_msgs/msg/occupancy_grid.hpp>
Expand All @@ -66,7 +67,7 @@ namespace costmap_2d
using geometry_msgs::msg::Pose;
using sensor_msgs::msg::PointCloud2;

class OccupancyGridMap : public nav2_costmap_2d::Costmap2D
class OccupancyGridMap : public OccupancyGridMapInterface
{
public:
OccupancyGridMap(
Expand All @@ -78,15 +79,15 @@ class OccupancyGridMap : public nav2_costmap_2d::Costmap2D

void updateOccupiedCells(const PointCloud2 & pointcloud);

void updateOrigin(double new_origin_x, double new_origin_y) override;

private:
void raytraceFreespace(const PointCloud2 & pointcloud, const Pose & robot_pose);

void updateCellsByPointCloud(const PointCloud2 & pointcloud, const unsigned char cost);

bool worldToMap(double wx, double wy, unsigned int & mx, unsigned int & my) const;

void initRosParam([[maybe_unused]] rclcpp::Node & node) override {}

rclcpp::Logger logger_{rclcpp::get_logger("laserscan_based_occupancy_grid_map")};
rclcpp::Clock clock_{RCL_ROS_TIME};
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,9 @@
#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_BASE_HPP_
#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_BASE_HPP_

#include "autoware/probabilistic_occupancy_grid_map/utils/cuda_pointcloud.hpp"

#include <autoware/cuda_utils/cuda_unique_ptr.hpp>
#include <autoware/universe_utils/math/unit_conversion.hpp>
#include <nav2_costmap_2d/costmap_2d.hpp>
#include <rclcpp/rclcpp.hpp>
Expand All @@ -72,18 +75,17 @@ class OccupancyGridMapInterface : public nav2_costmap_2d::Costmap2D
{
public:
OccupancyGridMapInterface(
const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution);
const bool use_cuda, const unsigned int cells_size_x, const unsigned int cells_size_y,
const float resolution);

virtual void updateWithPointCloud(
const PointCloud2 & raw_pointcloud, const PointCloud2 & obstacle_pointcloud,
const Pose & robot_pose, const Pose & scan_origin) = 0;
[[maybe_unused]] const CudaPointCloud2 & raw_pointcloud,
[[maybe_unused]] const CudaPointCloud2 & obstacle_pointcloud,
[[maybe_unused]] const Pose & robot_pose, [[maybe_unused]] const Pose & scan_origin) {};

void updateOrigin(double new_origin_x, double new_origin_y) override;
void raytrace(
const double source_x, const double source_y, const double target_x, const double target_y,
const unsigned char cost);
void setCellValue(const double wx, const double wy, const unsigned char cost);
using nav2_costmap_2d::Costmap2D::resetMaps;

void resetMaps() override;

virtual void initRosParam(rclcpp::Node & node) = 0;

Expand All @@ -92,47 +94,34 @@ class OccupancyGridMapInterface : public nav2_costmap_2d::Costmap2D
double min_height_;
double max_height_;

void setFieldOffsets(const PointCloud2 & input_raw, const PointCloud2 & input_obstacle);

int x_offset_raw_;
int y_offset_raw_;
int z_offset_raw_;
int x_offset_obstacle_;
int y_offset_obstacle_;
int z_offset_obstacle_;
bool offset_initialized_;

const double min_angle_ = autoware::universe_utils::deg2rad(-180.0);
const double max_angle_ = autoware::universe_utils::deg2rad(180.0);
const double angle_increment_inv_ = 1.0 / autoware::universe_utils::deg2rad(0.1);

Eigen::Matrix4f mat_map_, mat_scan_;

bool isPointValid(const Eigen::Vector4f & pt) const
{
// Apply height filter and exclude invalid points
return min_height_ < pt[2] && pt[2] < max_height_ && std::isfinite(pt[0]) &&
std::isfinite(pt[1]) && std::isfinite(pt[2]);
}
// Transform pt to (pt_map, pt_scan), then calculate angle_bin_index and range
void transformPointAndCalculate(
const Eigen::Vector4f & pt, Eigen::Vector4f & pt_map, int & angle_bin_index,
double & range) const
{
pt_map = mat_map_ * pt;
Eigen::Vector4f pt_scan(mat_scan_ * pt_map);
const double angle = atan2(pt_scan[1], pt_scan[0]);
angle_bin_index = (angle - min_angle_) * angle_increment_inv_;
range = std::sqrt(pt_scan[1] * pt_scan[1] + pt_scan[0] * pt_scan[0]);
}

private:
bool worldToMap(double wx, double wy, unsigned int & mx, unsigned int & my) const;
bool isCudaEnabled() const;

const autoware::cuda_utils::CudaUniquePtr<std::uint8_t[]> & getDeviceCostmap() const;

void copyDeviceCostmapToHost() const;

protected:
rclcpp::Logger logger_{rclcpp::get_logger("pointcloud_based_occupancy_grid_map")};
rclcpp::Clock clock_{RCL_ROS_TIME};

double resolution_inv_;

cudaStream_t stream_;

bool use_cuda_;
autoware::cuda_utils::CudaUniquePtr<std::uint8_t[]> device_costmap_;
autoware::cuda_utils::CudaUniquePtr<std::uint8_t[]> device_costmap_aux_;

autoware::cuda_utils::CudaUniquePtr<Eigen::Matrix3f> device_rotation_map_;
autoware::cuda_utils::CudaUniquePtr<Eigen::Vector3f> device_translation_map_;
autoware::cuda_utils::CudaUniquePtr<Eigen::Matrix3f> device_rotation_scan_;
autoware::cuda_utils::CudaUniquePtr<Eigen::Vector3f> device_translation_scan_;
};

} // namespace costmap_2d
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_FIXED_HPP_

#include "autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_base.hpp"
#include "autoware/probabilistic_occupancy_grid_map/utils/cuda_pointcloud.hpp"

namespace autoware::occupancy_grid_map
{
Expand All @@ -28,21 +29,20 @@ class OccupancyGridMapFixedBlindSpot : public OccupancyGridMapInterface
{
public:
OccupancyGridMapFixedBlindSpot(
const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution);
const bool use_cuda, const unsigned int cells_size_x, const unsigned int cells_size_y,
const float resolution);

void updateWithPointCloud(
const PointCloud2 & raw_pointcloud, const PointCloud2 & obstacle_pointcloud,
const CudaPointCloud2 & raw_pointcloud, const CudaPointCloud2 & obstacle_pointcloud,
const Pose & robot_pose, const Pose & scan_origin) override;

using OccupancyGridMapInterface::raytrace;
using OccupancyGridMapInterface::setCellValue;
using OccupancyGridMapInterface::setFieldOffsets;
using OccupancyGridMapInterface::updateOrigin;

void initRosParam(rclcpp::Node & node) override;

private:
protected:
double distance_margin_;

autoware::cuda_utils::CudaUniquePtr<std::uint64_t[]> raw_points_tensor_;
autoware::cuda_utils::CudaUniquePtr<std::uint64_t[]> obstacle_points_tensor_;
};

} // namespace costmap_2d
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
// Copyright 2021 Tier IV, Inc.
//
// 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.

#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_FIXED_KERNEL_HPP_
#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_FIXED_KERNEL_HPP_

#include "autoware/probabilistic_occupancy_grid_map/utils/utils_kernel.hpp"

#include <Eigen/Core>

#include <cstdint>

namespace autoware::occupancy_grid_map
{
namespace costmap_2d::map_fixed
{

void prepareTensorLaunch(
const float * input_pointcloud, const std::size_t num_points, const std::size_t points_step,
const std::size_t angle_bins, const std::size_t range_bins, const float min_height,
const float max_height, const float min_angle, const float angle_increment_inv,
const float range_resolution_inv, const Eigen::Matrix3f * rotation_map,
const Eigen::Vector3f * translation_map, const Eigen::Matrix3f * rotation_scan,
const Eigen::Vector3f * translation_scan, std::uint64_t * points_tensor, cudaStream_t stream);

void fillEmptySpaceLaunch(
const std::uint64_t * points_tensor, const std::size_t angle_bins, const std::size_t range_bins,
const float map_resolution_inv, const float scan_origin_x, const float scan_origin_y,
const float map_origin_x, const float map_origin_y, const int num_cells_x, const int num_cells_y,
std::uint8_t empty_value, std::uint8_t * costmap_tensor, cudaStream_t stream);

void fillUnknownSpaceLaunch(
const std::uint64_t * raw_points_tensor, const std::uint64_t * obstacle_points_tensor,
const float distance_margin, const std::size_t angle_bins, const std::size_t range_bins,
const float map_resolution_inv, const float scan_origin_x, const float scan_origin_y,
const float map_origin_x, const float map_origin_y, const int num_cells_x, const int num_cells_y,
std::uint8_t free_space_value, std::uint8_t no_information_value, std::uint8_t * costmap_tensor,
cudaStream_t stream);

void fillObstaclesLaunch(
const std::uint64_t * points_tensor, const float distance_margin, const std::size_t angle_bins,
const std::size_t range_bins, const float map_resolution_inv, const float map_origin_x,
const float map_origin_y, const int num_cells_x, const int num_cells_y,
std::uint8_t obstacle_value, std::uint8_t * costmap_tensor, cudaStream_t stream);

} // namespace costmap_2d::map_fixed
} // namespace autoware::occupancy_grid_map

#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_FIXED_KERNEL_HPP_
Loading

0 comments on commit 165be35

Please sign in to comment.