-
Notifications
You must be signed in to change notification settings - Fork 870
Expand file tree
/
Copy pathcamera_data.hpp
More file actions
106 lines (89 loc) · 3.56 KB
/
camera_data.hpp
File metadata and controls
106 lines (89 loc) · 3.56 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
// Copyright 2026 TIER IV
//
// 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__BEVFUSION__CAMERA__CAMERA_DATA_HPP_
#define AUTOWARE__BEVFUSION__CAMERA__CAMERA_DATA_HPP_
#include "autoware/bevfusion/camera/camera_matrices.hpp"
#include "autoware/bevfusion/camera/camera_preprocess.hpp"
#include <autoware/cuda_utils/cuda_check_error.hpp>
#include <autoware/cuda_utils/cuda_unique_ptr.hpp>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/camera_info.hpp>
#include <sensor_msgs/msg/compressed_image.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <memory>
#include <string>
namespace autoware::bevfusion
{
using autoware::cuda_utils::CudaUniquePtr;
struct ImagePreProcessingParams
{
std::int64_t original_image_height;
std::int64_t original_image_width;
std::int64_t roi_height;
std::int64_t roi_width;
float image_aug_scale_y;
float image_aug_scale_x;
bool run_image_undistortion;
bool flip_image_channels;
std::int64_t crop_height;
std::int64_t crop_width;
std::int64_t resized_height;
std::int64_t resized_width;
std::int64_t roi_start_y;
std::int64_t roi_start_x;
ImagePreProcessingParams(
const std::int64_t original_image_height, const std::int64_t original_image_width,
const std::int64_t roi_height, const std::int64_t roi_width, const float image_aug_scale_y,
const float image_aug_scale_x, const bool run_image_undistortion,
const bool flip_image_channels);
};
class CameraData
{
public:
CameraData(
rclcpp::Node * node, const int camera_id,
const ImagePreProcessingParams & image_pre_processing_params,
const std::shared_ptr<CameraMatrices> & camera_matrices_ptr);
~CameraData();
void update_image_msg(const sensor_msgs::msg::Image::ConstSharedPtr & input_camera_image_msg);
void update_camera_info(const sensor_msgs::msg::CameraInfo & input_camera_info_msg);
std::optional<sensor_msgs::msg::CameraInfo> camera_info() const;
sensor_msgs::msg::CameraInfo camera_info_value() const;
sensor_msgs::msg::Image::ConstSharedPtr image_msg() const;
bool is_image_msg_available() const;
bool is_camera_info_available() const;
std::size_t output_img_offset() const;
void preprocess_image(std::uint8_t * output_img);
bool is_camera_matrices_ready() const;
cudaError_t sync_cuda_stream();
private:
// Camera info buffer
std::optional<sensor_msgs::msg::CameraInfo> camera_info_;
// Image buffer
// TODO(KokSeang): Remove this once we move preprocessing to subscribers
sensor_msgs::msg::Image::ConstSharedPtr image_msg_;
// GPU Memory for preprocessed image
// image buffers
CudaUniquePtr<std::uint8_t[]> image_buffer_d_{nullptr};
CudaUniquePtr<std::uint8_t[]> undistorted_image_buffer_d_{nullptr};
rclcpp::Logger logger_;
int camera_id_;
ImagePreProcessingParams image_pre_processing_params_;
std::size_t output_img_offset_;
cudaStream_t stream_{nullptr};
std::unique_ptr<CameraPreprocess> camera_preprocess_ptr_{nullptr};
std::shared_ptr<CameraMatrices> camera_matrices_ptr_{nullptr};
};
} // namespace autoware::bevfusion
#endif // AUTOWARE__BEVFUSION__CAMERA__CAMERA_DATA_HPP_