Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

revert: "feat(lidar_transfusion): update TransFusion-L model" #1478

Merged
merged 1 commit into from
Aug 20, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
52 changes: 0 additions & 52 deletions perception/lidar_transfusion/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -137,58 +137,6 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()

find_package(ament_cmake_gtest REQUIRED)
ament_auto_add_gtest(test_detection_class_remapper
test/test_detection_class_remapper.cpp
)
ament_auto_add_gtest(test_ros_utils
test/test_ros_utils.cpp
)
ament_auto_add_gtest(test_nms
test/test_nms.cpp
)

# Temporary disabled, tracked by:
# https://github.com/autowarefoundation/autoware.universe/issues/7724
# ament_auto_add_gtest(test_voxel_generator
# test/test_voxel_generator.cpp
# )

# # preprocess kernel test
# add_executable(test_preprocess_kernel
# test/test_preprocess_kernel.cpp
# )
# target_include_directories(test_preprocess_kernel PUBLIC
# ${test_preprocess_kernel_SOURCE_DIR}
# )
# target_link_libraries(test_preprocess_kernel
# transfusion_cuda_lib
# gtest
# gtest_main
# )
# ament_add_test(test_preprocess_kernel
# GENERATE_RESULT_FOR_RETURN_CODE_ZERO
# COMMAND "$<TARGET_FILE:test_preprocess_kernel>"
# )

# # postprocess kernel test
# add_executable(test_postprocess_kernel
# test/test_postprocess_kernel.cpp
# )
# target_include_directories(test_postprocess_kernel PUBLIC
# ${test_postprocess_kernel_SOURCE_DIR}
# )
# target_link_libraries(test_postprocess_kernel
# transfusion_cuda_lib
# gtest
# gtest_main
# )
# ament_add_test(test_postprocess_kernel
# GENERATE_RESULT_FOR_RETURN_CODE_ZERO
# COMMAND "$<TARGET_FILE:test_postprocess_kernel>"
# )

endif()

ament_auto_package(
Expand Down
22 changes: 2 additions & 20 deletions perception/lidar_transfusion/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -59,31 +59,13 @@ ros2 launch lidar_transfusion lidar_transfusion.launch.xml log_level:=debug

## Assumptions / Known limits

This library operates on raw cloud data (bytes). It is assumed that the input pointcloud message has following format:

```python
[
sensor_msgs.msg.PointField(name='x', offset=0, datatype=7, count=1),
sensor_msgs.msg.PointField(name='y', offset=4, datatype=7, count=1),
sensor_msgs.msg.PointField(name='z', offset=8, datatype=7, count=1),
sensor_msgs.msg.PointField(name='intensity', offset=12, datatype=2, count=1)
]
```

This input may consist of other fields as well - shown format is required minimum.
For debug purposes, you can validate your pointcloud topic using simple command:

```bash
ros2 topic echo <input_topic> --field fields
```

## Trained Models

You can download the onnx format of trained models by clicking on the links below.

- TransFusion: [transfusion.onnx](https://awf.ml.dev.web.auto/perception/models/transfusion/t4xx1_90m/v2/transfusion.onnx)
- TransFusion: [transfusion.onnx](https://awf.ml.dev.web.auto/perception/models/transfusion/v1/transfusion.onnx)

The model was trained in TIER IV's internal database (~11k lidar frames) for 50 epochs.
The model was trained in TIER IV's internal database (~11k lidar frames) for 20 epochs.

### Changelog

Expand Down
7 changes: 3 additions & 4 deletions perception/lidar_transfusion/config/transfusion.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,8 @@
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
trt_precision: fp16
voxels_num: [5000, 30000, 60000] # [min, opt, max]
point_cloud_range: [-92.16, -92.16, -3.0, 92.16, 92.16, 7.0] # [x_min, y_min, z_min, x_max, y_max, z_max]
voxel_size: [0.24, 0.24, 10.0] # [x, y, z]
num_proposals: 500
point_cloud_range: [-76.8, -76.8, -3.0, 76.8, 76.8, 5.0] # [x_min, y_min, z_min, x_max, y_max, z_max]
voxel_size: [0.3, 0.3, 8.0] # [x, y, z]
onnx_path: "$(var model_path)/transfusion.onnx"
engine_path: "$(var model_path)/transfusion.engine"
# pre-process params
Expand All @@ -18,4 +17,4 @@
iou_nms_search_distance_2d: 10.0
iou_nms_threshold: 0.1
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] # refers to the class_names
score_threshold: 0.1
score_threshold: 0.2
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class DensificationParam

struct PointCloudWithTransform
{
cuda::unique_ptr<uint8_t[]> data_d{nullptr};
cuda::unique_ptr<float[]> points_d{nullptr};
std_msgs::msg::Header header;
size_t num_points{0};
Eigen::Affine3f affine_past2world;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,12 @@ class PreprocessCuda
unsigned int * mask, float * voxels, unsigned int * pillar_num, float * voxel_features,
unsigned int * voxel_num, unsigned int * voxel_idxs);

// cudaError_t generateVoxelsInput_launch(
// uint8_t * cloud_data, CloudInfo & cloud_info, unsigned int points_agg, unsigned int
// points_size, float time_lag, float * affine_transform, float * points);

cudaError_t generateSweepPoints_launch(
const uint8_t * input_data, size_t points_size, int input_point_step, float time_lag,
const float * input_points, size_t points_size, int input_point_step, float time_lag,
const float * transform, float * output_points);

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,17 +18,15 @@
#include "lidar_transfusion/cuda_utils.hpp"
#include "lidar_transfusion/preprocess/pointcloud_densification.hpp"
#include "lidar_transfusion/preprocess/preprocess_kernel.hpp"
#include "lidar_transfusion/ros_utils.hpp"
#include "lidar_transfusion/transfusion_config.hpp"
#include "lidar_transfusion/utils.hpp"

#ifdef ROS_DISTRO_GALACTIC
#include <tf2_eigen/tf2_eigen.h>
#else
#include <tf2_eigen/tf2_eigen.hpp>
#endif

#include <autoware_point_types/types.hpp>

#include <sensor_msgs/msg/point_cloud2.hpp>

#include <memory>
Expand All @@ -38,8 +36,8 @@

namespace lidar_transfusion
{
constexpr size_t AFF_MAT_SIZE = 16; // 4x4 matrix
constexpr size_t MAX_CLOUD_STEP_SIZE = sizeof(autoware_point_types::PointXYZIRCAEDT);
constexpr size_t AFF_MAT_SIZE = 16; // 4x4 matrix
constexpr size_t MAX_CLOUD_STEP_SIZE = 35; // PointXYZIRCADT

class VoxelGenerator
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,84 +17,16 @@

#include "lidar_transfusion/utils.hpp"

#include <autoware_point_types/types.hpp>

#include <autoware_perception_msgs/msg/detected_object_kinematics.hpp>
#include <autoware_perception_msgs/msg/detected_objects.hpp>
#include <autoware_perception_msgs/msg/object_classification.hpp>
#include <autoware_perception_msgs/msg/shape.hpp>
#include <sensor_msgs/msg/point_field.hpp>

#include <cstdint>
#include <string>
#include <vector>

#define CHECK_OFFSET(offset, structure, field) \
static_assert( \
offsetof(structure, field) == offset, \
"Offset of " #field " in " #structure " does not match expected offset.")
#define CHECK_TYPE(type, structure, field) \
static_assert( \
std::is_same<decltype(structure::field), type>::value, \
"Type of " #field " in " #structure " does not match expected type.")
#define CHECK_FIELD(offset, type, structure, field) \
CHECK_OFFSET(offset, structure, field); \
CHECK_TYPE(type, structure, field)

namespace lidar_transfusion
{
using sensor_msgs::msg::PointField;

CHECK_FIELD(0, float, autoware_point_types::PointXYZIRCAEDT, x);
CHECK_FIELD(4, float, autoware_point_types::PointXYZIRCAEDT, y);
CHECK_FIELD(8, float, autoware_point_types::PointXYZIRCAEDT, z);
CHECK_FIELD(12, uint8_t, autoware_point_types::PointXYZIRCAEDT, intensity);

struct CloudInfo
{
uint32_t x_offset{0};
uint32_t y_offset{sizeof(float)};
uint32_t z_offset{sizeof(float) * 2};
uint32_t intensity_offset{sizeof(float) * 3};
uint8_t x_datatype{PointField::FLOAT32};
uint8_t y_datatype{PointField::FLOAT32};
uint8_t z_datatype{PointField::FLOAT32};
uint8_t intensity_datatype{PointField::UINT8};
uint8_t x_count{1};
uint8_t y_count{1};
uint8_t z_count{1};
uint8_t intensity_count{1};
uint32_t point_step{sizeof(autoware_point_types::PointXYZIRCAEDT)};
bool is_bigendian{false};

bool operator!=(const CloudInfo & rhs) const
{
return x_offset != rhs.x_offset || y_offset != rhs.y_offset || z_offset != rhs.z_offset ||
intensity_offset != rhs.intensity_offset || x_datatype != rhs.x_datatype ||
y_datatype != rhs.y_datatype || z_datatype != rhs.z_datatype ||
intensity_datatype != rhs.intensity_datatype || x_count != rhs.x_count ||
y_count != rhs.y_count || z_count != rhs.z_count ||
intensity_count != rhs.intensity_count || is_bigendian != rhs.is_bigendian;
}

friend std::ostream & operator<<(std::ostream & os, const CloudInfo & info)
{
os << "x_offset: " << static_cast<int>(info.x_offset) << std::endl;
os << "y_offset: " << static_cast<int>(info.y_offset) << std::endl;
os << "z_offset: " << static_cast<int>(info.z_offset) << std::endl;
os << "intensity_offset: " << static_cast<int>(info.intensity_offset) << std::endl;
os << "x_datatype: " << static_cast<int>(info.x_datatype) << std::endl;
os << "y_datatype: " << static_cast<int>(info.y_datatype) << std::endl;
os << "z_datatype: " << static_cast<int>(info.z_datatype) << std::endl;
os << "intensity_datatype: " << static_cast<int>(info.intensity_datatype) << std::endl;
os << "x_count: " << static_cast<int>(info.x_count) << std::endl;
os << "y_count: " << static_cast<int>(info.y_count) << std::endl;
os << "z_count: " << static_cast<int>(info.z_count) << std::endl;
os << "intensity_count: " << static_cast<int>(info.intensity_count) << std::endl;
os << "is_bigendian: " << static_cast<int>(info.is_bigendian) << std::endl;
return os;
}
};

void box3DToDetectedObject(
const Box3D & box3d, const std::vector<std::string> & class_names,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,9 +26,8 @@ class TransfusionConfig
public:
TransfusionConfig(
const std::vector<int64_t> & voxels_num, const std::vector<double> & point_cloud_range,
const std::vector<double> & voxel_size, const int num_proposals,
const float circle_nms_dist_threshold, const std::vector<double> & yaw_norm_thresholds,
const float score_threshold)
const std::vector<double> & voxel_size, const float circle_nms_dist_threshold,
const std::vector<double> & yaw_norm_thresholds, const float score_threshold)
{
if (voxels_num.size() == 3) {
max_voxels_ = voxels_num[2];
Expand Down Expand Up @@ -62,9 +61,6 @@ class TransfusionConfig
voxel_y_size_ = static_cast<float>(voxel_size[1]);
voxel_z_size_ = static_cast<float>(voxel_size[2]);
}
if (num_proposals > 0) {
num_proposals_ = num_proposals;
}
if (score_threshold > 0.0) {
score_threshold_ = score_threshold;
}
Expand All @@ -80,9 +76,6 @@ class TransfusionConfig
grid_x_size_ = static_cast<std::size_t>((max_x_range_ - min_x_range_) / voxel_x_size_);
grid_y_size_ = static_cast<std::size_t>((max_y_range_ - min_y_range_) / voxel_y_size_);
grid_z_size_ = static_cast<std::size_t>((max_z_range_ - min_z_range_) / voxel_z_size_);

feature_x_size_ = grid_x_size_ / out_size_factor_;
feature_y_size_ = grid_y_size_ / out_size_factor_;
}

///// INPUT PARAMETERS /////
Expand Down Expand Up @@ -114,7 +107,7 @@ class TransfusionConfig
const std::size_t out_size_factor_{4};
const std::size_t max_num_points_per_pillar_{points_per_voxel_};
const std::size_t num_point_values_{4};
std::size_t num_proposals_{200};
const std::size_t num_proposals_{200};
// the number of feature maps for pillar scatter
const std::size_t num_feature_scatter_{pillar_feature_size_};
// the score threshold for classification
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,52 @@ struct Box3D
float yaw;
};

struct CloudInfo
{
uint32_t x_offset;
uint32_t y_offset;
uint32_t z_offset;
uint32_t intensity_offset;
uint8_t x_datatype;
uint8_t y_datatype;
uint8_t z_datatype;
uint8_t intensity_datatype;
uint8_t x_count;
uint8_t y_count;
uint8_t z_count;
uint8_t intensity_count;
uint32_t point_step;
bool is_bigendian;

CloudInfo()
: x_offset(0),
y_offset(4),
z_offset(8),
intensity_offset(12),
x_datatype(7),
y_datatype(7),
z_datatype(7),
intensity_datatype(7),
x_count(1),
y_count(1),
z_count(1),
intensity_count(1),
point_step(16),
is_bigendian(false)
{
}

bool operator!=(const CloudInfo & rhs) const
{
return x_offset != rhs.x_offset || y_offset != rhs.y_offset || z_offset != rhs.z_offset ||
intensity_offset != rhs.intensity_offset || x_datatype != rhs.x_datatype ||
y_datatype != rhs.y_datatype || z_datatype != rhs.z_datatype ||
intensity_datatype != rhs.intensity_datatype || x_count != rhs.x_count ||
y_count != rhs.y_count || z_count != rhs.z_count ||
intensity_count != rhs.intensity_count || is_bigendian != rhs.is_bigendian;
}
};

enum NetworkIO { voxels = 0, num_points, coors, cls_score, dir_pred, bbox_pred, ENUM_SIZE };

// cspell: ignore divup
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,15 +93,16 @@ void PointCloudDensification::enqueue(
affine_world2current_ = affine_world2current;
current_timestamp_ = rclcpp::Time(msg.header.stamp).seconds();

auto data_d = cuda::make_unique<uint8_t[]>(
sizeof(uint8_t) * msg.width * msg.height * msg.point_step / sizeof(uint8_t));
assert(sizeof(uint8_t) * msg.width * msg.height * msg.point_step % sizeof(float) == 1);
auto points_d = cuda::make_unique<float[]>(
sizeof(uint8_t) * msg.width * msg.height * msg.point_step / sizeof(float));

CHECK_CUDA_ERROR(cudaMemcpyAsync(
data_d.get(), msg.data.data(), sizeof(uint8_t) * msg.width * msg.height * msg.point_step,
points_d.get(), msg.data.data(), sizeof(uint8_t) * msg.width * msg.height * msg.point_step,
cudaMemcpyHostToDevice, stream_));

PointCloudWithTransform pointcloud = {
std::move(data_d), msg.header, msg.width * msg.height, affine_world2current.inverse()};
std::move(points_d), msg.header, msg.width * msg.height, affine_world2current.inverse()};

pointcloud_cache_.push_front(std::move(pointcloud));
}
Expand Down
Loading
Loading