Skip to content

Commit d3608e7

Browse files
committed
fix: mark TRTBEVDetNode constructor to explicit and try fix spell-check error
Signed-off-by: liu cui <cynthia.liu@autocore.ai>
1 parent 02f0178 commit d3608e7

File tree

4 files changed

+27
-22
lines changed

4 files changed

+27
-22
lines changed

perception/autoware_tensorrt_bevdet/include/autoware/tensorrt_bevdet/bevdet_node.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,6 @@
2222

2323
#include <Eigen/Core>
2424
#include <Eigen/Geometry>
25-
#include <opencv2/opencv.hpp>
2625

2726
#include <sensor_msgs/msg/image.hpp>
2827

@@ -159,7 +158,7 @@ class TRTBEVDetNode : public rclcpp::Node
159158
* @brief Constructor for TRTBEVDetNode.
160159
* @param options The options for the node.
161160
*/
162-
TRTBEVDetNode(const rclcpp::NodeOptions & options);
161+
explicit TRTBEVDetNode(const rclcpp::NodeOptions & options);
163162

164163
/**
165164
* @brief Destructor for TRTBEVDetNode.

perception/autoware_tensorrt_bevdet/include/autoware/tensorrt_bevdet/ros_utils.hpp

+6-1
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15+
// cspell:ignore BEVDET, bevdet
16+
1517
#ifndef AUTOWARE__TENSORRT_BEVDET__ROS_UTILS_HPP_
1618
#define AUTOWARE__TENSORRT_BEVDET__ROS_UTILS_HPP_
1719

@@ -21,7 +23,7 @@
2123
#include <geometry_msgs/msg/vector3.hpp>
2224
#include <sensor_msgs/msg/camera_info.hpp>
2325
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
24-
26+
#include <opencv2/opencv.hpp>
2527
#include <bevdet.h>
2628

2729
#include <string>
@@ -43,5 +45,8 @@ void getTransform(
4345
void getCameraIntrinsics(
4446
const sensor_msgs::msg::CameraInfo::SharedPtr msg, Eigen::Matrix3f & intrinsics);
4547

48+
// Convert images from OpenCV's cv:: Mat format to a specific format
49+
void imageTransport(std::vector<cv::Mat> imgs, uchar * out_imgs, size_t width, size_t height);
50+
4651
} // namespace autoware::tensorrt_bevdet
4752
#endif // AUTOWARE__TENSORRT_BEVDET__ROS_UTILS_HPP_

perception/autoware_tensorrt_bevdet/src/bevdet_node.cpp

+1-19
Original file line numberDiff line numberDiff line change
@@ -12,13 +12,10 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
// cspell:ignore BEVDET, thre, TRTBEV, bevdet, caminfo, intrin, Ncams, bevfeat, dlongterm, RGBHWC,
16-
// BGRCHW
15+
// cspell:ignore BEVDET, thre, TRTBEV, bevdet, caminfo, intrin, Ncams, bevfeat, dlongterm
1716

1817
#include "autoware/tensorrt_bevdet/bevdet_node.hpp"
1918

20-
#include <preprocess.h>
21-
2219
namespace autoware
2320
{
2421
namespace tensorrt_bevdet
@@ -144,21 +141,6 @@ void TRTBEVDetNode::startCameraInfoSubscription()
144141
[this](const sensor_msgs::msg::CameraInfo::SharedPtr msg) { cameraInfoCallback(5, msg); });
145142
}
146143

147-
void imageTransport(std::vector<cv::Mat> imgs, uchar * out_imgs, size_t width, size_t height)
148-
{
149-
uchar * temp = new uchar[width * height * 3];
150-
uchar * temp_gpu = nullptr;
151-
CHECK_CUDA(cudaMalloc(&temp_gpu, width * height * 3));
152-
153-
for (size_t i = 0; i < imgs.size(); i++) {
154-
cv::cvtColor(imgs[i], imgs[i], cv::COLOR_BGR2RGB);
155-
CHECK_CUDA(cudaMemcpy(temp_gpu, imgs[i].data, width * height * 3, cudaMemcpyHostToDevice));
156-
convert_RGBHWC_to_BGRCHW(temp_gpu, out_imgs + i * width * height * 3, 3, height, width);
157-
}
158-
delete[] temp;
159-
CHECK_CUDA(cudaFree(temp_gpu));
160-
}
161-
162144
void TRTBEVDetNode::callback(
163145
const sensor_msgs::msg::Image::ConstSharedPtr & msg_fl_img,
164146
const sensor_msgs::msg::Image::ConstSharedPtr & msg_f_img,

perception/autoware_tensorrt_bevdet/src/ros_utils.cpp

+19
Original file line numberDiff line numberDiff line change
@@ -12,11 +12,14 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15+
// cspell:ignore bevdet, RGBHWC, BGRCHW
16+
1517
#include "autoware/tensorrt_bevdet/ros_utils.hpp"
1618

1719
#include <autoware_perception_msgs/msg/detected_object_kinematics.hpp>
1820
#include <autoware_perception_msgs/msg/object_classification.hpp>
1921
#include <autoware_perception_msgs/msg/shape.hpp>
22+
#include <preprocess.h>
2023

2124
namespace autoware::tensorrt_bevdet
2225
{
@@ -114,4 +117,20 @@ void getCameraIntrinsics(
114117
intrinsics << msg->k[0], msg->k[1], msg->k[2], msg->k[3], msg->k[4], msg->k[5], msg->k[6],
115118
msg->k[7], msg->k[8];
116119
}
120+
121+
void imageTransport(std::vector<cv::Mat> imgs, uchar * out_imgs, size_t width, size_t height)
122+
{
123+
uchar * temp = new uchar[width * height * 3];
124+
uchar * temp_gpu = nullptr;
125+
CHECK_CUDA(cudaMalloc(&temp_gpu, width * height * 3));
126+
127+
for (size_t i = 0; i < imgs.size(); i++) {
128+
cv::cvtColor(imgs[i], imgs[i], cv::COLOR_BGR2RGB);
129+
CHECK_CUDA(cudaMemcpy(temp_gpu, imgs[i].data, width * height * 3, cudaMemcpyHostToDevice));
130+
convert_RGBHWC_to_BGRCHW(temp_gpu, out_imgs + i * width * height * 3, 3, height, width);
131+
}
132+
delete[] temp;
133+
CHECK_CUDA(cudaFree(temp_gpu));
134+
}
135+
117136
} // namespace autoware::tensorrt_bevdet

0 commit comments

Comments
 (0)