Skip to content

Commit

Permalink
feat(image_projection_based_fusion): add cache for camera projection (#…
Browse files Browse the repository at this point in the history
…9635)

* add camera_projection class and projection cache

Signed-off-by: a-maumau <[email protected]>

* style(pre-commit): autofix

* fix FOV filtering

Signed-off-by: a-maumau <[email protected]>

* style(pre-commit): autofix

* remove unused includes

Signed-off-by: a-maumau <[email protected]>

* update schema

Signed-off-by: a-maumau <[email protected]>

* fix cpplint error

Signed-off-by: a-maumau <[email protected]>

* apply suggestion: more simple and effcient computation

Signed-off-by: a-maumau <[email protected]>

* correct terminology

Signed-off-by: a-maumau <[email protected]>

* style(pre-commit): autofix

* fix comments

Signed-off-by: a-maumau <[email protected]>

* fix var name

Signed-off-by: a-maumau <[email protected]>
Co-authored-by: Taekjin LEE <[email protected]>

* fix variable names

Signed-off-by: a-maumau <[email protected]>
Co-authored-by: Taekjin LEE <[email protected]>

* fix variable names

Signed-off-by: a-maumau <[email protected]>
Co-authored-by: Taekjin LEE <[email protected]>

* fix variable names

Signed-off-by: a-maumau <[email protected]>
Co-authored-by: Taekjin LEE <[email protected]>

* fix variable names

Signed-off-by: a-maumau <[email protected]>
Co-authored-by: Taekjin LEE <[email protected]>

* fix variable names

Signed-off-by: a-maumau <[email protected]>

* fix initialization

Co-authored-by: badai nguyen  <[email protected]>
Signed-off-by: a-maumau <[email protected]>

* add verification to point_project_to_unrectified_image when loading

Co-authored-by: badai nguyen  <[email protected]>
Signed-off-by: a-maumau <[email protected]>

* chore: add option description to project points to unrectified image

Signed-off-by: Taekjin LEE <[email protected]>

---------

Signed-off-by: a-maumau <[email protected]>
Signed-off-by: Taekjin LEE <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: Taekjin LEE <[email protected]>
Co-authored-by: badai nguyen <[email protected]>
Co-authored-by: Taekjin LEE <[email protected]>
  • Loading branch information
5 people authored Dec 24, 2024
1 parent 308eefb commit ca3afdd
Show file tree
Hide file tree
Showing 20 changed files with 522 additions and 167 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ endif()

# Build non-CUDA dependent nodes
ament_auto_add_library(${PROJECT_NAME} SHARED
src/camera_projection.cpp
src/fusion_node.cpp
src/debugger.cpp
src/utils/geometry.cpp
Expand Down
6 changes: 6 additions & 0 deletions perception/autoware_image_projection_based_fusion/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,12 @@ ros2 launch autoware_image_projection_based_fusion pointpainting_fusion.launch.x

The rclcpp::TimerBase timer could not break a for loop, therefore even if time is out when fusing a roi msg at the middle, the program will run until all msgs are fused.

### Approximate camera projection

For algorithms like `pointpainting_fusion`, the computation required to project points onto an unrectified (raw) image can be substantial. To address this, an option is provided to reduce the computational load. Set the [`approximate_camera_projection parameter`](config/fusion_common.param.yaml) to `true` for each camera (ROIs). If the corresponding `point_project_to_unrectified_image` parameter is also set to true, the projections will be pre-cached.

The cached projections are calculated using a grid, with the grid size specified by the `approximation_grid_width_size` and `approximation_grid_height_size` parameters in the [configuration file](config/fusion_common.param.yaml). The centers of the grid are used as the projected points.

### Detail description of each fusion's algorithm is in the following links

| Fusion Name | Description | Detail |
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,8 @@
timeout_ms: 70.0
match_threshold_ms: 50.0
image_buffer_size: 15
point_project_to_unrectified_image: false
# projection setting for each ROI whether unrectify image
point_project_to_unrectified_image: [false, false, false, false, false, false]
debug_mode: false
filter_scope_min_x: -100.0
filter_scope_min_y: -100.0
Expand All @@ -13,5 +14,11 @@
filter_scope_max_y: 100.0
filter_scope_max_z: 100.0

# camera cache setting for each ROI
approximate_camera_projection: [true, true, true, true, true, true]
# grid size in pixels
approximation_grid_cell_width: 1.0
approximation_grid_cell_height: 1.0

# debug parameters
publish_processing_time_detail: false
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
// Copyright 2024 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__IMAGE_PROJECTION_BASED_FUSION__CAMERA_PROJECTION_HPP_
#define AUTOWARE__IMAGE_PROJECTION_BASED_FUSION__CAMERA_PROJECTION_HPP_

#define EIGEN_MPL2_ONLY

#include <Eigen/Core>
#include <opencv2/core/core.hpp>

#include <sensor_msgs/msg/camera_info.hpp>

#include <image_geometry/pinhole_camera_model.h>

#include <memory>

namespace autoware::image_projection_based_fusion
{
struct PixelPos
{
float x;
float y;
};

class CameraProjection
{
public:
explicit CameraProjection(
const sensor_msgs::msg::CameraInfo & camera_info, const float grid_cell_width,
const float grid_cell_height, const bool unrectify, const bool use_approximation);
CameraProjection() : cell_width_(1.0), cell_height_(1.0), unrectify_(false) {}
void initialize();
std::function<bool(const cv::Point3d &, Eigen::Vector2d &)> calcImageProjectedPoint;
sensor_msgs::msg::CameraInfo getCameraInfo();
bool isOutsideHorizontalView(const float px, const float pz);
bool isOutsideVerticalView(const float py, const float pz);
bool isOutsideFOV(const float px, const float py, const float pz);

protected:
bool calcRectifiedImageProjectedPoint(
const cv::Point3d & point3d, Eigen::Vector2d & projected_point);
bool calcRawImageProjectedPoint(const cv::Point3d & point3d, Eigen::Vector2d & projected_point);
bool calcRawImageProjectedPointWithApproximation(
const cv::Point3d & point3d, Eigen::Vector2d & projected_point);
void initializeCache();

sensor_msgs::msg::CameraInfo camera_info_;
uint32_t image_height_, image_width_;
double tan_h_x_, tan_h_y_;
double fov_left_, fov_right_, fov_top_, fov_bottom_;

uint32_t cache_size_;
float cell_width_;
float cell_height_;
float inv_cell_width_;
float inv_cell_height_;
int grid_width_;
int grid_height_;

bool unrectify_;
bool use_approximation_;

std::unique_ptr<PixelPos[]> projection_cache_;
image_geometry::PinholeCameraModel camera_model_;
};

} // namespace autoware::image_projection_based_fusion

#endif // AUTOWARE__IMAGE_PROJECTION_BASED_FUSION__CAMERA_PROJECTION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef AUTOWARE__IMAGE_PROJECTION_BASED_FUSION__FUSION_NODE_HPP_
#define AUTOWARE__IMAGE_PROJECTION_BASED_FUSION__FUSION_NODE_HPP_

#include <autoware/image_projection_based_fusion/camera_projection.hpp>
#include <autoware/image_projection_based_fusion/debugger.hpp>
#include <autoware/universe_utils/ros/debug_publisher.hpp>
#include <autoware/universe_utils/system/stop_watch.hpp>
Expand Down Expand Up @@ -55,6 +56,7 @@ using sensor_msgs::msg::PointCloud2;
using tier4_perception_msgs::msg::DetectedObjectsWithFeature;
using tier4_perception_msgs::msg::DetectedObjectWithFeature;
using PointCloud = pcl::PointCloud<pcl::PointXYZ>;
using autoware::image_projection_based_fusion::CameraProjection;
using autoware_perception_msgs::msg::ObjectClassification;

template <class TargetMsg3D, class ObjType, class Msg2D>
Expand Down Expand Up @@ -86,7 +88,7 @@ class FusionNode : public rclcpp::Node

virtual void fuseOnSingleImage(
const TargetMsg3D & input_msg, const std::size_t image_id, const Msg2D & input_roi_msg,
const sensor_msgs::msg::CameraInfo & camera_info, TargetMsg3D & output_msg) = 0;
TargetMsg3D & output_msg) = 0;

// set args if you need
virtual void postprocess(TargetMsg3D & output_msg);
Expand All @@ -100,11 +102,16 @@ class FusionNode : public rclcpp::Node
tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_;

bool point_project_to_unrectified_image_{false};
std::vector<bool> point_project_to_unrectified_image_;

// camera_info
std::map<std::size_t, sensor_msgs::msg::CameraInfo> camera_info_map_;
std::vector<rclcpp::Subscription<sensor_msgs::msg::CameraInfo>::SharedPtr> camera_info_subs_;
// camera projection
std::vector<CameraProjection> camera_projectors_;
std::vector<bool> approx_camera_projection_;
float approx_grid_cell_w_size_;
float approx_grid_cell_h_size_;

rclcpp::TimerBase::SharedPtr timer_;
double timeout_ms_{};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,15 +53,12 @@ class PointPaintingFusionNode
void fuseOnSingleImage(
const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const std::size_t image_id,
const DetectedObjectsWithFeature & input_roi_msg,
const sensor_msgs::msg::CameraInfo & camera_info,
sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg) override;

void postprocess(sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg) override;

rclcpp::Publisher<DetectedObjects>::SharedPtr obj_pub_ptr_;

std::vector<double> tan_h_; // horizontal field of view

int omp_num_threads_{1};
float score_threshold_{0.0};
std::vector<std::string> class_names_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@ class RoiClusterFusionNode
void fuseOnSingleImage(
const DetectedObjectsWithFeature & input_cluster_msg, const std::size_t image_id,
const DetectedObjectsWithFeature & input_roi_msg,
const sensor_msgs::msg::CameraInfo & camera_info,
DetectedObjectsWithFeature & output_cluster_msg) override;

std::string trust_object_iou_mode_{"iou"};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,13 +42,11 @@ class RoiDetectedObjectFusionNode

void fuseOnSingleImage(
const DetectedObjects & input_object_msg, const std::size_t image_id,
const DetectedObjectsWithFeature & input_roi_msg,
const sensor_msgs::msg::CameraInfo & camera_info, DetectedObjects & output_object_msg) override;
const DetectedObjectsWithFeature & input_roi_msg, DetectedObjects & output_object_msg) override;

std::map<std::size_t, DetectedObjectWithFeature> generateDetectedObjectRoIs(
const DetectedObjects & input_object_msg, const double image_width, const double image_height,
const Eigen::Affine3d & object2camera_affine,
const image_geometry::PinholeCameraModel & pinhole_camera_model);
const DetectedObjects & input_object_msg, const std::size_t & image_id,
const Eigen::Affine3d & object2camera_affine);

void fuseObjectsOnImage(
const DetectedObjects & input_object_msg,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,7 @@ class RoiPointCloudFusionNode

void fuseOnSingleImage(
const PointCloud2 & input_pointcloud_msg, const std::size_t image_id,
const DetectedObjectsWithFeature & input_roi_msg,
const sensor_msgs::msg::CameraInfo & camera_info, PointCloud2 & output_pointcloud_msg) override;
const DetectedObjectsWithFeature & input_roi_msg, PointCloud2 & output_pointcloud_msg) override;
bool out_of_scope(const DetectedObjectWithFeature & obj) override;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ class SegmentPointCloudFusionNode : public FusionNode<PointCloud2, PointCloud2,

void fuseOnSingleImage(
const PointCloud2 & input_pointcloud_msg, const std::size_t image_id, const Image & input_mask,
const CameraInfo & camera_info, PointCloud2 & output_pointcloud_msg) override;
PointCloud2 & output_pointcloud_msg) override;

bool out_of_scope(const PointCloud2 & filtered_cloud) override;
inline void copyPointCloud(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,10 +65,6 @@ struct PointData

bool checkCameraInfo(const sensor_msgs::msg::CameraInfo & camera_info);

Eigen::Vector2d calcRawImageProjectedPoint(
const image_geometry::PinholeCameraModel & pinhole_camera_model, const cv::Point3d & point3d,
const bool & unrectify = false);

std::optional<geometry_msgs::msg::TransformStamped> getTransformStamped(
const tf2_ros::Buffer & tf_buffer, const std::string & target_frame_id,
const std::string & source_frame_id, const rclcpp::Time & time);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,11 @@
"default": 15,
"minimum": 1
},
"point_project_to_unrectified_image": {
"type": "array",
"description": "An array of options indicating whether to project point to unrectified image or not.",
"default": [false, false, false, false, false, false]
},
"debug_mode": {
"type": "boolean",
"description": "Whether to debug or not.",
Expand Down Expand Up @@ -65,6 +70,21 @@
"type": "number",
"description": "Maximum z position [m].",
"default": 100.0
},
"approximate_camera_projection": {
"type": "array",
"description": "An array of options indicating whether to use approximated projection for each camera.",
"default": [true, true, true, true, true, true]
},
"approximation_grid_cell_width": {
"type": "number",
"description": "The width of grid cell used in approximated projection [pixel].",
"default": 1.0
},
"approximation_grid_cell_height": {
"type": "number",
"description": "The height of grid cell used in approximated projection [pixel].",
"default": 1.0
}
}
}
Expand Down
Loading

0 comments on commit ca3afdd

Please sign in to comment.