1. 首先ROS2在编译前先
    source /opt/ros/foxy/setup.bash
  2. 在编译后记得要在工作空间目录的/srcsource install/setup.bash
  3. 关于自定义消息格式的编译,在编译过程中关于rosidl的报错,需要注意在编译自定义消息的功能包时候,将conda环境deactivate,要把base环境也取消掉。
  4. 在重新编译的时候注意要把 build、install 等文件夹(编译的过程文件)全部删除后重新编译才可以哦。
  5. 上述问题原因可能在于conda环境和ros环境有冲突。

具体代码如下,可供参考:
(可视化部分有待优化)

import os
import sys

sys.path.append("/home/wyk/mmdetection3d") #导入当前工作空间路径

import time
import glob
import math
import torch
import rclpy
import copy
import mmcv
import argparse
import numpy as np
import open3d as o3d
from open3d import geometry
import scipy.linalg as linalg
from argparse import ArgumentParser
from pathlib import Path
from pyquaternion import Quaternion
from rclpy.node import Node

from sensor_msgs.msg import PointCloud2
from builtin_interfaces.msg import Duration
from visualization_msgs.msg import Marker,MarkerArray
from typing import List, Optional, Sequence, Tuple, Union, Iterable, List, NamedTuple, Optional
from objects_msgs.msg import ObjectInfo,ObjectsInfoList

from mmdet3d.visualization import Det3DLocalVisualizer
from mmdet3d.structures import LiDARInstance3DBoxes
from mmdet3d.apis import inference_detector, init_model
from mmdet3d.structures.points import get_points_type
from mmdet3d.registry import VISUALIZERS
from mmdet3d.structures import (Box3DMode, CameraInstance3DBoxes, LiDARInstance3DBoxes)
from mmengine import load

class MMDET3DInference(Node):
    def __init__(self):                                                              
        super().__init__('pointpillars_inference')
        # 实车数据ROS2消息器
        self.lidar_subscriber = self.create_subscription(PointCloud2, '/ch128x1/lslidar_point_cloud', self.lidar_callback,10)
        self.inference_data_publisher = self.create_publisher(ObjectsInfoList, 'Detection_3DBBOX_DATA', 10)

        # 填写训练权重文件实际路径 and 配置文件实际路径
        self.checkpoint_file = '/home/wyk/mmdetection3d/work_dirs/epoch_80.pth'
        self.config_file = '/home/wyk/mmdetection3d/work_dirs/pointpillars_hv_secfpn_8xb6-160e_ls-3d-car.py'
        self.model = init_model(self.config_file, self.checkpoint_file, device='cuda:0')
        
        # 可视化
        self.vis = Det3DLocalVisualizer()
        self.to_reset = True
        
    def lidar_callback(self, msg):
        # 获取点云消息中的二进制数据
        data = msg.data

        # 将二进制数据保存为二进制文件
        bin_filename = f'point_cloud.bin'
        with open(bin_filename, 'wb') as f:
            f.write(data)
    
        result, data_ = inference_detector(self.model, 'point_cloud.bin')
        scores = result.pred_instances_3d.scores_3d
        mask = scores > 0.5
        scores = scores[mask]
        boxes_lidar = result.pred_instances_3d.bboxes_3d[mask]
        

        '''
        可视化模块
        '''
        self.vis.o3d_vis.clear_geometries()
        # 从二进制文件加载点云数据
        with open(bin_filename, 'rb') as f:
            data = f.read()
        # 将二进制数据转换为numpy数组
        points_np = np.frombuffer(data, dtype=np.float32)
        # 重塑数组以得到点云
        points = points_np.reshape(-1, 8)


        self.vis.set_points(points)
        self.vis.draw_bboxes_3d(boxes_lidar)
        # global to_reset 重置坐标位置和大小
        if self.to_reset:
            self.vis.o3d_vis.reset_view_point(True)
            self.to_reset = False
        # 获取渲染选项对象
        render_options = self.vis.o3d_vis.get_render_option()
        render_options.point_size = 0.3 
        render_options.show_coordinate_frame = True
        # 显示;更新;清楚
        self.vis.o3d_vis.poll_events()
        self.vis.o3d_vis.update_renderer()
        # time.sleep(0.001)

        '''
        发布结果消息部分
        '''
        
        object_list = ObjectsInfoList()     # boxes list 消息
        boxes_lidar = result.pred_instances_3d.bboxes_3d[mask].tensor.cpu().numpy() 
        if boxes_lidar.shape[0] > 0:
            for i in range(boxes_lidar.shape[0]):   
                q = Quaternion(axis=(0, 0, 1), radians=float(boxes_lidar[i][6]))    # 转角
                # 将检测结果转化到车辆GPS坐标系中
                YAW_LIDAR = 0 + 1.57
                TX = 0      # Lidar到GPS沿X轴的距离
                TY = 1.7    # Lidar到GPS沿Y轴的距离
                TZ = -0.9   # Lidar到GPS沿Z轴的距离
                R_T_MATRIX = np.array([[np.cos(YAW_LIDAR),-np.sin(YAW_LIDAR),0,TX],
                                       [np.sin(YAW_LIDAR),np.cos(YAW_LIDAR),0,TY],
                                       [0,0,1,TZ],
                                       [0,0,0,1]])
                CENTER_LIDAR = np.array([[float(boxes_lidar[i][0])],
                                         [float(boxes_lidar[i][1])],
                                         [float(boxes_lidar[i][2])],
                                         [1]
                                         ])
                CENTER_GPS = np.dot(R_T_MATRIX,CENTER_LIDAR)

                # 添加代码将检测到的BBOX的信息封装为指定的消息格式传给后后续节点使用
                object1 = ObjectInfo()
                object1.id = i
                # object1.cls = 'car'
                object1.cls = 1
                object1.heading = q.z + 1.57
                object1.center.x = CENTER_GPS[0,0]
                object1.center.y = CENTER_GPS[1,0]
                object1.center.z = CENTER_GPS[2,0]
                object1.length = float(boxes_lidar[i][3])
                object1.width = float(boxes_lidar[i][4])
                object1.height = float(boxes_lidar[i][5])
            object_list.objects.append(object1)

        if len(object_list.objects) != 0:
            self.inference_data_publisher.publish(object_list)

def main(args=None):
    rclpy.init(args=args)
    mmdet3d_inference = MMDET3DInference()
    rclpy.spin(mmdet3d_inference)
    mmdet3d_inference.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main()
Logo

魔乐社区(Modelers.cn) 是一个中立、公益的人工智能社区,提供人工智能工具、模型、数据的托管、展示与应用协同服务,为人工智能开发及爱好者搭建开放的学习交流平台。社区通过理事会方式运作,由全产业链共同建设、共同运营、共同享有,推动国产AI生态繁荣发展。

更多推荐