init
23
src/rm_auto_aim/README.md
Normal file
@@ -0,0 +1,23 @@
|
||||
# rm_auto_aim
|
||||
|
||||
FYT视觉24赛季装甲板识别与跟踪算法ROS2功能包
|
||||
|
||||
**主要参考**: [rm_vision](https://gitlab.com/rm_vision)
|
||||
|
||||
## 维护者及开源许可证
|
||||
|
||||
Maintainer : Chengfu Zou, chengfuzou@outlook.com
|
||||
|
||||
```
|
||||
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.
|
||||
```
|
||||
99
src/rm_auto_aim/armor_detector/CMakeLists.txt
Normal file
@@ -0,0 +1,99 @@
|
||||
cmake_minimum_required(VERSION 3.10)
|
||||
project(armor_detector)
|
||||
|
||||
## Set CMake policy to suppress OpenGL warning
|
||||
cmake_policy(SET CMP0072 NEW)
|
||||
|
||||
## Use C++14
|
||||
set(CMAKE_CXX_STANDARD 17)
|
||||
set(CMAKE_CXX_STANDARD_REQUIRED ON)
|
||||
|
||||
## By adding -Wall and -Werror, the compiler does not ignore warnings anymore,
|
||||
## enforcing cleaner code.
|
||||
add_definitions(-Wall -Werror)
|
||||
add_definitions(-O3)
|
||||
|
||||
|
||||
## Export compile commands for clangd
|
||||
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
|
||||
|
||||
#######################
|
||||
## Find dependencies ##
|
||||
#######################
|
||||
|
||||
# set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${PROJECT_SOURCE_DIR}/cmake_modules)
|
||||
set(G2O_DIR "/usr/local/lib/cmake/g2o")
|
||||
set(EXTERNAL_INCLUDE_DIRS ${G2O_INCLUDE_DIR})
|
||||
set(EXTERNAL_LIBS ${G2O_LIBRARIES})
|
||||
|
||||
find_package(ament_cmake_auto REQUIRED)
|
||||
find_package(OpenCV REQUIRED)
|
||||
find_package(TBB REQUIRED COMPONENTS tbb)
|
||||
find_package(g2o REQUIRED)
|
||||
find_package(fmt REQUIRED)
|
||||
find_package(Sophus REQUIRED)
|
||||
ament_auto_find_build_dependencies()
|
||||
|
||||
###########
|
||||
## Build ##
|
||||
###########
|
||||
|
||||
ament_auto_add_library(${PROJECT_NAME} SHARED
|
||||
DIRECTORY src
|
||||
)
|
||||
|
||||
target_include_directories(${PROJECT_NAME} PUBLIC
|
||||
${OpenCV_INCLUDE_DIRS}
|
||||
${G2O_INCLUDE_DIRS}
|
||||
${Sophus_INCLUDE_DIRS}
|
||||
${EIGEN3_INCLUDE_DIRS}
|
||||
)
|
||||
|
||||
target_link_libraries(${PROJECT_NAME}
|
||||
${OpenCV_LIBS}
|
||||
g2o_core
|
||||
g2o_stuff
|
||||
g2o_solver_csparse
|
||||
g2o_types_sba
|
||||
g2o_types_slam3d
|
||||
g2o_solver_dense
|
||||
fmt::fmt
|
||||
tbb
|
||||
)
|
||||
|
||||
|
||||
rclcpp_components_register_node(${PROJECT_NAME}
|
||||
PLUGIN fyt::auto_aim::ArmorDetectorNode
|
||||
EXECUTABLE armor_detector_node
|
||||
)
|
||||
|
||||
#############
|
||||
## Testing ##
|
||||
#############
|
||||
|
||||
if(BUILD_TESTING)
|
||||
find_package(ament_lint_auto REQUIRED)
|
||||
list(APPEND AMENT_LINT_AUTO_EXCLUDE
|
||||
ament_cmake_copyright
|
||||
ament_cmake_uncrustify
|
||||
ament_cmake_cpplint
|
||||
ament_cmake_lint_cmake
|
||||
)
|
||||
ament_lint_auto_find_test_dependencies()
|
||||
|
||||
find_package(ament_cmake_gtest)
|
||||
ament_add_gtest(test_detector test/test_detector.cpp)
|
||||
target_link_libraries(test_detector ${PROJECT_NAME})
|
||||
|
||||
endif()
|
||||
|
||||
#############
|
||||
## Install ##
|
||||
#############
|
||||
|
||||
ament_auto_package(
|
||||
USE_SCOPED_HEADER_INSTALL_DIR
|
||||
INSTALL_TO_SHARE
|
||||
docs
|
||||
model
|
||||
)
|
||||
141
src/rm_auto_aim/armor_detector/README.md
Normal file
@@ -0,0 +1,141 @@
|
||||
# armor_detector
|
||||
|
||||
订阅相机参数及图像流进行装甲板的识别并解算三维位置,输出识别到的装甲板在输入frame下的三维位置 (一般是以相机光心为原点的相机坐标系)
|
||||
|
||||
## fyt::ArmorDetectorNode
|
||||
|
||||
装甲板识别节点
|
||||
|
||||
### 发布话题
|
||||
|
||||
* `armor_detector/armors` (`rm_interfaces/msg/Armors`) - 识别到的装甲板信息
|
||||
* `armor_detector/debug_lights` (`rm_interfaces/msg/DebugLights`) - Debug灯条信息
|
||||
* `armor_detector/debug_armors` (`rm_interfaces/msg/DebugArmors`) - Debug装甲板信息
|
||||
* `armor_detector/result_img` (`sensor_msgs/msg/Image`) - 识别结果可视化图像
|
||||
* `armor_detector/binary_img` (`sensor_msgs/msg/Image`) - 二值化图像
|
||||
* `armor_detector/number_img` (`sensor_msgs/msg/Image`) - 数字识别roi
|
||||
|
||||
### 订阅话题
|
||||
|
||||
* `image_raw` (`sensor_msgs/msg/Image`) - 相机图像
|
||||
* `camera_info` (`sensor_msgs/msg/CameraInfo`) - 相机参数
|
||||
|
||||
### 服务
|
||||
|
||||
* `armor_detector/set_mode` (`rm_interfaces/srv/SetMode`) - 设置模式
|
||||
|
||||
### 参数
|
||||
|
||||
* `debug` (`bool`, default: false) - 是否开启调试模式
|
||||
* `classify_threshold` (`double`, default: 0.8) - 数字分类阈值
|
||||
* `ignore_class` (`vector<string>`, default: ["negativie"]) - 跳过的类别
|
||||
* `binary_thres` (`int`, default: 100) - 二值化阈值
|
||||
* `light.min_ratio` (`double`, default: 0.08) - 灯条最小长宽比
|
||||
* `light.max_ratio` (`double`, default: 0.4) - 灯条最大长宽比
|
||||
* `light.max_angle` (`double`, default: 40) - 灯条最大倾斜角度
|
||||
* `light.color_diff_thresh` (`int`, default: 25) - 灯条颜色差异阈值`
|
||||
* `armor.min_light_ratio` (`double`, default: 0.6) - 装甲板最小长宽比
|
||||
* `armor.min_small_center_distance` (`double`, default: 0.8) - 小装甲板最小中心距离长宽比
|
||||
* `armor.max_small_center_distance` (`double`, default: 3.2) - 小装甲板最大中心距离长宽比
|
||||
* `armor.min_large_center_distance` (`double`, default: 1.8) - 大装甲板最小中心距离长宽比
|
||||
* `armor.max_large_center_distance` (`double`, default: 6.4) - 大装甲板最大中心距离长宽比
|
||||
* `armor.max_angle` (`double`, default: 35.0) - 装甲板最大倾斜角度
|
||||
|
||||
|
||||
## Detector
|
||||
装甲板识别器
|
||||
|
||||
### preprocessImage
|
||||
预处理
|
||||
|
||||
|  |  |  |
|
||||
| :---------------: | :-------------------: | :--------------------: |
|
||||
| 原图 | 通过颜色二值化 | 通过灰度二值化 |
|
||||
|
||||
由于一般工业相机的动态范围不够大,导致若要能够清晰分辨装甲板的数字,得到的相机图像中灯条中心就会过曝,灯条中心的像素点的值往往都是 R=B。根据颜色信息来进行二值化效果不佳,因此此处选择了直接通过灰度图进行二值化,将灯条的颜色判断放到后续处理中。
|
||||
|
||||
### findLights
|
||||
寻找灯条
|
||||
|
||||
通过 findContours 得到轮廓,再通过 minAreaRect 获得最小外接矩形,对其进行长宽比和倾斜角度的判断,可以高效的筛除形状不满足的亮斑。
|
||||
|
||||
判断灯条颜色这里采用了对轮廓内的的R/B值求和,判断两和的的大小的方法,若 `sum_r > sum_b` 则认为是红色灯条,反之则认为是蓝色灯条。
|
||||
|
||||
|  |  |
|
||||
| :---------------: | :----------------: |
|
||||
| 提取出的红色灯条 | 提取出的蓝色灯条 |
|
||||
|
||||
### matchLights
|
||||
配对灯条
|
||||
|
||||
根据 `detect_color` 选择对应颜色的灯条进行两两配对,首先筛除掉两条灯条中间包含另一个灯条的情况,然后根据两灯条的长度之比、两灯条中心的距离、配对出装甲板的倾斜角度来筛选掉条件不满足的结果,得到形状符合装甲板特征的灯条配对。
|
||||
|
||||
## NumberClassifier
|
||||
数字分类器
|
||||
|
||||
### extractNumbers
|
||||
提取数字
|
||||
|
||||
|  |  |  |  |
|
||||
| :-------------------: | :--------------------: | :-------------------: | :-------------------: |
|
||||
| 原图 | 透视变换 | 取ROI | 二值化 |
|
||||
|
||||
将每条灯条上下的角点拉伸到装甲板的上下边缘作为待变换点,进行透视变换,再对变换后的图像取ROI。考虑到数字图案实质上就是黑色背景+白色图案,所以此处使用了大津法进行二值化。
|
||||
|
||||
### Classify
|
||||
分类
|
||||
|
||||
我们使用LeNet-5网络结构进行数字分类,同时在训练过程中加入了大量的椒盐噪声,有利于提高暗环境下的识别准确率
|
||||
|
||||
网络结构:
|
||||
|
||||

|
||||
|
||||
效果图:
|
||||
|
||||

|
||||
|
||||
## 角点矫正
|
||||
|
||||
在原版rm_vision中,使用旋转矩形的上顶点作为灯条角点,这种方法很受二值化图像的影响,当给不同的二值化阈值或者环境光照不均匀时,识别到的角点位置会发生变化,如图旋转矩形顶点1和2。这会导致角点实际坐标与types.hpp中定义的物体坐标不对应,影响到PnP的准确性。
|
||||
|
||||
|  |  |  |  |
|
||||
| :-------------------: | :--------------------: | :-------------------: | :-------------------: |
|
||||
| 旋转矩形顶点1 | 旋转矩形顶点2 | PCA1 | PCA2 |
|
||||
|
||||
为了解决这个问题,我们使用PCA方法对灯条的角点进行矫正,先利用[主成分分析](https://docs.opencv.org/4.x/d1/dee/tutorial_introduction_to_pca.html)(Principal Component Analysis, PCA)方法获取灯条的对称轴,然后根据沿着对称轴方向寻找上下两个亮度变化最大的点(通常是图PCA2中那样的明暗交界处),作为灯条的角点。
|
||||
|
||||
如图PCA1和PCA2所示,这种方法获得的角点在不同光照下表现出一致性,可以提高PnP的准确性。
|
||||
|
||||
## BA优化
|
||||
|
||||

|
||||
|
||||
<!-- 根据RoboMaster机器人制作规范,非平衡机器人在平地上,每块装甲板相对地面坐标系的姿态角应为Roll=0,Pitch=15°,Yaw=$\theta$,其中只有Yaw角度是未知的。可以根据这个特征求取装甲板的Yaw角度,参考上海交通大学2023年全国赛青工会上的展示。
|
||||
|
||||
我们使用BA优化的方式来求取Yaw角度,BA(光束法平差,Bundle Adjustment)优化是一种特殊的最小二乘问题,其通过最小化重投影误差来求取相机位姿。
|
||||
|
||||
假设装甲板Yaw角度为$\theta$,相机系下装甲板位姿为$(R^{camera}_{armor},t^{camera}_{armor})$,IMU系下相机姿态为$R^{imu}_{camera}$,相机内参为$K$,装甲板第$i$个角点在装甲板坐标系下为$P^{armor}_i$
|
||||
|
||||
则易得$R^{camera}_{armor}$为$\theta$的一元函数值
|
||||
$$
|
||||
R^{camera}_{armor} = {R^{imu}_{camera}}^T ·R^{imu}_{armor}=R^{camera}_{imu}·R(Z,\theta)·R(Y,15°)·R(X,0)=f(\theta)
|
||||
$$
|
||||
装甲板角点在图像中的未归一化投影坐标为:
|
||||
$$
|
||||
P^{img}_i=K·(R^{camera}_{armor}·P^{armor}_i+t^{camera}_{armor})
|
||||
$$
|
||||
其中$t^{camera}_{armor}$可用PnP的结果
|
||||
|
||||
设每个角点在图像中识别到的坐标为$P^{det}_i$,则有误差函数:
|
||||
$$
|
||||
e(\theta)=\sum^{n}_{i}||P^{det}_i-\frac{P^{img}_i}{P^{img}_i.z}||^2
|
||||
$$
|
||||
最小化该误差函数即可得到优化后的Yaw角度$\hat{\theta}$
|
||||
$$
|
||||
\hat{\theta}={argmin}_{\theta} \space e(\theta)
|
||||
$$
|
||||
|
||||
|
||||
可以使用各类数值优化方法,例如最速下降、高斯牛顿等方法求解,但更推荐使用一些现成的优化库,例如G2O、Ceres实现该问题的求解
|
||||
-->
|
||||
107
src/rm_auto_aim/armor_detector/cmake_modules/FindG2O.cmake.bak
Normal file
@@ -0,0 +1,107 @@
|
||||
# Locate the g2o libraries
|
||||
# A general framework for graph optimization.
|
||||
#
|
||||
# This module defines
|
||||
# G2O_FOUND, if false, do not try to link against g2o
|
||||
# G2O_LIBRARIES, path to the libg2o
|
||||
# G2O_INCLUDE_DIR, where to find the g2o header files
|
||||
#
|
||||
# Niko Suenderhauf <niko@etit.tu-chemnitz.de>
|
||||
# Adapted by Felix Endres <endres@informatik.uni-freiburg.de>
|
||||
|
||||
IF(UNIX)
|
||||
|
||||
#IF(G2O_INCLUDE_DIR AND G2O_LIBRARIES)
|
||||
# in cache already
|
||||
# SET(G2O_FIND_QUIETLY TRUE)
|
||||
#ENDIF(G2O_INCLUDE_DIR AND G2O_LIBRARIES)
|
||||
|
||||
MESSAGE(STATUS "Searching for g2o ...")
|
||||
FIND_PATH(G2O_INCLUDE_DIR
|
||||
NAMES core types stuff
|
||||
PATHS /usr/local /usr
|
||||
PATH_SUFFIXES include/g2o include)
|
||||
|
||||
IF (G2O_INCLUDE_DIR)
|
||||
MESSAGE(STATUS "Found g2o headers in: ${G2O_INCLUDE_DIR}")
|
||||
ELSE()
|
||||
MESSAGE(STATUS "G2O_INCLUDE_DIR not found")
|
||||
ENDIF ()
|
||||
|
||||
FIND_LIBRARY(G2O_CORE_LIB
|
||||
NAMES g2o_core g2o_core_rd
|
||||
PATHS /usr/local /usr ${CMAKE_PREFIX_PATH}
|
||||
PATH_SUFFIXES lib)
|
||||
FIND_LIBRARY(G2O_STUFF_LIB
|
||||
NAMES g2o_stuff g2o_stuff_rd
|
||||
PATHS /usr/local /usr ${CMAKE_PREFIX_PATH}
|
||||
PATH_SUFFIXES lib)
|
||||
FIND_LIBRARY(G2O_TYPES_SLAM2D_LIB
|
||||
NAMES g2o_types_slam2d g2o_types_slam2d_rd
|
||||
PATHS /usr/local /usr ${CMAKE_PREFIX_PATH}
|
||||
PATH_SUFFIXES lib)
|
||||
FIND_LIBRARY(G2O_TYPES_SLAM3D_LIB
|
||||
NAMES g2o_types_slam3d g2o_types_slam3d_rd
|
||||
PATHS /usr/local /usr ${CMAKE_PREFIX_PATH}
|
||||
PATH_SUFFIXES lib)
|
||||
FIND_LIBRARY(G2O_SOLVER_CHOLMOD_LIB
|
||||
NAMES g2o_solver_cholmod g2o_solver_cholmod_rd
|
||||
PATHS /usr/local /usr ${CMAKE_PREFIX_PATH}
|
||||
PATH_SUFFIXES lib)
|
||||
FIND_LIBRARY(G2O_SOLVER_PCG_LIB
|
||||
NAMES g2o_solver_pcg g2o_solver_pcg_rd
|
||||
PATHS /usr/local /usr ${CMAKE_PREFIX_PATH}
|
||||
PATH_SUFFIXES lib)
|
||||
FIND_LIBRARY(G2O_SOLVER_CSPARSE_LIB
|
||||
NAMES g2o_solver_csparse g2o_solver_csparse_rd
|
||||
PATHS /usr/local /usr
|
||||
PATH_SUFFIXES lib)
|
||||
FIND_LIBRARY(G2O_INCREMENTAL_LIB
|
||||
NAMES g2o_incremental g2o_incremental_rd
|
||||
PATHS /usr/local /usr ${CMAKE_PREFIX_PATH}
|
||||
PATH_SUFFIXES lib)
|
||||
FIND_LIBRARY(G2O_CSPARSE_EXTENSION_LIB
|
||||
NAMES g2o_csparse_extension g2o_csparse_extension_rd
|
||||
PATHS /usr/local /usr ${CMAKE_PREFIX_PATH}
|
||||
PATH_SUFFIXES lib)
|
||||
MESSAGE(STATUS "G2O_CORE_LIB: ${G2O_CORE_LIB}")
|
||||
MESSAGE(STATUS "G2O_STUFF_LIB: ${G2O_STUFF_LIB}")
|
||||
MESSAGE(STATUS "G2O_TYPES_SLAM2D_LIB: ${G2O_TYPES_SLAM2D_LIB}")
|
||||
MESSAGE(STATUS "G2O_TYPES_SLAM3D_LIB: ${G2O_TYPES_SLAM3D_LIB}")
|
||||
MESSAGE(STATUS "G2O_SOLVER_CHOLMOD_LIB: ${G2O_SOLVER_CHOLMOD_LIB}")
|
||||
MESSAGE(STATUS "G2O_SOLVER_PCG_LIB: ${G2O_SOLVER_PCG_LIB}")
|
||||
MESSAGE(STATUS "G2O_SOLVER_CSPARSE_LIB: ${G2O_SOLVER_CSPARSE_LIB}")
|
||||
MESSAGE(STATUS "G2O_INCREMENTAL_LIB: ${G2O_INCREMENTAL_LIB}")
|
||||
MESSAGE(STATUS "G2O_CSPARSE_EXTENSION_LIB: ${G2O_CSPARSE_EXTENSION_LIB}")
|
||||
|
||||
SET(G2O_LIBRARIES ${G2O_CSPARSE_EXTENSION_LIB}
|
||||
${G2O_CORE_LIB}
|
||||
${G2O_STUFF_LIB}
|
||||
${G2O_TYPES_SLAM2D_LIB}
|
||||
${G2O_TYPES_SLAM3D_LIB}
|
||||
${G2O_SOLVER_CHOLMOD_LIB}
|
||||
${G2O_SOLVER_PCG_LIB}
|
||||
${G2O_SOLVER_CSPARSE_LIB}
|
||||
${G2O_INCREMENTAL_LIB}
|
||||
)
|
||||
|
||||
IF(G2O_LIBRARIES AND G2O_INCLUDE_DIR)
|
||||
SET(G2O_FOUND "YES")
|
||||
IF(NOT G2O_FIND_QUIETLY)
|
||||
MESSAGE(STATUS "Found libg2o: ${G2O_LIBRARIES}")
|
||||
ENDIF()
|
||||
ELSE(G2O_LIBRARIES AND G2O_INCLUDE_DIR)
|
||||
IF(NOT G2O_LIBRARIES)
|
||||
IF(G2O_FIND_REQUIRED)
|
||||
message(FATAL_ERROR "Could not find libg2o!")
|
||||
ENDIF()
|
||||
ENDIF()
|
||||
|
||||
IF(NOT G2O_INCLUDE_DIR)
|
||||
IF(G2O_FIND_REQUIRED)
|
||||
message(FATAL_ERROR "Could not find g2o include directory!")
|
||||
ENDIF()
|
||||
ENDIF()
|
||||
ENDIF()
|
||||
|
||||
ENDIF(UNIX)
|
||||
BIN
src/rm_auto_aim/armor_detector/docs/BA.png
Normal file
|
After Width: | Height: | Size: 185 KiB |
BIN
src/rm_auto_aim/armor_detector/docs/blue.png
Normal file
|
After Width: | Height: | Size: 7.8 KiB |
BIN
src/rm_auto_aim/armor_detector/docs/classify.png
Normal file
|
After Width: | Height: | Size: 41 KiB |
BIN
src/rm_auto_aim/armor_detector/docs/gray_bin.png
Normal file
|
After Width: | Height: | Size: 9.5 KiB |
BIN
src/rm_auto_aim/armor_detector/docs/hsv_bin.png
Normal file
|
After Width: | Height: | Size: 17 KiB |
1
src/rm_auto_aim/armor_detector/docs/model.svg
Normal file
|
After Width: | Height: | Size: 35 KiB |
BIN
src/rm_auto_aim/armor_detector/docs/num_bin.png
Normal file
|
After Width: | Height: | Size: 5.5 KiB |
BIN
src/rm_auto_aim/armor_detector/docs/num_raw.png
Normal file
|
After Width: | Height: | Size: 307 KiB |
BIN
src/rm_auto_aim/armor_detector/docs/num_roi.png
Normal file
|
After Width: | Height: | Size: 16 KiB |
BIN
src/rm_auto_aim/armor_detector/docs/num_warp.png
Normal file
|
After Width: | Height: | Size: 25 KiB |
BIN
src/rm_auto_aim/armor_detector/docs/origin1.png
Normal file
|
After Width: | Height: | Size: 230 KiB |
BIN
src/rm_auto_aim/armor_detector/docs/origin2.png
Normal file
|
After Width: | Height: | Size: 239 KiB |
BIN
src/rm_auto_aim/armor_detector/docs/pca1.png
Normal file
|
After Width: | Height: | Size: 296 KiB |
BIN
src/rm_auto_aim/armor_detector/docs/pca2.png
Normal file
|
After Width: | Height: | Size: 181 KiB |
BIN
src/rm_auto_aim/armor_detector/docs/raw.png
Normal file
|
After Width: | Height: | Size: 260 KiB |
BIN
src/rm_auto_aim/armor_detector/docs/red.png
Normal file
|
After Width: | Height: | Size: 5.6 KiB |
BIN
src/rm_auto_aim/armor_detector/docs/test.png
Normal file
|
After Width: | Height: | Size: 106 KiB |
@@ -0,0 +1,105 @@
|
||||
// Copyright Chen Jun 2023. Licensed under the MIT License.
|
||||
//
|
||||
// Additional modifications and features by Chengfu Zou, Labor. Licensed under Apache License 2.0.
|
||||
//
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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 ARMOR_DETECTOR_DETECTOR_HPP_
|
||||
#define ARMOR_DETECTOR_DETECTOR_HPP_
|
||||
|
||||
// std
|
||||
#include <cmath>
|
||||
#include <rm_utils/common.hpp>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
// third party
|
||||
#include <opencv2/core.hpp>
|
||||
#include <opencv2/core/types.hpp>
|
||||
// project
|
||||
#include "armor_detector/light_corner_corrector.hpp"
|
||||
#include "armor_detector/types.hpp"
|
||||
#include "armor_detector/number_classifier.hpp"
|
||||
#include "rm_interfaces/msg/debug_armors.hpp"
|
||||
#include "rm_interfaces/msg/debug_lights.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
class Detector {
|
||||
public:
|
||||
struct LightParams {
|
||||
// width / height
|
||||
double min_ratio;
|
||||
double max_ratio;
|
||||
// vertical angle
|
||||
double max_angle;
|
||||
// Use least-squares line fitting (cv::fitLine) to refine top/bottom points
|
||||
bool use_fit_line;
|
||||
// judge color
|
||||
int color_diff_thresh;
|
||||
};
|
||||
|
||||
struct ArmorParams {
|
||||
double min_light_ratio;
|
||||
// light pairs distance
|
||||
double min_small_center_distance;
|
||||
double max_small_center_distance;
|
||||
double min_large_center_distance;
|
||||
double max_large_center_distance;
|
||||
// horizontal angle
|
||||
double max_angle;
|
||||
};
|
||||
|
||||
Detector(const int &bin_thres, const EnemyColor &color, const LightParams &l,
|
||||
const ArmorParams &a);
|
||||
|
||||
std::vector<Armor> detect(const cv::Mat &input) noexcept;
|
||||
|
||||
cv::Mat preprocessImage(const cv::Mat &input) noexcept;
|
||||
std::vector<Light> findLights(const cv::Mat &rbg_img,
|
||||
const cv::Mat &binary_img) noexcept;
|
||||
std::vector<Armor> matchLights(const std::vector<Light> &lights) noexcept;
|
||||
|
||||
// For debug usage
|
||||
cv::Mat getAllNumbersImage() const noexcept;
|
||||
void drawResults(cv::Mat &img) const noexcept;
|
||||
|
||||
// Parameters
|
||||
int binary_thres;
|
||||
EnemyColor detect_color;
|
||||
LightParams light_params;
|
||||
ArmorParams armor_params;
|
||||
|
||||
std::unique_ptr<NumberClassifier> classifier;
|
||||
std::unique_ptr<LightCornerCorrector> corner_corrector;
|
||||
|
||||
// Debug msgs
|
||||
bool enable_debug = false;
|
||||
cv::Mat binary_img;
|
||||
rm_interfaces::msg::DebugLights debug_lights;
|
||||
rm_interfaces::msg::DebugArmors debug_armors;
|
||||
|
||||
private:
|
||||
bool isLight(const Light &possible_light) noexcept;
|
||||
bool containLight(const int i,const int j,const std::vector<Light> &lights) noexcept;
|
||||
ArmorType isArmor(const Light &light_1, const Light &light_2) noexcept;
|
||||
|
||||
cv::Mat gray_img_;
|
||||
|
||||
std::vector<Light> lights_;
|
||||
std::vector<Armor> armors_;
|
||||
};
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
|
||||
#endif // ARMOR_DETECTOR_DETECTOR_HPP_
|
||||
@@ -0,0 +1,193 @@
|
||||
// Copyright Chen Jun 2023. Licensed under the MIT License.
|
||||
//
|
||||
// Additional modifications and features by Chengfu Zou, Labor. Licensed under
|
||||
// Apache License 2.0.
|
||||
//
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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 ARMOR_DETECTOR_DETECTOR_NODE_HPP_
|
||||
#define ARMOR_DETECTOR_DETECTOR_NODE_HPP_
|
||||
|
||||
// ros2
|
||||
#include <tf2_ros/buffer.h>
|
||||
#include <tf2_ros/buffer_interface.h>
|
||||
#include <tf2_ros/transform_broadcaster.h>
|
||||
#include <tf2_ros/transform_listener.h>
|
||||
|
||||
#include <geometry_msgs/msg/transform_stamped.hpp>
|
||||
#include <image_transport/image_transport.hpp>
|
||||
#include <image_transport/publisher.hpp>
|
||||
#include <image_transport/subscriber_filter.hpp>
|
||||
#include <rcl_interfaces/msg/set_parameters_result.hpp>
|
||||
#include <rclcpp/publisher.hpp>
|
||||
#include <rclcpp/rclcpp.hpp>
|
||||
#include <sensor_msgs/msg/camera_info.hpp>
|
||||
#include <sensor_msgs/msg/image.hpp>
|
||||
#include <visualization_msgs/msg/marker_array.hpp>
|
||||
// std
|
||||
#include <chrono>
|
||||
#include <condition_variable>
|
||||
#include <deque>
|
||||
#include <atomic>
|
||||
#include <memory>
|
||||
#include <mutex>
|
||||
#include <string>
|
||||
#include <thread>
|
||||
#include <vector>
|
||||
// project
|
||||
#include "armor_detector/armor_detector.hpp"
|
||||
#include "armor_detector/armor_pose_estimator.hpp"
|
||||
#include "armor_detector/number_classifier.hpp"
|
||||
#include "rm_interfaces/msg/armors.hpp"
|
||||
#include "rm_interfaces/msg/target.hpp"
|
||||
#include "rm_interfaces/srv/set_mode.hpp"
|
||||
#include "rm_utils/heartbeat.hpp"
|
||||
#include "rm_utils/logger/log.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
|
||||
// Armor Detector Node
|
||||
// Subscribe to the image topic, run the armor detection alogorithm and publish
|
||||
// the detected armors
|
||||
class ArmorDetectorNode : public rclcpp::Node {
|
||||
public:
|
||||
ArmorDetectorNode(const rclcpp::NodeOptions &options);
|
||||
~ArmorDetectorNode() override;
|
||||
|
||||
private:
|
||||
struct PendingFrame {
|
||||
sensor_msgs::msg::Image::ConstSharedPtr img_msg;
|
||||
std::chrono::steady_clock::time_point frame_start;
|
||||
};
|
||||
|
||||
void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr img_msg);
|
||||
void processImageLoop();
|
||||
void processFrame(PendingFrame frame);
|
||||
// void targetCallback(const rm_interfaces::msg::Target::SharedPtr
|
||||
// target_msg);
|
||||
|
||||
std::unique_ptr<Detector> initDetector();
|
||||
|
||||
std::vector<Armor> detectArmors(const sensor_msgs::msg::Image::ConstSharedPtr &img_msg,
|
||||
double *detect_ms = nullptr,
|
||||
double *debug_publish_ms = nullptr);
|
||||
|
||||
void createDebugPublishers() noexcept;
|
||||
void destroyDebugPublishers() noexcept;
|
||||
void refreshDebugPublishersIfNeeded() noexcept;
|
||||
|
||||
void publishMarkers() noexcept;
|
||||
|
||||
void setModeCallback(
|
||||
const std::shared_ptr<rm_interfaces::srv::SetMode::Request> request,
|
||||
std::shared_ptr<rm_interfaces::srv::SetMode::Response> response);
|
||||
|
||||
// Dynamic Parameter
|
||||
rcl_interfaces::msg::SetParametersResult
|
||||
onSetParameters(std::vector<rclcpp::Parameter> parameters);
|
||||
rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr
|
||||
on_set_parameters_callback_handle_;
|
||||
|
||||
// Heartbeat
|
||||
HeartBeatPublisher::SharedPtr heartbeat_;
|
||||
|
||||
// Armor Detector
|
||||
std::unique_ptr<Detector> detector_;
|
||||
|
||||
// Pose Solver
|
||||
bool use_ba_;
|
||||
std::unique_ptr<ArmorPoseEstimator> armor_pose_estimator_;
|
||||
|
||||
// Detected armors publisher
|
||||
rm_interfaces::msg::Armors armors_msg_;
|
||||
rclcpp::Publisher<rm_interfaces::msg::Armors>::SharedPtr armors_pub_;
|
||||
|
||||
// Visualization marker publisher
|
||||
visualization_msgs::msg::Marker armor_marker_;
|
||||
visualization_msgs::msg::Marker text_marker_;
|
||||
visualization_msgs::msg::MarkerArray marker_array_;
|
||||
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr
|
||||
marker_pub_;
|
||||
|
||||
// Camera info part
|
||||
rclcpp::Subscription<sensor_msgs::msg::CameraInfo>::SharedPtr cam_info_sub_;
|
||||
cv::Point2f cam_center_;
|
||||
std::shared_ptr<sensor_msgs::msg::CameraInfo> cam_info_;
|
||||
|
||||
// Image subscription
|
||||
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr img_sub_;
|
||||
|
||||
// Target subscription
|
||||
// rclcpp::Subscription<rm_interfaces::msg::Target>::SharedPtr target_sub_;
|
||||
// rm_interfaces::msg::Target::SharedPtr tracked_target_;
|
||||
std::deque<Armor> tracked_armors_;
|
||||
|
||||
// ReceiveData subscripiton
|
||||
std::string odom_frame_;
|
||||
std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
|
||||
std::shared_ptr<tf2_ros::TransformListener> tf2_listener_;
|
||||
|
||||
// Async image processing
|
||||
std::mutex queue_mutex_;
|
||||
std::condition_variable queue_cv_;
|
||||
std::deque<PendingFrame> frame_queue_;
|
||||
size_t max_queue_size_ = 3;
|
||||
bool stop_processing_ = false;
|
||||
int process_every_n_frames_ = 1;
|
||||
std::thread image_processing_thread_;
|
||||
|
||||
// Shared processing state
|
||||
std::mutex processing_mutex_;
|
||||
|
||||
// Enable/Disable Armor Detector
|
||||
rclcpp::Service<rm_interfaces::srv::SetMode>::SharedPtr set_mode_srv_;
|
||||
|
||||
// Debug information
|
||||
bool debug_;
|
||||
int debug_log_interval_frames_ = 30;
|
||||
bool debug_terminal_log_ = true;
|
||||
bool debug_markers_ = true;
|
||||
bool debug_lights_msg_ = true;
|
||||
bool debug_armors_msg_ = true;
|
||||
bool debug_binary_img_ = true;
|
||||
bool debug_number_img_ = true;
|
||||
bool debug_result_img_ = true;
|
||||
bool debug_lights_pub_active_ = false;
|
||||
bool debug_armors_pub_active_ = false;
|
||||
bool debug_binary_pub_active_ = false;
|
||||
bool debug_number_pub_active_ = false;
|
||||
bool debug_result_pub_active_ = false;
|
||||
std::atomic<uint64_t> input_frame_counter_{0};
|
||||
std::atomic<uint64_t> debug_log_counter_{0};
|
||||
int tf_error_log_interval_ms_ = 1000;
|
||||
std::mutex tf_error_log_mutex_;
|
||||
std::chrono::steady_clock::time_point last_tf_error_log_time_;
|
||||
std::atomic<uint64_t> tf_error_suppressed_counter_{0};
|
||||
std::shared_ptr<rclcpp::ParameterEventHandler> debug_param_sub_;
|
||||
std::shared_ptr<rclcpp::ParameterCallbackHandle> debug_cb_handle_;
|
||||
rclcpp::TimerBase::SharedPtr debug_publishers_refresh_timer_;
|
||||
std::atomic<bool> debug_publishers_refresh_requested_{false};
|
||||
rclcpp::Publisher<rm_interfaces::msg::DebugLights>::SharedPtr
|
||||
lights_data_pub_;
|
||||
rclcpp::Publisher<rm_interfaces::msg::DebugArmors>::SharedPtr
|
||||
armors_data_pub_;
|
||||
image_transport::Publisher binary_img_pub_;
|
||||
image_transport::Publisher number_img_pub_;
|
||||
image_transport::Publisher result_img_pub_;
|
||||
};
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
|
||||
#endif // ARMOR_DETECTOR_DETECTOR_NODE_HPP_
|
||||
@@ -0,0 +1,62 @@
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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 ARMOR_DETECTOR_ARMOR_POSE_ESTIMATOR_HPP_
|
||||
#define ARMOR_DETECTOR_ARMOR_POSE_ESTIMATOR_HPP_
|
||||
|
||||
// std
|
||||
#include <array>
|
||||
#include <memory>
|
||||
#include <vector>
|
||||
// OpenCV
|
||||
#include <opencv2/opencv.hpp>
|
||||
// Eigen
|
||||
#include <Eigen/Dense>
|
||||
// ros2
|
||||
#include <geometry_msgs/msg/pose.hpp>
|
||||
#include <rclcpp/rclcpp.hpp>
|
||||
#include <sensor_msgs/msg/camera_info.hpp>
|
||||
#include <tf2_ros/buffer.h>
|
||||
// project
|
||||
#include "armor_detector/ba_solver.hpp"
|
||||
#include "rm_interfaces/msg/armor.hpp"
|
||||
#include "rm_utils/math/pnp_solver.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
class ArmorPoseEstimator {
|
||||
public:
|
||||
explicit ArmorPoseEstimator(sensor_msgs::msg::CameraInfo::SharedPtr camera_info);
|
||||
|
||||
std::vector<rm_interfaces::msg::Armor> extractArmorPoses(const std::vector<Armor> &armors,
|
||||
Eigen::Matrix3d R_imu_camera);
|
||||
|
||||
void enableBA(bool enable) { use_ba_ = enable; }
|
||||
|
||||
private:
|
||||
// Select the best PnP solution according to the armor's direction in image, only available for SOLVEPNP_IPPE
|
||||
void sortPnPResult(const Armor &armor, std::vector<cv::Mat> &rvecs,
|
||||
std::vector<cv::Mat> &tvecs) const;
|
||||
|
||||
// Convert a rotation matrix to RPY
|
||||
static Eigen::Vector3d rotationMatrixToRPY(const Eigen::Matrix3d &R);
|
||||
|
||||
bool use_ba_;
|
||||
|
||||
Eigen::Matrix3d R_gimbal_camera_;
|
||||
|
||||
std::unique_ptr<BaSolver> ba_solver_;
|
||||
std::unique_ptr<PnPSolver> pnp_solver_;
|
||||
};
|
||||
} // namespace fyt::auto_aim
|
||||
#endif // ARMOR_POSE_ESTIMATOR_HPP_
|
||||
@@ -0,0 +1,66 @@
|
||||
// Created by Labor 2023.8.25
|
||||
// Maintained by Labor, Chengfu Zou
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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 ARMOR_DETECTOR_BA_SOLVER_HPP_
|
||||
#define ARMOR_DETECTOR_BA_SOLVER_HPP_
|
||||
|
||||
// std
|
||||
#include <array>
|
||||
#include <cstddef>
|
||||
#include <tuple>
|
||||
#include <vector>
|
||||
// 3rd party
|
||||
#include <Eigen/Core>
|
||||
#include <Eigen/Dense>
|
||||
#include <opencv2/core.hpp>
|
||||
#include <sophus/so3.hpp>
|
||||
#include <std_msgs/msg/float32.hpp>
|
||||
// g2o
|
||||
#include <g2o/core/base_multi_edge.h>
|
||||
#include <g2o/core/base_vertex.h>
|
||||
#include <g2o/core/optimization_algorithm.h>
|
||||
#include <g2o/core/optimization_algorithm_factory.h>
|
||||
#include <g2o/core/optimization_algorithm_levenberg.h>
|
||||
#include <g2o/core/robust_kernel.h>
|
||||
#include <g2o/core/sparse_optimizer.h>
|
||||
// project
|
||||
#include "armor_detector/graph_optimizer.hpp"
|
||||
#include "armor_detector/types.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
|
||||
// BA algorithm based Optimizer for the armor pose estimation (Particularly for
|
||||
// the Yaw angle)
|
||||
class BaSolver {
|
||||
public:
|
||||
BaSolver(std::array<double, 9> &camera_matrix,
|
||||
std::vector<double> &dist_coeffs);
|
||||
|
||||
// Solve the armor pose using the BA algorithm, return the optimized rotation
|
||||
Eigen::Matrix3d solveBa(const Armor &armor,
|
||||
const Eigen::Vector3d &t_camera_armor,
|
||||
const Eigen::Matrix3d &R_camera_armor,
|
||||
const Eigen::Matrix3d &R_imu_camera) noexcept;
|
||||
|
||||
private:
|
||||
Eigen::Matrix3d K_;
|
||||
g2o::SparseOptimizer optimizer_;
|
||||
g2o::OptimizationAlgorithmProperty solver_property_;
|
||||
g2o::OptimizationAlgorithmLevenberg *lm_algorithm_;
|
||||
};
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
#endif // ARMOR_DETECTOR_BAS_SOLVER_HPP_
|
||||
@@ -0,0 +1,76 @@
|
||||
// Created by Labor 2023.8.25
|
||||
// Maintained by Labor, Chengfu Zou
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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 ARMOR_DETECTOR_GRAPH_OPTIMIZER_HPP_
|
||||
#define ARMOR_DETECTOR_GRAPH_OPTIMIZER_HPP_
|
||||
|
||||
// std
|
||||
#include <array>
|
||||
// g2o
|
||||
#include <g2o/core/auto_differentiation.h>
|
||||
#include <g2o/core/base_binary_edge.h>
|
||||
#include <g2o/core/base_unary_edge.h>
|
||||
#include <g2o/core/base_vertex.h>
|
||||
#include <g2o/core/optimization_algorithm.h>
|
||||
#include <g2o/core/optimization_algorithm_factory.h>
|
||||
#include <g2o/core/sparse_optimizer.h>
|
||||
// 3rd party
|
||||
#include <Eigen/Dense>
|
||||
#include <g2o/types/slam3d/vertex_pointxyz.h>
|
||||
#include <opencv2/core.hpp>
|
||||
#include <sophus/se3.hpp>
|
||||
#include <sophus/so3.hpp>
|
||||
// project
|
||||
#include "armor_detector/types.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
// Vertex of graph optimization algorithm for the yaw angle
|
||||
class VertexYaw : public g2o::BaseVertex<1, double> {
|
||||
public:
|
||||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
|
||||
|
||||
VertexYaw() = default;
|
||||
virtual void setToOriginImpl() override { _estimate = 0; }
|
||||
virtual void oplusImpl(const double *update) override;
|
||||
|
||||
virtual bool read(std::istream &in) override { return true; }
|
||||
virtual bool write(std::ostream &out) const override { return true; }
|
||||
};
|
||||
|
||||
// Edge of graph optimization algorithm for reporjection error calculation using
|
||||
// yaw angle and observation
|
||||
class EdgeProjection : public g2o::BaseBinaryEdge<2, Eigen::Vector2d, VertexYaw,
|
||||
g2o::VertexPointXYZ> {
|
||||
public:
|
||||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
|
||||
using InfoMatrixType = Eigen::Matrix<double, 2, 2>;
|
||||
|
||||
EdgeProjection(const Sophus::SO3d &R_camera_imu, const Sophus::SO3d &R_pitch,
|
||||
const Eigen::Vector3d &t, const Eigen::Matrix3d &K);
|
||||
virtual void computeError() override;
|
||||
|
||||
virtual bool read(std::istream &in) override { return true; }
|
||||
virtual bool write(std::ostream &out) const override { return true; }
|
||||
|
||||
private:
|
||||
Sophus::SO3d R_camera_imu_;
|
||||
Sophus::SO3d R_pitch_;
|
||||
Eigen::Vector3d t_;
|
||||
Eigen::Matrix3d K_;
|
||||
};
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
#endif // ARMOR_DETECTOR_GRAPH_OPTIMIZER_HPP_
|
||||
@@ -0,0 +1,54 @@
|
||||
// Maintained by Shenglin Qin, Chengfu Zou
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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 ARMOR_DETECTOR_LIGHT_CORNER_CORRECTOR_HPP_
|
||||
#define ARMOR_DETECTOR_LIGHT_CORNER_CORRECTOR_HPP_
|
||||
|
||||
// opencv
|
||||
#include <opencv2/opencv.hpp>
|
||||
// project
|
||||
#include "armor_detector/types.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
|
||||
struct SymmetryAxis {
|
||||
cv::Point2f centroid;
|
||||
cv::Point2f direction;
|
||||
float mean_val; // Mean brightness
|
||||
};
|
||||
|
||||
// This class is used to improve the precision of the corner points of the light bar.
|
||||
// First, the PCA algorithm is used to find the symmetry axis of the light bar,
|
||||
// and then along the symmetry axis to find the corner points of the light bar based on the gradient of brightness.
|
||||
class LightCornerCorrector {
|
||||
public:
|
||||
explicit LightCornerCorrector() noexcept {}
|
||||
|
||||
// Correct the corners of the armor's lights
|
||||
void correctCorners(Armor &armor, const cv::Mat &gray_img);
|
||||
|
||||
private:
|
||||
// Find the symmetry axis of the light
|
||||
SymmetryAxis findSymmetryAxis(const cv::Mat &gray_img, const Light &light);
|
||||
|
||||
// Find the corner of the light
|
||||
cv::Point2f findCorner(const cv::Mat &gray_img,
|
||||
const Light &light,
|
||||
const SymmetryAxis &axis,
|
||||
std::string order);
|
||||
};
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
#endif // ARMOR_DETECTOR_LIGHT_CORNER_CORRECTOR_HPP_
|
||||
@@ -0,0 +1,60 @@
|
||||
// Copyright Chen Jun 2023. Licensed under the MIT License.
|
||||
//
|
||||
// Additional modifications and features by Chengfu Zou, Labor. Licensed under Apache License 2.0.
|
||||
//
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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 ARMOR_DETECTOR_NUMBER_CLASSIFIER_HPP_
|
||||
#define ARMOR_DETECTOR_NUMBER_CLASSIFIER_HPP_
|
||||
|
||||
// std
|
||||
#include <cstddef>
|
||||
#include <iostream>
|
||||
#include <map>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
// third party
|
||||
#include <opencv2/opencv.hpp>
|
||||
// project
|
||||
#include "armor_detector/types.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
// Class used to classify the number of the armor, based on the MLP model
|
||||
class NumberClassifier {
|
||||
public:
|
||||
NumberClassifier(const std::string &model_path,
|
||||
const std::string &label_path,
|
||||
const double threshold,
|
||||
const std::vector<std::string> &ignore_classes = {});
|
||||
|
||||
// Extract the roi image of number from the src
|
||||
cv::Mat extractNumber(const cv::Mat &src, const Armor &armor) const noexcept;
|
||||
|
||||
// Classify the number of the armor
|
||||
void classify(const cv::Mat &src, Armor &armor) noexcept;
|
||||
|
||||
// Erase the ignore classes
|
||||
void eraseIgnoreClasses(std::vector<Armor> &armors) noexcept;
|
||||
|
||||
double threshold;
|
||||
|
||||
private:
|
||||
std::mutex mutex_;
|
||||
cv::dnn::Net net_;
|
||||
std::vector<std::string> class_names_;
|
||||
std::vector<std::string> ignore_classes_;
|
||||
};
|
||||
} // namespace fyt::auto_aim
|
||||
#endif // ARMOR_DETECTOR_NUMBER_CLASSIFIER_HPP_
|
||||
177
src/rm_auto_aim/armor_detector/include/armor_detector/types.hpp
Normal file
@@ -0,0 +1,177 @@
|
||||
// Created by Chengfu Zou on 2023.10.26
|
||||
// Maintained by Chengfu Zou
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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 ARMOR_DETECTOR_TYPES_HPP_
|
||||
#define ARMOR_DETECTOR_TYPES_HPP_
|
||||
|
||||
// std
|
||||
#include <algorithm>
|
||||
#include <numeric>
|
||||
#include <string>
|
||||
// 3rd party
|
||||
#include <Eigen/Dense>
|
||||
#include <opencv2/core.hpp>
|
||||
#include <opencv2/core/types.hpp>
|
||||
#include <opencv2/imgproc.hpp>
|
||||
#include <sophus/so3.hpp>
|
||||
// project
|
||||
#include "rm_utils/assert.hpp"
|
||||
#include "rm_utils/common.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
|
||||
// Armor size, Unit: m
|
||||
constexpr double SMALL_ARMOR_WIDTH = 133.0 / 1000.0; // 135
|
||||
constexpr double SMALL_ARMOR_HEIGHT = 50.0 / 1000.0; // 55
|
||||
constexpr double LARGE_ARMOR_WIDTH = 225.0 / 1000.0;
|
||||
constexpr double LARGE_ARMOR_HEIGHT = 50.0 / 1000.0; // 55
|
||||
|
||||
// 15 degree in rad
|
||||
constexpr double FIFTTEN_DEGREE_RAD = 15 * CV_PI / 180;
|
||||
|
||||
// Armor type
|
||||
enum class ArmorType { SMALL, LARGE, INVALID };
|
||||
inline std::string armorTypeToString(const ArmorType &type) {
|
||||
switch (type) {
|
||||
case ArmorType::SMALL:
|
||||
return "small";
|
||||
case ArmorType::LARGE:
|
||||
return "large";
|
||||
default:
|
||||
return "invalid";
|
||||
}
|
||||
}
|
||||
|
||||
// Struct used to store the light bar
|
||||
struct Light : public cv::RotatedRect {
|
||||
Light() = default;
|
||||
explicit Light(const std::vector<cv::Point> &contour)
|
||||
: cv::RotatedRect(cv::minAreaRect(contour)), color(EnemyColor::WHITE) {
|
||||
FYT_ASSERT(contour.size() > 0);
|
||||
|
||||
center = std::accumulate(
|
||||
contour.begin(),
|
||||
contour.end(),
|
||||
cv::Point2f(0, 0),
|
||||
[n = static_cast<float>(contour.size())](const cv::Point2f &a, const cv::Point &b) {
|
||||
return a + cv::Point2f(b.x, b.y) / n;
|
||||
});
|
||||
|
||||
cv::Point2f p[4];
|
||||
this->points(p);
|
||||
std::sort(p, p + 4, [](const cv::Point2f &a, const cv::Point2f &b) { return a.y < b.y; });
|
||||
top = (p[0] + p[1]) / 2;
|
||||
bottom = (p[2] + p[3]) / 2;
|
||||
|
||||
length = cv::norm(top - bottom);
|
||||
width = cv::norm(p[0] - p[1]);
|
||||
|
||||
axis = top - bottom;
|
||||
axis = axis / cv::norm(axis);
|
||||
|
||||
// Calculate the tilt angle
|
||||
// The angle is the angle between the light bar and the horizontal line
|
||||
tilt_angle = std::atan2(std::abs(top.x - bottom.x), std::abs(top.y - bottom.y));
|
||||
tilt_angle = tilt_angle / CV_PI * 180;
|
||||
}
|
||||
|
||||
// Constructor using fitLine results
|
||||
explicit Light(
|
||||
cv::RotatedRect box, cv::Point2f top, cv::Point2f bottom, double length, double width)
|
||||
: cv::RotatedRect(box)
|
||||
, color(EnemyColor::WHITE)
|
||||
, top(top)
|
||||
, bottom(bottom)
|
||||
, length(length)
|
||||
, width(width) {
|
||||
center = (top + bottom) / 2;
|
||||
axis = top - bottom;
|
||||
axis = axis / cv::norm(axis);
|
||||
tilt_angle = std::atan2(std::abs(top.x - bottom.x), std::abs(top.y - bottom.y));
|
||||
tilt_angle = tilt_angle / CV_PI * 180;
|
||||
}
|
||||
|
||||
EnemyColor color;
|
||||
cv::Point2f top, bottom, center;
|
||||
cv::Point2f axis;
|
||||
double length;
|
||||
double width;
|
||||
float tilt_angle;
|
||||
};
|
||||
|
||||
// Struct used to store the armor
|
||||
struct Armor {
|
||||
static constexpr const int N_LANDMARKS = 6;
|
||||
static constexpr const int N_LANDMARKS_2 = N_LANDMARKS * 2;
|
||||
Armor() = default;
|
||||
Armor(const Light &l1, const Light &l2) {
|
||||
if (l1.center.x < l2.center.x) {
|
||||
left_light = l1, right_light = l2;
|
||||
} else {
|
||||
left_light = l2, right_light = l1;
|
||||
}
|
||||
|
||||
center = (left_light.center + right_light.center) / 2;
|
||||
}
|
||||
|
||||
// Build the points in the object coordinate system, start from bottom left in
|
||||
// clockwise order
|
||||
template <typename PointType>
|
||||
static inline std::vector<PointType> buildObjectPoints(const double &w,
|
||||
const double &h) noexcept {
|
||||
if constexpr (N_LANDMARKS == 4) {
|
||||
return {PointType(0, w / 2, -h / 2),
|
||||
PointType(0, w / 2, h / 2),
|
||||
PointType(0, -w / 2, h / 2),
|
||||
PointType(0, -w / 2, -h / 2)};
|
||||
} else {
|
||||
return {PointType(0, w / 2, -h / 2),
|
||||
PointType(0, w / 2, 0),
|
||||
PointType(0, w / 2, h / 2),
|
||||
PointType(0, -w / 2, h / 2),
|
||||
PointType(0, -w / 2, 0),
|
||||
PointType(0, -w / 2, -h / 2)};
|
||||
}
|
||||
}
|
||||
|
||||
// Landmarks start from bottom left in clockwise order
|
||||
std::vector<cv::Point2f> landmarks() const {
|
||||
if constexpr (N_LANDMARKS == 4) {
|
||||
return {left_light.bottom, left_light.top, right_light.top, right_light.bottom};
|
||||
} else {
|
||||
return {left_light.bottom,
|
||||
left_light.center,
|
||||
left_light.top,
|
||||
right_light.top,
|
||||
right_light.center,
|
||||
right_light.bottom};
|
||||
}
|
||||
}
|
||||
|
||||
// Light pairs part
|
||||
Light left_light, right_light;
|
||||
cv::Point2f center;
|
||||
ArmorType type;
|
||||
|
||||
// Number part
|
||||
cv::Mat number_img;
|
||||
std::string number;
|
||||
float confidence;
|
||||
std::string classfication_result;
|
||||
};
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
#endif // ARMOR_DETECTOR_ARMOR_HPP_
|
||||
9
src/rm_auto_aim/armor_detector/model/label.txt
Normal file
@@ -0,0 +1,9 @@
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
outpost
|
||||
sentry
|
||||
base
|
||||
negative
|
||||
BIN
src/rm_auto_aim/armor_detector/model/lenet.onnx
Normal file
BIN
src/rm_auto_aim/armor_detector/model/mlp.onnx
Normal file
46
src/rm_auto_aim/armor_detector/package.xml
Normal file
@@ -0,0 +1,46 @@
|
||||
<?xml version="1.0"?>
|
||||
<?xml-model
|
||||
href="http://download.ros.org/schema/package_format3.xsd"
|
||||
schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<package format="3">
|
||||
<name>armor_detector</name>
|
||||
<version>0.1.0</version>
|
||||
<description>A template for ROS packages.</description>
|
||||
<maintainer email="chen.junn@outlook.com">Chen Jun</maintainer>
|
||||
<license>BSD</license>
|
||||
<url type="website">https://github.com/chenjunnn/rm_auto_aim</url>
|
||||
<url type="bugtracker">https://github.com/chenjunnn/rm_auto_aim/issues</url>
|
||||
<author email="chen.junn@outlook.com">Chen Jun</author>
|
||||
|
||||
<!-- buildtool_depend: dependencies of the build process -->
|
||||
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||
|
||||
<!-- depend: build, export, and execution dependency -->
|
||||
<depend>rclcpp</depend>
|
||||
<depend>rclcpp_components</depend>
|
||||
<depend>sensor_msgs</depend>
|
||||
<depend>geometry_msgs</depend>
|
||||
<depend>std_srvs</depend>
|
||||
<depend>visualization_msgs</depend>
|
||||
<depend>message_filters</depend>
|
||||
<depend>cv_bridge</depend>
|
||||
<depend>image_transport</depend>
|
||||
<depend>image_transport_plugins</depend>
|
||||
<depend>rm_interfaces</depend>
|
||||
<depend>vision_opencv</depend>
|
||||
<depend>tf2</depend>
|
||||
<depend>eigen</depend>
|
||||
<depend>fmt</depend>
|
||||
<depend>tf2_ros</depend>
|
||||
<depend>tf2_geometry_msgs</depend>
|
||||
<depend>rm_utils</depend>
|
||||
|
||||
<test_depend>ament_lint_auto</test_depend>
|
||||
<test_depend>ament_lint_common</test_depend>
|
||||
<test_depend>ament_cmake_gtest</test_depend>
|
||||
<test_depend>ament_cmake_clang_format</test_depend>
|
||||
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
</export>
|
||||
</package>
|
||||
351
src/rm_auto_aim/armor_detector/src/armor_detector.cpp
Normal file
@@ -0,0 +1,351 @@
|
||||
// Copyright Chen Jun 2023. Licensed under the MIT License.
|
||||
//
|
||||
// Additional modifications and features by Chengfu Zou, Labor. Licensed under Apache License 2.0.
|
||||
//
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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.
|
||||
|
||||
#include "armor_detector/armor_detector.hpp"
|
||||
// std
|
||||
#include <algorithm>
|
||||
#include <cmath>
|
||||
#include <vector>
|
||||
// OpenCV
|
||||
#include <opencv2/core.hpp>
|
||||
#include <opencv2/core/base.hpp>
|
||||
#include <opencv2/core/mat.hpp>
|
||||
#include <opencv2/core/types.hpp>
|
||||
#include <opencv2/highgui.hpp>
|
||||
#include <opencv2/imgproc.hpp>
|
||||
// project
|
||||
#include "armor_detector/types.hpp"
|
||||
#include "rm_utils/common.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
Detector::Detector(const int &bin_thres,
|
||||
const EnemyColor &color,
|
||||
const LightParams &l,
|
||||
const ArmorParams &a)
|
||||
: binary_thres(bin_thres), detect_color(color), light_params(l), armor_params(a) {}
|
||||
|
||||
std::vector<Armor> Detector::detect(const cv::Mat &input) noexcept {
|
||||
// 1. Preprocess the image
|
||||
binary_img = preprocessImage(input);
|
||||
// 2. Find lights
|
||||
lights_ = findLights(input, binary_img);
|
||||
// 3. Match lights to armors
|
||||
armors_ = matchLights(lights_);
|
||||
|
||||
if (!armors_.empty() && classifier != nullptr) {
|
||||
// Sequential processing here avoids nested parallelism with node-level workers.
|
||||
for (auto &armor : armors_) {
|
||||
// 4. Extract the number image
|
||||
armor.number_img = classifier->extractNumber(input, armor);
|
||||
// 5. Do classification
|
||||
classifier->classify(input, armor);
|
||||
// 6. Correct the corners of the armor
|
||||
if (corner_corrector != nullptr) {
|
||||
corner_corrector->correctCorners(armor, gray_img_);
|
||||
}
|
||||
}
|
||||
|
||||
// 7. Erase the armors with ignore classes
|
||||
classifier->eraseIgnoreClasses(armors_);
|
||||
}
|
||||
|
||||
return armors_;
|
||||
}
|
||||
|
||||
cv::Mat Detector::preprocessImage(const cv::Mat &rgb_img) noexcept {
|
||||
cv::cvtColor(rgb_img, gray_img_, cv::COLOR_RGB2GRAY);
|
||||
|
||||
cv::Mat binary_img;
|
||||
cv::threshold(gray_img_, binary_img, binary_thres, 255, cv::THRESH_BINARY);
|
||||
|
||||
return binary_img;
|
||||
}
|
||||
|
||||
std::vector<Light> Detector::findLights(const cv::Mat &rgb_img,
|
||||
const cv::Mat &binary_img) noexcept {
|
||||
using std::vector;
|
||||
vector<vector<cv::Point>> contours;
|
||||
vector<cv::Vec4i> hierarchy;
|
||||
cv::findContours(binary_img, contours, hierarchy, cv::RETR_EXTERNAL, cv::CHAIN_APPROX_SIMPLE);
|
||||
|
||||
vector<Light> lights;
|
||||
lights.reserve(contours.size());
|
||||
if (enable_debug) {
|
||||
debug_lights.data.clear();
|
||||
}
|
||||
|
||||
for (const auto &contour : contours) {
|
||||
if (contour.size() < 6) continue;
|
||||
|
||||
Light light;
|
||||
std::vector<cv::Point> points;
|
||||
|
||||
if (light_params.use_fit_line) {
|
||||
auto b_rect = cv::boundingRect(contour);
|
||||
auto r_rect = cv::minAreaRect(contour);
|
||||
// Fit line (least-squares) for more accurate top/bottom
|
||||
cv::Mat mask = cv::Mat::zeros(b_rect.size(), CV_8UC1);
|
||||
std::vector<cv::Point> mask_contour;
|
||||
mask_contour.reserve(contour.size());
|
||||
for (const auto &p : contour) {
|
||||
mask_contour.emplace_back(p - cv::Point(b_rect.x, b_rect.y));
|
||||
}
|
||||
cv::fillPoly(mask, {mask_contour}, 255);
|
||||
cv::findNonZero(mask, points);
|
||||
|
||||
// Filter by fill ratio, similar to attachment but simplified
|
||||
if (points.empty()) continue;
|
||||
|
||||
cv::Vec4f return_param;
|
||||
cv::fitLine(points, return_param, cv::DIST_L2, 0, 0.01, 0.01);
|
||||
cv::Point2f top, bottom;
|
||||
if (int(return_param[0] * 100) == 100 || int(return_param[1] * 100) == 0) {
|
||||
top = cv::Point2f(b_rect.x + b_rect.width / 2, b_rect.y);
|
||||
bottom = cv::Point2f(b_rect.x + b_rect.width / 2, b_rect.y + b_rect.height);
|
||||
} else {
|
||||
auto k = return_param[1] / return_param[0];
|
||||
auto b = (return_param[3] + b_rect.y) - k * (return_param[2] + b_rect.x);
|
||||
top = cv::Point2f((b_rect.y - b) / k, b_rect.y);
|
||||
bottom = cv::Point2f((b_rect.y + b_rect.height - b) / k, b_rect.y + b_rect.height);
|
||||
}
|
||||
|
||||
// Use the short side of minAreaRect as width
|
||||
double width = std::min(r_rect.size.width, r_rect.size.height);
|
||||
double length = cv::norm(top - bottom);
|
||||
light = Light(r_rect, top, bottom, length, width);
|
||||
} else {
|
||||
// Disable least-squares fitting: fall back to minAreaRect-based endpoints
|
||||
light = Light(contour);
|
||||
}
|
||||
|
||||
if (isLight(light)) {
|
||||
int sum_r = 0;
|
||||
int sum_b = 0;
|
||||
int sample_count = 0;
|
||||
if (light_params.use_fit_line && !points.empty()) {
|
||||
// fit-line mode keeps local contour pixels in points; convert to global by boundingRect offset
|
||||
auto b_rect = cv::boundingRect(contour);
|
||||
for (const auto &point : points) {
|
||||
const int x = point.x + b_rect.x;
|
||||
const int y = point.y + b_rect.y;
|
||||
const auto &pixel = rgb_img.at<cv::Vec3b>(y, x);
|
||||
sum_r += pixel[0];
|
||||
sum_b += pixel[2];
|
||||
++sample_count;
|
||||
}
|
||||
} else {
|
||||
// no-fit-line mode: use contour points directly to avoid expensive mask + findNonZero
|
||||
for (const auto &point : contour) {
|
||||
const auto &pixel = rgb_img.at<cv::Vec3b>(point.y, point.x);
|
||||
sum_r += pixel[0];
|
||||
sum_b += pixel[2];
|
||||
++sample_count;
|
||||
}
|
||||
}
|
||||
|
||||
if (sample_count > 0 &&
|
||||
std::abs(sum_r - sum_b) / sample_count > light_params.color_diff_thresh) {
|
||||
light.color = sum_r > sum_b ? EnemyColor::RED : EnemyColor::BLUE;
|
||||
}
|
||||
lights.emplace_back(light);
|
||||
}
|
||||
}
|
||||
std::sort(lights.begin(), lights.end(), [](const Light &l1, const Light &l2) {
|
||||
return l1.center.x < l2.center.x;
|
||||
});
|
||||
return lights;
|
||||
}
|
||||
|
||||
bool Detector::isLight(const Light &light) noexcept {
|
||||
// The ratio of light (short side / long side)
|
||||
float ratio = light.width / light.length;
|
||||
bool ratio_ok = light_params.min_ratio < ratio && ratio < light_params.max_ratio;
|
||||
|
||||
bool angle_ok = light.tilt_angle < light_params.max_angle;
|
||||
|
||||
bool is_light = ratio_ok && angle_ok;
|
||||
|
||||
if (enable_debug) {
|
||||
// Fill in debug information
|
||||
rm_interfaces::msg::DebugLight light_data;
|
||||
light_data.center_x = light.center.x;
|
||||
light_data.ratio = ratio;
|
||||
light_data.angle = light.tilt_angle;
|
||||
light_data.is_light = is_light;
|
||||
this->debug_lights.data.emplace_back(light_data);
|
||||
}
|
||||
|
||||
return is_light;
|
||||
}
|
||||
|
||||
std::vector<Armor> Detector::matchLights(const std::vector<Light> &lights) noexcept {
|
||||
std::vector<Armor> armors;
|
||||
if (enable_debug) {
|
||||
this->debug_armors.data.clear();
|
||||
}
|
||||
// Loop all the pairing of lights
|
||||
for (auto light_1 = lights.begin(); light_1 != lights.end(); light_1++) {
|
||||
if (light_1->color != detect_color) continue;
|
||||
double max_iter_width = light_1->length * armor_params.max_large_center_distance;
|
||||
|
||||
for (auto light_2 = light_1 + 1; light_2 != lights.end(); light_2++) {
|
||||
if (light_2->color != detect_color) continue;
|
||||
if (containLight(light_1 - lights.begin(), light_2 - lights.begin(), lights)) {
|
||||
continue;
|
||||
}
|
||||
if (light_2->center.x - light_1->center.x > max_iter_width) break;
|
||||
|
||||
auto type = isArmor(*light_1, *light_2);
|
||||
if (type != ArmorType::INVALID) {
|
||||
auto armor = Armor(*light_1, *light_2);
|
||||
armor.type = type;
|
||||
armors.emplace_back(armor);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return armors;
|
||||
}
|
||||
|
||||
// Check if there is another light in the boundingRect formed by the 2 lights
|
||||
bool Detector::containLight(const int i, const int j, const std::vector<Light> &lights) noexcept {
|
||||
const Light &light_1 = lights.at(i), light_2 = lights.at(j);
|
||||
auto points = std::vector<cv::Point2f>{light_1.top, light_1.bottom, light_2.top, light_2.bottom};
|
||||
auto bounding_rect = cv::boundingRect(points);
|
||||
double avg_length = (light_1.length + light_2.length) / 2.0;
|
||||
double avg_width = (light_1.width + light_2.width) / 2.0;
|
||||
// Only check lights in between
|
||||
for (int k = i + 1; k < j; k++) {
|
||||
const Light &test_light = lights.at(k);
|
||||
|
||||
// 防止数字干扰
|
||||
if (test_light.width > 2 * avg_width) {
|
||||
continue;
|
||||
}
|
||||
// 防止红点准星或弹丸干扰
|
||||
if (test_light.length < 0.5 * avg_length) {
|
||||
continue;
|
||||
}
|
||||
|
||||
if (bounding_rect.contains(test_light.top) || bounding_rect.contains(test_light.bottom) ||
|
||||
bounding_rect.contains(test_light.center)) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
ArmorType Detector::isArmor(const Light &light_1, const Light &light_2) noexcept {
|
||||
// Ratio of the length of 2 lights (short side / long side)
|
||||
float light_length_ratio = light_1.length < light_2.length ? light_1.length / light_2.length
|
||||
: light_2.length / light_1.length;
|
||||
bool light_ratio_ok = light_length_ratio > armor_params.min_light_ratio;
|
||||
|
||||
// Distance between the center of 2 lights (unit : light length)
|
||||
float avg_light_length = (light_1.length + light_2.length) / 2;
|
||||
float center_distance = cv::norm(light_1.center - light_2.center) / avg_light_length;
|
||||
bool center_distance_ok = (armor_params.min_small_center_distance <= center_distance &&
|
||||
center_distance < armor_params.max_small_center_distance) ||
|
||||
(armor_params.min_large_center_distance <= center_distance &&
|
||||
center_distance < armor_params.max_large_center_distance);
|
||||
|
||||
// Angle of light center connection
|
||||
cv::Point2f diff = light_1.center - light_2.center;
|
||||
float angle = std::abs(std::atan(diff.y / diff.x)) / CV_PI * 180;
|
||||
bool angle_ok = angle < armor_params.max_angle;
|
||||
|
||||
bool is_armor = light_ratio_ok && center_distance_ok && angle_ok;
|
||||
|
||||
// Judge armor type
|
||||
ArmorType type;
|
||||
if (is_armor) {
|
||||
// 优先认为是小装甲板,提高大装甲板的判断阈值
|
||||
// 标准值:小装甲板 ~2.5,大装甲板 ~4.1
|
||||
// 将阈值设为 3.4 可以减少因灯条拟合变短导致的比值偏大从而误判为大装甲板的情况
|
||||
type = center_distance > 3.5 ? ArmorType::LARGE : ArmorType::SMALL;
|
||||
} else {
|
||||
type = ArmorType::INVALID;
|
||||
}
|
||||
|
||||
if (enable_debug) {
|
||||
// Fill in debug information
|
||||
rm_interfaces::msg::DebugArmor armor_data;
|
||||
armor_data.type = armorTypeToString(type);
|
||||
armor_data.center_x = (light_1.center.x + light_2.center.x) / 2;
|
||||
armor_data.light_ratio = light_length_ratio;
|
||||
armor_data.center_distance = center_distance;
|
||||
armor_data.angle = angle;
|
||||
this->debug_armors.data.emplace_back(armor_data);
|
||||
}
|
||||
|
||||
return type;
|
||||
}
|
||||
|
||||
cv::Mat Detector::getAllNumbersImage() const noexcept {
|
||||
if (armors_.empty()) {
|
||||
return cv::Mat(cv::Size(20, 28), CV_8UC1);
|
||||
} else {
|
||||
std::vector<cv::Mat> number_imgs;
|
||||
number_imgs.reserve(armors_.size());
|
||||
for (auto &armor : armors_) {
|
||||
number_imgs.emplace_back(armor.number_img);
|
||||
}
|
||||
cv::Mat all_num_img;
|
||||
cv::vconcat(number_imgs, all_num_img);
|
||||
return all_num_img;
|
||||
}
|
||||
}
|
||||
|
||||
void Detector::drawResults(cv::Mat &img) const noexcept {
|
||||
// Draw Lights
|
||||
|
||||
// for (const auto &light : lights_) {
|
||||
// auto line_color =
|
||||
// light.color == EnemyColor::RED ? cv::Scalar(0, 255, 255) : cv::Scalar(255, 255, 0);
|
||||
// // cv::ellipse(img, light, line_color, 2);
|
||||
// cv::line(img, light.top, light.bottom, line_color, 1);
|
||||
// }
|
||||
|
||||
// Draw armors
|
||||
for (const auto &armor : armors_) {
|
||||
// cv::line(img, armor.left_light.top, armor.right_light.bottom, cv::Scalar(0, 255, 0), 1);
|
||||
// cv::line(img, armor.left_light.bottom, armor.right_light.top, cv::Scalar(0, 255, 0), 1);
|
||||
|
||||
cv::line(
|
||||
img, armor.left_light.top, armor.left_light.bottom, cv::Scalar(0, 255, 0), 1, cv::LINE_AA);
|
||||
cv::line(
|
||||
img, armor.right_light.bottom, armor.right_light.top, cv::Scalar(0, 255, 0), 1, cv::LINE_AA);
|
||||
cv::line(
|
||||
img, armor.left_light.top, armor.right_light.top, cv::Scalar(0, 255, 0), 1, cv::LINE_AA);
|
||||
cv::line(img,
|
||||
armor.right_light.bottom,
|
||||
armor.left_light.bottom,
|
||||
cv::Scalar(0, 255, 0),
|
||||
1,
|
||||
cv::LINE_AA);
|
||||
}
|
||||
// Show numbers and confidence
|
||||
for (const auto &armor : armors_) {
|
||||
std::string text =
|
||||
fmt::format("{} {}", armorTypeToString(armor.type), armor.classfication_result);
|
||||
cv::putText(
|
||||
img, text, armor.left_light.top, cv::FONT_HERSHEY_SIMPLEX, 0.8, cv::Scalar(0, 255, 255), 2);
|
||||
}
|
||||
}
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
685
src/rm_auto_aim/armor_detector/src/armor_detector_node.cpp
Normal file
@@ -0,0 +1,685 @@
|
||||
// Copyright Chen Jun 2023. Licensed under the MIT License.
|
||||
//
|
||||
// Additional modifications and features by Chengfu Zou, Labor. Licensed under
|
||||
// Apache License 2.0.
|
||||
//
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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.
|
||||
|
||||
// std
|
||||
#include <algorithm>
|
||||
#include <chrono>
|
||||
#include <cstddef>
|
||||
#include <filesystem>
|
||||
#include <functional>
|
||||
#include <iomanip>
|
||||
#include <map>
|
||||
#include <memory>
|
||||
#include <numeric>
|
||||
#include <sstream>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
// ros2
|
||||
#include <cv_bridge/cv_bridge.h>
|
||||
#include <tf2/LinearMath/Matrix3x3.h>
|
||||
#include <tf2/LinearMath/Quaternion.h>
|
||||
#include <tf2/convert.h>
|
||||
#include <tf2/time.h>
|
||||
#include <tf2_ros/buffer.h>
|
||||
#include <tf2_ros/create_timer_ros.h>
|
||||
|
||||
#include <image_transport/image_transport.hpp>
|
||||
#include <rclcpp/qos.hpp>
|
||||
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
|
||||
// third party
|
||||
#include <opencv2/core.hpp>
|
||||
#include <opencv2/highgui.hpp>
|
||||
#include <opencv2/imgproc.hpp>
|
||||
// project
|
||||
#include "armor_detector/armor_detector_node.hpp"
|
||||
#include "armor_detector/ba_solver.hpp"
|
||||
#include "armor_detector/types.hpp"
|
||||
#include "rm_utils/assert.hpp"
|
||||
#include "rm_utils/common.hpp"
|
||||
#include "rm_utils/logger/log.hpp"
|
||||
#include "rm_utils/math/pnp_solver.hpp"
|
||||
#include "rm_utils/math/utils.hpp"
|
||||
#include "rm_utils/url_resolver.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
namespace {
|
||||
|
||||
double durationMs(const std::chrono::steady_clock::duration &duration) {
|
||||
return std::chrono::duration<double, std::milli>(duration).count();
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
ArmorDetectorNode::ArmorDetectorNode(const rclcpp::NodeOptions &options)
|
||||
: Node("armor_detector", options) {
|
||||
FYT_REGISTER_LOGGER("armor_detector", "~/fyt2024-log", INFO);
|
||||
FYT_INFO("armor_detector", "Starting ArmorDetectorNode!");
|
||||
// Detector
|
||||
detector_ = initDetector();
|
||||
|
||||
const int max_queue_size_param = static_cast<int>(this->declare_parameter("max_queue_size", 3));
|
||||
max_queue_size_ = static_cast<size_t>(std::max(1, max_queue_size_param));
|
||||
process_every_n_frames_ =
|
||||
std::max(1, static_cast<int>(this->declare_parameter("process_every_n_frames", 1)));
|
||||
|
||||
// Tricks to make pose more accurate
|
||||
use_ba_ = this->declare_parameter("use_ba", true);
|
||||
|
||||
// Armors Publisher
|
||||
armors_pub_ = this->create_publisher<rm_interfaces::msg::Armors>("armor_detector/armors",
|
||||
rclcpp::SensorDataQoS());
|
||||
|
||||
// Transform initialize
|
||||
odom_frame_ = this->declare_parameter("target_frame", "odom");
|
||||
|
||||
// Visualization Marker Publisher
|
||||
// See http://wiki.ros.org/rviz/DisplayTypes/Marker
|
||||
armor_marker_.ns = "armors";
|
||||
armor_marker_.action = visualization_msgs::msg::Marker::ADD;
|
||||
armor_marker_.type = visualization_msgs::msg::Marker::CUBE;
|
||||
armor_marker_.scale.x = 0.03;
|
||||
armor_marker_.scale.y = 0.15;
|
||||
armor_marker_.scale.z = 0.12;
|
||||
armor_marker_.color.a = 1.0;
|
||||
armor_marker_.color.r = 1.0;
|
||||
armor_marker_.lifetime = rclcpp::Duration::from_seconds(0.1);
|
||||
|
||||
text_marker_.ns = "classification";
|
||||
text_marker_.action = visualization_msgs::msg::Marker::ADD;
|
||||
text_marker_.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING;
|
||||
text_marker_.scale.z = 0.1;
|
||||
text_marker_.color.a = 1.0;
|
||||
text_marker_.color.r = 1.0;
|
||||
text_marker_.color.g = 1.0;
|
||||
text_marker_.color.b = 1.0;
|
||||
text_marker_.lifetime = rclcpp::Duration::from_seconds(0.1);
|
||||
|
||||
marker_pub_ =
|
||||
this->create_publisher<visualization_msgs::msg::MarkerArray>("armor_detector/marker", 10);
|
||||
|
||||
// Debug Publishers
|
||||
debug_ = this->declare_parameter("debug", false);
|
||||
debug_log_interval_frames_ =
|
||||
std::max(1, static_cast<int>(this->declare_parameter("debug_log_interval_frames", 30)));
|
||||
debug_terminal_log_ = this->declare_parameter("debug.enable_terminal_log", true);
|
||||
debug_markers_ = this->declare_parameter("debug.enable_markers", true);
|
||||
debug_lights_msg_ = this->declare_parameter("debug.enable_lights_msg", true);
|
||||
debug_armors_msg_ = this->declare_parameter("debug.enable_armors_msg", true);
|
||||
debug_binary_img_ = this->declare_parameter("debug.enable_binary_img", true);
|
||||
debug_number_img_ = this->declare_parameter("debug.enable_number_img", true);
|
||||
debug_result_img_ = this->declare_parameter("debug.enable_result_img", true);
|
||||
tf_error_log_interval_ms_ =
|
||||
std::max(1, static_cast<int>(this->declare_parameter("tf_error_log_interval_ms", 1000)));
|
||||
if (debug_) {
|
||||
createDebugPublishers();
|
||||
}
|
||||
debug_publishers_refresh_timer_ = this->create_wall_timer(
|
||||
std::chrono::milliseconds(100),
|
||||
[this]() { refreshDebugPublishersIfNeeded(); });
|
||||
// Debug param change moniter
|
||||
debug_param_sub_ = std::make_shared<rclcpp::ParameterEventHandler>(this);
|
||||
debug_cb_handle_ =
|
||||
debug_param_sub_->add_parameter_callback("debug", [this](const rclcpp::Parameter &p) {
|
||||
std::lock_guard<std::mutex> lock(processing_mutex_);
|
||||
debug_ = p.as_bool();
|
||||
debug_ ? createDebugPublishers() : destroyDebugPublishers();
|
||||
});
|
||||
|
||||
cam_info_sub_ = this->create_subscription<sensor_msgs::msg::CameraInfo>(
|
||||
"camera_info",
|
||||
rclcpp::SensorDataQoS(),
|
||||
[this](sensor_msgs::msg::CameraInfo::SharedPtr camera_info) {
|
||||
std::lock_guard<std::mutex> lock(processing_mutex_);
|
||||
cam_center_ = cv::Point2f(camera_info->k[2], camera_info->k[5]);
|
||||
cam_info_ = std::make_shared<sensor_msgs::msg::CameraInfo>(*camera_info);
|
||||
// Setup armor pose solver
|
||||
armor_pose_estimator_ = std::make_unique<ArmorPoseEstimator>(cam_info_);
|
||||
armor_pose_estimator_->enableBA(use_ba_);
|
||||
cam_info_sub_.reset();
|
||||
});
|
||||
|
||||
img_sub_ = this->create_subscription<sensor_msgs::msg::Image>(
|
||||
"image_raw",
|
||||
rclcpp::SensorDataQoS(),
|
||||
std::bind(&ArmorDetectorNode::imageCallback, this, std::placeholders::_1));
|
||||
|
||||
// target_sub_ = this->create_subscription<rm_interfaces::msg::Target>(
|
||||
// "armor_solver/target",
|
||||
// rclcpp::SensorDataQoS(),
|
||||
// std::bind(&ArmorDetectorNode::targetCallback, this,
|
||||
// std::placeholders::_1));
|
||||
|
||||
tf2_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
|
||||
auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
|
||||
this->get_node_base_interface(), this->get_node_timers_interface());
|
||||
tf2_buffer_->setCreateTimerInterface(timer_interface);
|
||||
tf2_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf2_buffer_);
|
||||
|
||||
set_mode_srv_ = this->create_service<rm_interfaces::srv::SetMode>(
|
||||
"armor_detector/set_mode",
|
||||
std::bind(
|
||||
&ArmorDetectorNode::setModeCallback, this, std::placeholders::_1, std::placeholders::_2));
|
||||
|
||||
image_processing_thread_ = std::thread(&ArmorDetectorNode::processImageLoop, this);
|
||||
FYT_INFO("armor_detector",
|
||||
"Image worker started: threads=1, max_queue_size={}",
|
||||
max_queue_size_);
|
||||
|
||||
heartbeat_ = HeartBeatPublisher::create(this);
|
||||
}
|
||||
|
||||
ArmorDetectorNode::~ArmorDetectorNode() {
|
||||
{
|
||||
std::lock_guard<std::mutex> lock(queue_mutex_);
|
||||
stop_processing_ = true;
|
||||
}
|
||||
queue_cv_.notify_one();
|
||||
if (image_processing_thread_.joinable()) {
|
||||
image_processing_thread_.join();
|
||||
}
|
||||
}
|
||||
|
||||
void ArmorDetectorNode::imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr img_msg) {
|
||||
if ((input_frame_counter_.fetch_add(1, std::memory_order_relaxed) + 1) %
|
||||
static_cast<uint64_t>(process_every_n_frames_) !=
|
||||
0) {
|
||||
return;
|
||||
}
|
||||
|
||||
auto frame_start = std::chrono::steady_clock::now();
|
||||
{
|
||||
std::lock_guard<std::mutex> lock(queue_mutex_);
|
||||
if (frame_queue_.size() >= max_queue_size_) {
|
||||
frame_queue_.pop_front();
|
||||
}
|
||||
frame_queue_.push_back(PendingFrame{.img_msg = img_msg, .frame_start = frame_start});
|
||||
}
|
||||
queue_cv_.notify_one();
|
||||
}
|
||||
|
||||
void ArmorDetectorNode::processImageLoop() {
|
||||
while (true) {
|
||||
PendingFrame frame;
|
||||
{
|
||||
std::unique_lock<std::mutex> lock(queue_mutex_);
|
||||
queue_cv_.wait(lock, [this]() { return stop_processing_ || !frame_queue_.empty(); });
|
||||
if (stop_processing_ && frame_queue_.empty()) {
|
||||
return;
|
||||
}
|
||||
frame = std::move(frame_queue_.front());
|
||||
frame_queue_.pop_front();
|
||||
}
|
||||
|
||||
processFrame(std::move(frame));
|
||||
}
|
||||
}
|
||||
|
||||
void ArmorDetectorNode::processFrame(PendingFrame frame) {
|
||||
bool debug_enabled = false;
|
||||
bool debug_terminal_log_enabled = false;
|
||||
bool debug_marker_enabled = false;
|
||||
{
|
||||
std::lock_guard<std::mutex> lock(processing_mutex_);
|
||||
debug_enabled = debug_;
|
||||
debug_terminal_log_enabled = debug_terminal_log_;
|
||||
debug_marker_enabled = debug_markers_;
|
||||
}
|
||||
|
||||
auto stage_start = std::chrono::steady_clock::now();
|
||||
Eigen::Matrix3d imu_to_camera = Eigen::Matrix3d::Identity();
|
||||
|
||||
try {
|
||||
rclcpp::Time target_time = frame.img_msg->header.stamp;
|
||||
auto odom_to_gimbal = tf2_buffer_->lookupTransform(
|
||||
odom_frame_, frame.img_msg->header.frame_id, target_time, rclcpp::Duration::from_seconds(0.01));
|
||||
auto msg_q = odom_to_gimbal.transform.rotation;
|
||||
tf2::Quaternion tf_q;
|
||||
tf2::fromMsg(msg_q, tf_q);
|
||||
tf2::Matrix3x3 tf2_matrix = tf2::Matrix3x3(tf_q);
|
||||
imu_to_camera << tf2_matrix.getRow(0)[0], tf2_matrix.getRow(0)[1], tf2_matrix.getRow(0)[2],
|
||||
tf2_matrix.getRow(1)[0], tf2_matrix.getRow(1)[1], tf2_matrix.getRow(1)[2],
|
||||
tf2_matrix.getRow(2)[0], tf2_matrix.getRow(2)[1], tf2_matrix.getRow(2)[2];
|
||||
} catch (const tf2::TransformException &ex) {
|
||||
bool should_log = false;
|
||||
uint64_t suppressed_count = 0;
|
||||
const auto now = std::chrono::steady_clock::now();
|
||||
{
|
||||
std::lock_guard<std::mutex> log_lock(tf_error_log_mutex_);
|
||||
if (last_tf_error_log_time_.time_since_epoch().count() == 0 ||
|
||||
durationMs(now - last_tf_error_log_time_) >= static_cast<double>(tf_error_log_interval_ms_)) {
|
||||
should_log = true;
|
||||
last_tf_error_log_time_ = now;
|
||||
suppressed_count = tf_error_suppressed_counter_.exchange(0, std::memory_order_relaxed);
|
||||
} else {
|
||||
tf_error_suppressed_counter_.fetch_add(1, std::memory_order_relaxed);
|
||||
}
|
||||
}
|
||||
if (should_log) {
|
||||
FYT_ERROR("armor_detector",
|
||||
"lookUpTransform failed: {} -> {}, error: {}, suppressed={}",
|
||||
odom_frame_,
|
||||
frame.img_msg->header.frame_id,
|
||||
ex.what(),
|
||||
suppressed_count);
|
||||
}
|
||||
return;
|
||||
}
|
||||
const double tf_ms = durationMs(std::chrono::steady_clock::now() - stage_start);
|
||||
|
||||
// Detect armors
|
||||
double detect_ms = 0.0;
|
||||
double debug_image_ms = 0.0;
|
||||
stage_start = std::chrono::steady_clock::now();
|
||||
auto armors = detectArmors(frame.img_msg, &detect_ms, &debug_image_ms);
|
||||
const double detect_total_ms = durationMs(std::chrono::steady_clock::now() - stage_start);
|
||||
|
||||
rm_interfaces::msg::Armors armors_msg;
|
||||
// Init message
|
||||
armors_msg.header = frame.img_msg->header;
|
||||
armors_msg.armors.clear();
|
||||
|
||||
// Extract armor poses
|
||||
stage_start = std::chrono::steady_clock::now();
|
||||
{
|
||||
std::lock_guard<std::mutex> lock(processing_mutex_);
|
||||
if (armor_pose_estimator_ != nullptr) {
|
||||
armors_msg.armors = armor_pose_estimator_->extractArmorPoses(armors, imu_to_camera);
|
||||
|
||||
// std::string path =
|
||||
// fmt::format("/home/zcf/fyt2024-log/images/{}/{}.jpg",
|
||||
// armor_msg.number, now().seconds());
|
||||
// cv::imwrite(path, armor.number_img);
|
||||
} else {
|
||||
FYT_WARN("armor_detector", "PnP Failed!");
|
||||
}
|
||||
}
|
||||
const double pose_ms = durationMs(std::chrono::steady_clock::now() - stage_start);
|
||||
|
||||
// Publishing marker
|
||||
stage_start = std::chrono::steady_clock::now();
|
||||
{
|
||||
std::lock_guard<std::mutex> lock(processing_mutex_);
|
||||
if (debug_enabled && debug_marker_enabled) {
|
||||
armors_msg_ = armors_msg;
|
||||
marker_array_.markers.clear();
|
||||
armor_marker_.id = 0;
|
||||
text_marker_.id = 0;
|
||||
armor_marker_.header = text_marker_.header = armors_msg_.header;
|
||||
// Fill the markers
|
||||
for (const auto &armor : armors_msg_.armors) {
|
||||
armor_marker_.pose = armor.pose;
|
||||
armor_marker_.id++;
|
||||
text_marker_.pose.position = armor.pose.position;
|
||||
text_marker_.id++;
|
||||
text_marker_.pose.position.y -= 0.1;
|
||||
text_marker_.text = armor.number;
|
||||
marker_array_.markers.emplace_back(armor_marker_);
|
||||
marker_array_.markers.emplace_back(text_marker_);
|
||||
}
|
||||
publishMarkers();
|
||||
}
|
||||
}
|
||||
const double marker_ms = durationMs(std::chrono::steady_clock::now() - stage_start);
|
||||
|
||||
// Publishing detected armors
|
||||
stage_start = std::chrono::steady_clock::now();
|
||||
armors_pub_->publish(armors_msg);
|
||||
const double publish_ms = durationMs(std::chrono::steady_clock::now() - stage_start);
|
||||
|
||||
if (debug_enabled && debug_terminal_log_enabled &&
|
||||
(debug_log_counter_.fetch_add(1, std::memory_order_relaxed) + 1) %
|
||||
static_cast<uint64_t>(debug_log_interval_frames_) == 0) {
|
||||
const double total_ms = durationMs(std::chrono::steady_clock::now() - frame.frame_start);
|
||||
FYT_INFO("armor_detector",
|
||||
"Detector Latency: total={:.3f}ms tf={:.3f}ms detect={:.3f}ms "
|
||||
"(core={:.3f}ms debug_img={:.3f}ms) pose={:.3f}ms marker={:.3f}ms publish={:.3f}ms",
|
||||
total_ms,
|
||||
tf_ms,
|
||||
detect_total_ms,
|
||||
detect_ms,
|
||||
debug_image_ms,
|
||||
pose_ms,
|
||||
marker_ms,
|
||||
publish_ms);
|
||||
}
|
||||
}
|
||||
|
||||
std::unique_ptr<Detector> ArmorDetectorNode::initDetector() {
|
||||
rcl_interfaces::msg::ParameterDescriptor param_desc;
|
||||
param_desc.integer_range.resize(1);
|
||||
param_desc.integer_range[0].step = 1;
|
||||
param_desc.integer_range[0].from_value = 0;
|
||||
param_desc.integer_range[0].to_value = 255;
|
||||
int binary_thres = declare_parameter("binary_thres", 160, param_desc);
|
||||
|
||||
Detector::LightParams l_params = {
|
||||
.min_ratio = declare_parameter("light.min_ratio", 0.08),
|
||||
.max_ratio = declare_parameter("light.max_ratio", 0.4),
|
||||
.max_angle = declare_parameter("light.max_angle", 40.0),
|
||||
.use_fit_line = declare_parameter("light.use_fit_line", true),
|
||||
.color_diff_thresh = static_cast<int>(declare_parameter("light.color_diff_thresh", 25))};
|
||||
|
||||
Detector::ArmorParams a_params = {
|
||||
.min_light_ratio = declare_parameter("armor.min_light_ratio", 0.6),
|
||||
.min_small_center_distance = declare_parameter("armor.min_small_center_distance", 0.8),
|
||||
.max_small_center_distance = declare_parameter("armor.max_small_center_distance", 3.2),
|
||||
.min_large_center_distance = declare_parameter("armor.min_large_center_distance", 3.2),
|
||||
.max_large_center_distance = declare_parameter("armor.max_large_center_distance", 5.0),
|
||||
.max_angle = declare_parameter("armor.max_angle", 35.0)};
|
||||
|
||||
auto detector = std::make_unique<Detector>(binary_thres, EnemyColor::RED, l_params, a_params);
|
||||
|
||||
// Init classifier
|
||||
namespace fs = std::filesystem;
|
||||
fs::path model_path =
|
||||
utils::URLResolver::getResolvedPath("package://armor_detector/model/lenet.onnx");
|
||||
fs::path label_path =
|
||||
utils::URLResolver::getResolvedPath("package://armor_detector/model/label.txt");
|
||||
FYT_ASSERT_MSG(fs::exists(model_path) && fs::exists(label_path),
|
||||
model_path.string() + " Not Found!");
|
||||
|
||||
double threshold = this->declare_parameter("classifier_threshold", 0.7);
|
||||
std::vector<std::string> ignore_classes =
|
||||
this->declare_parameter("ignore_classes", std::vector<std::string>{"negative"});
|
||||
detector->classifier =
|
||||
std::make_unique<NumberClassifier>(model_path, label_path, threshold, ignore_classes);
|
||||
|
||||
// Init Corrector
|
||||
bool use_pca = this->declare_parameter("use_pca", true);
|
||||
if (use_pca) {
|
||||
detector->corner_corrector = std::make_unique<LightCornerCorrector>();
|
||||
}
|
||||
|
||||
// Set dynamic parameter callback
|
||||
on_set_parameters_callback_handle_ = this->add_on_set_parameters_callback(
|
||||
std::bind(&ArmorDetectorNode::onSetParameters, this, std::placeholders::_1));
|
||||
|
||||
return detector;
|
||||
}
|
||||
|
||||
std::vector<Armor> ArmorDetectorNode::detectArmors(
|
||||
const sensor_msgs::msg::Image::ConstSharedPtr &img_msg,
|
||||
double *detect_ms,
|
||||
double *debug_publish_ms) {
|
||||
std::lock_guard<std::mutex> lock(processing_mutex_);
|
||||
auto stage_start = std::chrono::steady_clock::now();
|
||||
// Convert ROS img to cv::Mat
|
||||
auto img = cv_bridge::toCvShare(img_msg, "rgb8")->image;
|
||||
|
||||
detector_->enable_debug = debug_;
|
||||
auto armors = detector_->detect(img);
|
||||
if (detect_ms != nullptr) {
|
||||
*detect_ms = durationMs(std::chrono::steady_clock::now() - stage_start);
|
||||
}
|
||||
|
||||
auto final_time = this->now();
|
||||
auto latency = (final_time - img_msg->header.stamp).seconds() * 1000;
|
||||
|
||||
// Publish debug info
|
||||
stage_start = std::chrono::steady_clock::now();
|
||||
if (debug_) {
|
||||
if (debug_binary_img_ && debug_binary_pub_active_) {
|
||||
binary_img_pub_.publish(
|
||||
cv_bridge::CvImage(img_msg->header, "mono8", detector_->binary_img).toImageMsg());
|
||||
}
|
||||
|
||||
if (debug_lights_msg_ || debug_armors_msg_) {
|
||||
// Sort lights and armors data by x coordinate
|
||||
std::sort(detector_->debug_lights.data.begin(),
|
||||
detector_->debug_lights.data.end(),
|
||||
[](const auto &l1, const auto &l2) { return l1.center_x < l2.center_x; });
|
||||
std::sort(detector_->debug_armors.data.begin(),
|
||||
detector_->debug_armors.data.end(),
|
||||
[](const auto &a1, const auto &a2) { return a1.center_x < a2.center_x; });
|
||||
}
|
||||
|
||||
if (debug_lights_msg_ && debug_lights_pub_active_) {
|
||||
lights_data_pub_->publish(detector_->debug_lights);
|
||||
}
|
||||
if (debug_armors_msg_ && debug_armors_pub_active_) {
|
||||
armors_data_pub_->publish(detector_->debug_armors);
|
||||
}
|
||||
|
||||
if (debug_number_img_ && debug_number_pub_active_ && !armors.empty()) {
|
||||
auto all_num_img = detector_->getAllNumbersImage();
|
||||
number_img_pub_.publish(
|
||||
*cv_bridge::CvImage(img_msg->header, "mono8", all_num_img).toImageMsg());
|
||||
}
|
||||
|
||||
if (debug_result_img_ && debug_result_pub_active_) {
|
||||
detector_->drawResults(img);
|
||||
|
||||
// Draw camera center
|
||||
cv::circle(img, cam_center_, 5, cv::Scalar(255, 0, 0), 2);
|
||||
// Draw latency
|
||||
std::stringstream latency_ss;
|
||||
latency_ss << "Latency: " << std::fixed << std::setprecision(2) << latency << "ms";
|
||||
auto latency_s = latency_ss.str();
|
||||
cv::putText(
|
||||
img,
|
||||
latency_s,
|
||||
cv::Point(10, 30),
|
||||
cv::FONT_HERSHEY_SIMPLEX,
|
||||
1.0,
|
||||
cv::Scalar(0, 255, 0),
|
||||
2);
|
||||
result_img_pub_.publish(cv_bridge::CvImage(img_msg->header, "rgb8", img).toImageMsg());
|
||||
}
|
||||
}
|
||||
if (debug_publish_ms != nullptr) {
|
||||
*debug_publish_ms = durationMs(std::chrono::steady_clock::now() - stage_start);
|
||||
}
|
||||
|
||||
return armors;
|
||||
}
|
||||
|
||||
rcl_interfaces::msg::SetParametersResult ArmorDetectorNode::onSetParameters(
|
||||
std::vector<rclcpp::Parameter> parameters) {
|
||||
rcl_interfaces::msg::SetParametersResult result;
|
||||
result.successful = true;
|
||||
std::lock_guard<std::mutex> lock(processing_mutex_);
|
||||
bool refresh_debug_publishers = false;
|
||||
for (const auto ¶m : parameters) {
|
||||
if (param.get_name() == "binary_thres") {
|
||||
detector_->binary_thres = param.as_int();
|
||||
} else if (param.get_name() == "debug.enable_terminal_log") {
|
||||
debug_terminal_log_ = param.as_bool();
|
||||
} else if (param.get_name() == "debug.enable_markers") {
|
||||
debug_markers_ = param.as_bool();
|
||||
} else if (param.get_name() == "debug.enable_lights_msg") {
|
||||
debug_lights_msg_ = param.as_bool();
|
||||
refresh_debug_publishers = true;
|
||||
} else if (param.get_name() == "debug.enable_armors_msg") {
|
||||
debug_armors_msg_ = param.as_bool();
|
||||
refresh_debug_publishers = true;
|
||||
} else if (param.get_name() == "debug.enable_binary_img") {
|
||||
debug_binary_img_ = param.as_bool();
|
||||
refresh_debug_publishers = true;
|
||||
} else if (param.get_name() == "debug.enable_number_img") {
|
||||
debug_number_img_ = param.as_bool();
|
||||
refresh_debug_publishers = true;
|
||||
} else if (param.get_name() == "debug.enable_result_img") {
|
||||
debug_result_img_ = param.as_bool();
|
||||
refresh_debug_publishers = true;
|
||||
} else if (param.get_name() == "classifier_threshold") {
|
||||
detector_->classifier->threshold = param.as_double();
|
||||
} else if (param.get_name() == "light.min_ratio") {
|
||||
detector_->light_params.min_ratio = param.as_double();
|
||||
} else if (param.get_name() == "light.max_ratio") {
|
||||
detector_->light_params.max_ratio = param.as_double();
|
||||
} else if (param.get_name() == "light.max_angle") {
|
||||
detector_->light_params.max_angle = param.as_double();
|
||||
} else if (param.get_name() == "light.use_fit_line") {
|
||||
detector_->light_params.use_fit_line = param.as_bool();
|
||||
} else if (param.get_name() == "light.color_diff_thresh") {
|
||||
detector_->light_params.color_diff_thresh = param.as_int();
|
||||
} else if (param.get_name() == "armor.min_light_ratio") {
|
||||
detector_->armor_params.min_light_ratio = param.as_double();
|
||||
} else if (param.get_name() == "armor.min_small_center_distance") {
|
||||
detector_->armor_params.min_small_center_distance = param.as_double();
|
||||
} else if (param.get_name() == "armor.max_small_center_distance") {
|
||||
detector_->armor_params.max_small_center_distance = param.as_double();
|
||||
} else if (param.get_name() == "armor.min_large_center_distance") {
|
||||
detector_->armor_params.min_large_center_distance = param.as_double();
|
||||
} else if (param.get_name() == "armor.max_large_center_distance") {
|
||||
detector_->armor_params.max_large_center_distance = param.as_double();
|
||||
} else if (param.get_name() == "armor.max_angle") {
|
||||
detector_->armor_params.max_angle = param.as_double();
|
||||
}
|
||||
}
|
||||
if (refresh_debug_publishers) {
|
||||
debug_publishers_refresh_requested_.store(true, std::memory_order_relaxed);
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
// void ArmorDetectorNode::targetCallback(const
|
||||
// rm_interfaces::msg::Target::SharedPtr target_msg) {
|
||||
// if (target_msg->tracking) {
|
||||
// tracked_target_ = target_msg;
|
||||
// } else {
|
||||
// tracked_target_ = nullptr;
|
||||
// if (!tracked_armors_.empty()) {
|
||||
// tracked_armors_.clear();
|
||||
// }
|
||||
// }
|
||||
// }
|
||||
|
||||
void ArmorDetectorNode::createDebugPublishers() noexcept {
|
||||
debug_lights_pub_active_ = false;
|
||||
debug_armors_pub_active_ = false;
|
||||
debug_binary_pub_active_ = false;
|
||||
debug_number_pub_active_ = false;
|
||||
debug_result_pub_active_ = false;
|
||||
|
||||
if (debug_lights_msg_) {
|
||||
lights_data_pub_ =
|
||||
this->create_publisher<rm_interfaces::msg::DebugLights>("armor_detector/debug_lights", 10);
|
||||
debug_lights_pub_active_ = true;
|
||||
}
|
||||
if (debug_armors_msg_) {
|
||||
armors_data_pub_ =
|
||||
this->create_publisher<rm_interfaces::msg::DebugArmors>("armor_detector/debug_armors", 10);
|
||||
debug_armors_pub_active_ = true;
|
||||
}
|
||||
if (!this->has_parameter("armor_detector.result_img.jpeg_quality")) {
|
||||
this->declare_parameter("armor_detector.result_img.jpeg_quality", 50);
|
||||
}
|
||||
if (!this->has_parameter("armor_detector.binary_img.jpeg_quality")) {
|
||||
this->declare_parameter("armor_detector.binary_img.jpeg_quality", 50);
|
||||
}
|
||||
if (debug_binary_img_) {
|
||||
binary_img_pub_ = image_transport::create_publisher(this, "armor_detector/binary_img");
|
||||
debug_binary_pub_active_ = true;
|
||||
}
|
||||
if (debug_number_img_) {
|
||||
number_img_pub_ = image_transport::create_publisher(this, "armor_detector/number_img");
|
||||
debug_number_pub_active_ = true;
|
||||
}
|
||||
if (debug_result_img_) {
|
||||
result_img_pub_ = image_transport::create_publisher(this, "armor_detector/result_img");
|
||||
debug_result_pub_active_ = true;
|
||||
}
|
||||
}
|
||||
|
||||
void ArmorDetectorNode::destroyDebugPublishers() noexcept {
|
||||
lights_data_pub_.reset();
|
||||
armors_data_pub_.reset();
|
||||
|
||||
binary_img_pub_.shutdown();
|
||||
number_img_pub_.shutdown();
|
||||
result_img_pub_.shutdown();
|
||||
|
||||
debug_lights_pub_active_ = false;
|
||||
debug_armors_pub_active_ = false;
|
||||
debug_binary_pub_active_ = false;
|
||||
debug_number_pub_active_ = false;
|
||||
debug_result_pub_active_ = false;
|
||||
}
|
||||
|
||||
void ArmorDetectorNode::refreshDebugPublishersIfNeeded() noexcept {
|
||||
if (!debug_publishers_refresh_requested_.exchange(false, std::memory_order_relaxed)) {
|
||||
return;
|
||||
}
|
||||
|
||||
std::lock_guard<std::mutex> lock(processing_mutex_);
|
||||
destroyDebugPublishers();
|
||||
if (debug_) {
|
||||
createDebugPublishers();
|
||||
}
|
||||
}
|
||||
|
||||
void ArmorDetectorNode::publishMarkers() noexcept {
|
||||
using Marker = visualization_msgs::msg::Marker;
|
||||
armor_marker_.action = armors_msg_.armors.empty() ? Marker::DELETEALL : Marker::ADD;
|
||||
marker_array_.markers.emplace_back(armor_marker_);
|
||||
marker_pub_->publish(marker_array_);
|
||||
}
|
||||
|
||||
void ArmorDetectorNode::setModeCallback(
|
||||
const std::shared_ptr<rm_interfaces::srv::SetMode::Request> request,
|
||||
std::shared_ptr<rm_interfaces::srv::SetMode::Response> response) {
|
||||
response->success = true;
|
||||
response->message = "0";
|
||||
|
||||
VisionMode mode = static_cast<VisionMode>(request->mode);
|
||||
std::string mode_name = visionModeToString(mode);
|
||||
if (mode_name == "UNKNOWN") {
|
||||
FYT_ERROR("armor_detector", "Invalid mode: {}", request->mode);
|
||||
return;
|
||||
}
|
||||
|
||||
auto createImageSub = [this]() {
|
||||
if (img_sub_ == nullptr) {
|
||||
img_sub_ = this->create_subscription<sensor_msgs::msg::Image>(
|
||||
"image_raw",
|
||||
rclcpp::SensorDataQoS(),
|
||||
std::bind(&ArmorDetectorNode::imageCallback, this, std::placeholders::_1));
|
||||
}
|
||||
};
|
||||
|
||||
switch (mode) {
|
||||
case VisionMode::AUTO_AIM_RED: {
|
||||
detector_->detect_color = EnemyColor::RED;
|
||||
createImageSub();
|
||||
break;
|
||||
}
|
||||
case VisionMode::AUTO_AIM_BLUE: {
|
||||
detector_->detect_color = EnemyColor::BLUE;
|
||||
createImageSub();
|
||||
break;
|
||||
}
|
||||
default: {
|
||||
img_sub_.reset();
|
||||
std::lock_guard<std::mutex> lock(queue_mutex_);
|
||||
frame_queue_.clear();
|
||||
}
|
||||
}
|
||||
|
||||
FYT_WARN("armor_detector", "Set mode to {}", mode_name);
|
||||
}
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
|
||||
#include "rclcpp_components/register_node_macro.hpp"
|
||||
|
||||
// Register the component with class_loader.
|
||||
// This acts as a sort of entry point, allowing the component to be discoverable
|
||||
// when its library is being loaded into a running process.
|
||||
RCLCPP_COMPONENTS_REGISTER_NODE(fyt::auto_aim::ArmorDetectorNode)
|
||||
154
src/rm_auto_aim/armor_detector/src/armor_pose_estimator.cpp
Normal file
@@ -0,0 +1,154 @@
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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.
|
||||
|
||||
#include "armor_detector/armor_pose_estimator.hpp"
|
||||
|
||||
#include "armor_detector/types.hpp"
|
||||
#include "rm_utils/logger/log.hpp"
|
||||
#include "rm_utils/math/utils.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
ArmorPoseEstimator::ArmorPoseEstimator(sensor_msgs::msg::CameraInfo::SharedPtr camera_info) {
|
||||
// Setup pnp solver
|
||||
pnp_solver_ = std::make_unique<PnPSolver>(camera_info->k, camera_info->d);
|
||||
pnp_solver_->setObjectPoints(
|
||||
"small", Armor::buildObjectPoints<cv::Point3f>(SMALL_ARMOR_WIDTH, SMALL_ARMOR_HEIGHT));
|
||||
pnp_solver_->setObjectPoints(
|
||||
"large", Armor::buildObjectPoints<cv::Point3f>(LARGE_ARMOR_WIDTH, LARGE_ARMOR_HEIGHT));
|
||||
// BA solver
|
||||
ba_solver_ = std::make_unique<BaSolver>(camera_info->k, camera_info->d);
|
||||
|
||||
R_gimbal_camera_ = Eigen::Matrix3d::Identity();
|
||||
R_gimbal_camera_ << 0, 0, 1, -1, 0, 0, 0, -1, 0;
|
||||
}
|
||||
|
||||
std::vector<rm_interfaces::msg::Armor> ArmorPoseEstimator::extractArmorPoses(
|
||||
const std::vector<Armor> &armors, Eigen::Matrix3d R_imu_camera) {
|
||||
std::vector<rm_interfaces::msg::Armor> armors_msg;
|
||||
|
||||
for (const auto &armor : armors) {
|
||||
std::vector<cv::Mat> rvecs, tvecs;
|
||||
|
||||
// Use PnP to get the initial pose information
|
||||
if (pnp_solver_->solvePnPGeneric(
|
||||
armor.landmarks(), rvecs, tvecs, (armor.type == ArmorType::SMALL ? "small" : "large"))) {
|
||||
sortPnPResult(armor, rvecs, tvecs);
|
||||
cv::Mat rmat;
|
||||
cv::Rodrigues(rvecs[0], rmat);
|
||||
|
||||
Eigen::Matrix3d R = utils::cvToEigen(rmat);
|
||||
Eigen::Vector3d t = utils::cvToEigen(tvecs[0]);
|
||||
|
||||
double armor_roll = rotationMatrixToRPY(R_gimbal_camera_ * R)[0] * 180 / M_PI;
|
||||
|
||||
if (use_ba_ && std::abs(armor_roll) < 15) {
|
||||
// Use BA alogorithm to optimize the pose from PnP
|
||||
// solveBa() will modify the rotation_matrix
|
||||
R = ba_solver_->solveBa(armor, t, R, R_imu_camera);
|
||||
}
|
||||
Eigen::Quaterniond q(R);
|
||||
|
||||
// Fill the armor message
|
||||
rm_interfaces::msg::Armor armor_msg;
|
||||
|
||||
// Fill basic info
|
||||
armor_msg.type = armorTypeToString(armor.type);
|
||||
armor_msg.number = armor.number;
|
||||
|
||||
// Fill pose
|
||||
armor_msg.pose.position.x = t(0);
|
||||
armor_msg.pose.position.y = t(1);
|
||||
armor_msg.pose.position.z = t(2);
|
||||
armor_msg.pose.orientation.x = q.x();
|
||||
armor_msg.pose.orientation.y = q.y();
|
||||
armor_msg.pose.orientation.z = q.z();
|
||||
armor_msg.pose.orientation.w = q.w();
|
||||
|
||||
// Fill the distance to image center
|
||||
armor_msg.distance_to_image_center = pnp_solver_->calculateDistanceToCenter(armor.center);
|
||||
|
||||
armors_msg.push_back(std::move(armor_msg));
|
||||
} else {
|
||||
FYT_WARN("armor_detector", "PnP Failed!");
|
||||
}
|
||||
}
|
||||
|
||||
return armors_msg;
|
||||
}
|
||||
|
||||
Eigen::Vector3d ArmorPoseEstimator::rotationMatrixToRPY(const Eigen::Matrix3d &R) {
|
||||
// Transform to camera frame
|
||||
Eigen::Quaterniond q(R);
|
||||
// Get armor yaw
|
||||
tf2::Quaternion tf_q(q.x(), q.y(), q.z(), q.w());
|
||||
Eigen::Vector3d rpy;
|
||||
tf2::Matrix3x3(tf_q).getRPY(rpy[0], rpy[1], rpy[2]);
|
||||
return rpy;
|
||||
}
|
||||
|
||||
void ArmorPoseEstimator::sortPnPResult(const Armor &armor,
|
||||
std::vector<cv::Mat> &rvecs,
|
||||
std::vector<cv::Mat> &tvecs) const {
|
||||
constexpr float PROJECT_ERR_THRES = 3.0;
|
||||
|
||||
// 获取这两个解
|
||||
cv::Mat &rvec1 = rvecs.at(0);
|
||||
cv::Mat &tvec1 = tvecs.at(0);
|
||||
cv::Mat &rvec2 = rvecs.at(1);
|
||||
cv::Mat &tvec2 = tvecs.at(1);
|
||||
|
||||
// 将旋转向量转换为旋转矩阵
|
||||
cv::Mat R1_cv, R2_cv;
|
||||
cv::Rodrigues(rvec1, R1_cv);
|
||||
cv::Rodrigues(rvec2, R2_cv);
|
||||
|
||||
// 转换为Eigen矩阵
|
||||
Eigen::Matrix3d R1 = utils::cvToEigen(R1_cv);
|
||||
Eigen::Matrix3d R2 = utils::cvToEigen(R2_cv);
|
||||
|
||||
// 计算云台系下装甲板的RPY角
|
||||
auto rpy1 = rotationMatrixToRPY(R_gimbal_camera_ * R1);
|
||||
auto rpy2 = rotationMatrixToRPY(R_gimbal_camera_ * R2);
|
||||
|
||||
std::string coord_frame_name = (armor.type == ArmorType::SMALL ? "small" : "large");
|
||||
double error1 =
|
||||
pnp_solver_->calculateReprojectionError(armor.landmarks(), rvec1, tvec1, coord_frame_name);
|
||||
double error2 =
|
||||
pnp_solver_->calculateReprojectionError(armor.landmarks(), rvec2, tvec2, coord_frame_name);
|
||||
|
||||
// 两个解的重投影误差差距较大或者roll角度较大时,不做选择
|
||||
if ((error2 / error1 > PROJECT_ERR_THRES) || (std::abs(rpy1[0]) > 10 * M_PI / 180) ||
|
||||
(std::abs(rpy2[0]) > 10 * M_PI / 180)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// 计算灯条在图像中的倾斜角度
|
||||
double l_angle = std::atan2(armor.left_light.axis.y, armor.left_light.axis.x) * 180 / M_PI;
|
||||
double r_angle = std::atan2(armor.right_light.axis.y, armor.right_light.axis.x) * 180 / M_PI;
|
||||
double angle = (l_angle + r_angle) / 2;
|
||||
angle += 90.0;
|
||||
|
||||
if (armor.number == "outpost") angle = -angle;
|
||||
|
||||
// 根据倾斜角度选择解
|
||||
// 如果装甲板左倾(angle > 0),选择Yaw为负的解
|
||||
// 如果装甲板右倾(angle < 0),选择Yaw为正的解
|
||||
if ((angle > 0 && rpy1[2] > 0 && rpy2[2] < 0) || (angle < 0 && rpy1[2] < 0 && rpy2[2] > 0)) {
|
||||
std::swap(rvec1, rvec2);
|
||||
std::swap(tvec1, tvec2);
|
||||
FYT_DEBUG("armor_detector", "PnP Solution 2 Selected");
|
||||
}
|
||||
}
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
137
src/rm_auto_aim/armor_detector/src/ba_solver.cpp
Normal file
@@ -0,0 +1,137 @@
|
||||
// Created by Labor 2023.8.25
|
||||
// Maintained by Chengfu Zou, Labor
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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.
|
||||
|
||||
#include "armor_detector/ba_solver.hpp"
|
||||
// std
|
||||
#include <memory>
|
||||
// g2o
|
||||
#include <g2o/core/robust_kernel.h>
|
||||
#include <g2o/core/robust_kernel_factory.h>
|
||||
#include <g2o/core/robust_kernel_impl.h>
|
||||
#include <g2o/types/slam3d/types_slam3d.h>
|
||||
// 3rd party
|
||||
#include <Eigen/Core>
|
||||
#include <opencv2/core/eigen.hpp>
|
||||
#include <sophus/se3.hpp>
|
||||
#include <sophus/so3.hpp>
|
||||
// project
|
||||
#include "armor_detector/graph_optimizer.hpp"
|
||||
#include "armor_detector/types.hpp"
|
||||
#include "rm_utils/logger/log.hpp"
|
||||
#include "rm_utils/math/utils.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
G2O_USE_OPTIMIZATION_LIBRARY(dense)
|
||||
|
||||
BaSolver::BaSolver(std::array<double, 9> &camera_matrix,
|
||||
std::vector<double> &dist_coeffs) {
|
||||
K_ = Eigen::Matrix3d::Identity();
|
||||
K_(0, 0) = camera_matrix[0];
|
||||
K_(1, 1) = camera_matrix[4];
|
||||
K_(0, 2) = camera_matrix[2];
|
||||
K_(1, 2) = camera_matrix[5];
|
||||
|
||||
// Optimization information
|
||||
optimizer_.setVerbose(false);
|
||||
// Optimization method
|
||||
optimizer_.setAlgorithm(
|
||||
g2o::OptimizationAlgorithmFactory::instance()->construct(
|
||||
"lm_dense", solver_property_));
|
||||
// Initial step size
|
||||
lm_algorithm_ = dynamic_cast<g2o::OptimizationAlgorithmLevenberg *>(
|
||||
const_cast<g2o::OptimizationAlgorithm *>(optimizer_.algorithm()));
|
||||
lm_algorithm_->setUserLambdaInit(0.1);
|
||||
}
|
||||
|
||||
Eigen::Matrix3d
|
||||
BaSolver::solveBa(const Armor &armor, const Eigen::Vector3d &t_camera_armor,
|
||||
const Eigen::Matrix3d &R_camera_armor,
|
||||
const Eigen::Matrix3d &R_imu_camera) noexcept {
|
||||
// Reset optimizer
|
||||
optimizer_.clear();
|
||||
|
||||
// Essential coordinate system transformation
|
||||
Eigen::Matrix3d R_imu_armor = R_imu_camera * R_camera_armor;
|
||||
Sophus::SO3d R_camera_imu = Sophus::SO3d(R_imu_camera.transpose());
|
||||
|
||||
// Compute the initial yaw from rotation matrix
|
||||
double initial_armor_yaw;
|
||||
auto theta_by_sin = std::asin(-R_imu_armor(0, 1));
|
||||
auto theta_by_cos = std::acos(R_imu_armor(1, 1));
|
||||
if (std::abs(theta_by_sin) > 1e-5) {
|
||||
initial_armor_yaw = theta_by_sin > 0 ? theta_by_cos : -theta_by_cos;
|
||||
} else {
|
||||
initial_armor_yaw = R_imu_armor(1, 1) > 0 ? 0 : CV_PI;
|
||||
}
|
||||
|
||||
// Get the pitch angle of the armor
|
||||
double armor_pitch =
|
||||
armor.number == "outpost" ? -FIFTTEN_DEGREE_RAD : FIFTTEN_DEGREE_RAD;
|
||||
Sophus::SO3d R_pitch = Sophus::SO3d::exp(Eigen::Vector3d(0, armor_pitch, 0));
|
||||
|
||||
// Get the 3D points of the armor
|
||||
const auto armor_size =
|
||||
armor.type == ArmorType::SMALL
|
||||
? Eigen::Vector2d(SMALL_ARMOR_WIDTH, SMALL_ARMOR_HEIGHT)
|
||||
: Eigen::Vector2d(LARGE_ARMOR_WIDTH, LARGE_ARMOR_HEIGHT);
|
||||
const auto object_points =
|
||||
Armor::buildObjectPoints<Eigen::Vector3d>(armor_size(0), armor_size(1));
|
||||
|
||||
// Fill the optimizer
|
||||
size_t id_counter = 0;
|
||||
|
||||
VertexYaw *v_yaw = new VertexYaw();
|
||||
v_yaw->setId(id_counter++);
|
||||
v_yaw->setEstimate(initial_armor_yaw);
|
||||
optimizer_.addVertex(v_yaw);
|
||||
|
||||
const auto &landmarks = armor.landmarks();
|
||||
for (size_t i = 0; i < Armor::N_LANDMARKS; i++) {
|
||||
g2o::VertexPointXYZ *v_point = new g2o::VertexPointXYZ();
|
||||
v_point->setId(id_counter++);
|
||||
v_point->setEstimate(Eigen::Vector3d(
|
||||
object_points[i].x(), object_points[i].y(), object_points[i].z()));
|
||||
v_point->setFixed(true);
|
||||
optimizer_.addVertex(v_point);
|
||||
|
||||
EdgeProjection *edge =
|
||||
new EdgeProjection(R_camera_imu, R_pitch, t_camera_armor, K_);
|
||||
edge->setId(id_counter++);
|
||||
edge->setVertex(0, v_yaw);
|
||||
edge->setVertex(1, v_point);
|
||||
edge->setMeasurement(Eigen::Vector2d(landmarks[i].x, landmarks[i].y));
|
||||
edge->setInformation(EdgeProjection::InfoMatrixType::Identity());
|
||||
edge->setRobustKernel(new g2o::RobustKernelHuber);
|
||||
optimizer_.addEdge(edge);
|
||||
}
|
||||
|
||||
// Start optimizing
|
||||
optimizer_.initializeOptimization();
|
||||
optimizer_.optimize(20);
|
||||
|
||||
// Get yaw angle after optimization
|
||||
double yaw_optimized = v_yaw->estimate();
|
||||
|
||||
if (std::isnan(yaw_optimized)) {
|
||||
FYT_ERROR("armor_detector", "Yaw angle is nan after optimization");
|
||||
return R_camera_armor;
|
||||
}
|
||||
|
||||
Sophus::SO3d R_yaw = Sophus::SO3d::exp(Eigen::Vector3d(0, 0, yaw_optimized));
|
||||
return (R_camera_imu * R_yaw * R_pitch).matrix();
|
||||
}
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
63
src/rm_auto_aim/armor_detector/src/graph_optimizer.cpp
Normal file
@@ -0,0 +1,63 @@
|
||||
// Created by Labor 2023.8.25
|
||||
// Maintained by Chengfu Zou, Labor
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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.
|
||||
|
||||
#include "armor_detector/graph_optimizer.hpp"
|
||||
// std
|
||||
#include <algorithm>
|
||||
// third party
|
||||
#include <Eigen/Core>
|
||||
#include <g2o/types/slam3d/vertex_pointxyz.h>
|
||||
#include <sophus/so3.hpp>
|
||||
// project
|
||||
#include "armor_detector/types.hpp"
|
||||
#include "rm_utils/math/utils.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
|
||||
void VertexYaw::oplusImpl(const double *update) {
|
||||
Sophus::SO3d R_yaw = Sophus::SO3d::exp(Eigen::Vector3d(0, 0, update[0])) *
|
||||
Sophus::SO3d::exp(Eigen::Vector3d(0, 0, _estimate));
|
||||
_estimate = R_yaw.log()(2);
|
||||
}
|
||||
|
||||
EdgeProjection::EdgeProjection(const Sophus::SO3d &R_camera_imu,
|
||||
const Sophus::SO3d &R_pitch,
|
||||
const Eigen::Vector3d &t,
|
||||
const Eigen::Matrix3d &K)
|
||||
: R_camera_imu_(R_camera_imu), R_pitch_(R_pitch), t_(t), K_(K) {}
|
||||
|
||||
void EdgeProjection::computeError() {
|
||||
// Get the rotation
|
||||
double yaw = static_cast<VertexYaw *>(_vertices[0])->estimate();
|
||||
Sophus::SO3d R_yaw = Sophus::SO3d::exp(Eigen::Vector3d(0, 0, yaw));
|
||||
Sophus::SO3d R = R_camera_imu_ * R_yaw * R_pitch_;
|
||||
|
||||
// Get the 3D point
|
||||
Eigen::Vector3d p_3d =
|
||||
static_cast<g2o::VertexPointXYZ *>(_vertices[1])->estimate();
|
||||
|
||||
// Get the observed 2D point
|
||||
Eigen::Vector2d obs(_measurement);
|
||||
|
||||
// Project the 3D point to the 2D point
|
||||
Eigen::Vector3d p_2d = R * p_3d + t_;
|
||||
p_2d = K_ * (p_2d / p_2d.z());
|
||||
|
||||
// Calculate the error
|
||||
_error = obs - p_2d.head<2>();
|
||||
}
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
176
src/rm_auto_aim/armor_detector/src/light_corner_corrector.cpp
Normal file
@@ -0,0 +1,176 @@
|
||||
// Maintained by Shenglin Qin, Chengfu Zou
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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.
|
||||
|
||||
#include "armor_detector/light_corner_corrector.hpp"
|
||||
|
||||
#include <numeric>
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
|
||||
void LightCornerCorrector::correctCorners(Armor &armor, const cv::Mat &gray_img) {
|
||||
// If the width of the light is too small, the correction is not performed
|
||||
constexpr int PASS_OPTIMIZE_WIDTH = 3;
|
||||
|
||||
if (armor.left_light.width > PASS_OPTIMIZE_WIDTH) {
|
||||
// Find the symmetry axis of the light
|
||||
SymmetryAxis left_axis = findSymmetryAxis(gray_img, armor.left_light);
|
||||
armor.left_light.center = left_axis.centroid;
|
||||
armor.left_light.axis = left_axis.direction;
|
||||
// Find the corner of the light
|
||||
if (cv::Point2f t = findCorner(gray_img, armor.left_light, left_axis, "top"); t.x > 0) {
|
||||
armor.left_light.top = t;
|
||||
}
|
||||
if (cv::Point2f b = findCorner(gray_img, armor.left_light, left_axis, "bottom"); b.x > 0) {
|
||||
armor.left_light.bottom = b;
|
||||
}
|
||||
}
|
||||
|
||||
if (armor.right_light.width > PASS_OPTIMIZE_WIDTH) {
|
||||
// Find the symmetry axis of the light
|
||||
SymmetryAxis right_axis = findSymmetryAxis(gray_img, armor.right_light);
|
||||
armor.right_light.center = right_axis.centroid;
|
||||
armor.right_light.axis = right_axis.direction;
|
||||
// Find the corner of the light
|
||||
if (cv::Point2f t = findCorner(gray_img, armor.right_light, right_axis, "top"); t.x > 0) {
|
||||
armor.right_light.top = t;
|
||||
}
|
||||
if (cv::Point2f b = findCorner(gray_img, armor.right_light, right_axis, "bottom"); b.x > 0) {
|
||||
armor.right_light.bottom = b;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
SymmetryAxis LightCornerCorrector::findSymmetryAxis(const cv::Mat &gray_img, const Light &light) {
|
||||
constexpr float MAX_BRIGHTNESS = 25;
|
||||
constexpr float SCALE = 0.07;
|
||||
|
||||
// Scale the bounding box
|
||||
cv::Rect light_box = light.boundingRect();
|
||||
light_box.x -= light_box.width * SCALE;
|
||||
light_box.y -= light_box.height * SCALE;
|
||||
light_box.width += light_box.width * SCALE * 2;
|
||||
light_box.height += light_box.height * SCALE * 2;
|
||||
|
||||
// Check boundary
|
||||
light_box.x = std::max(light_box.x, 0);
|
||||
light_box.x = std::min(light_box.x, gray_img.cols - 1);
|
||||
light_box.y = std::max(light_box.y, 0);
|
||||
light_box.y = std::min(light_box.y, gray_img.rows - 1);
|
||||
light_box.width = std::min(light_box.width, gray_img.cols - light_box.x);
|
||||
light_box.height = std::min(light_box.height, gray_img.rows - light_box.y);
|
||||
|
||||
// Get normalized light image
|
||||
cv::Mat roi = gray_img(light_box);
|
||||
float mean_val = cv::mean(roi)[0];
|
||||
roi.convertTo(roi, CV_32F);
|
||||
cv::normalize(roi, roi, 0, MAX_BRIGHTNESS, cv::NORM_MINMAX);
|
||||
|
||||
// Calculate the centroid
|
||||
cv::Moments moments = cv::moments(roi, false);
|
||||
cv::Point2f centroid = cv::Point2f(moments.m10 / moments.m00, moments.m01 / moments.m00) +
|
||||
cv::Point2f(light_box.x, light_box.y);
|
||||
|
||||
// Initialize the PointCloud
|
||||
std::vector<cv::Point2f> points;
|
||||
for (int i = 0; i < roi.rows; i++) {
|
||||
for (int j = 0; j < roi.cols; j++) {
|
||||
for (int k = 0; k < std::round(roi.at<float>(i, j)); k++) {
|
||||
points.emplace_back(cv::Point2f(j, i));
|
||||
}
|
||||
}
|
||||
}
|
||||
cv::Mat points_mat = cv::Mat(points).reshape(1);
|
||||
|
||||
// PCA (Principal Component Analysis)
|
||||
auto pca = cv::PCA(points_mat, cv::Mat(), cv::PCA::DATA_AS_ROW);
|
||||
|
||||
// Get the symmetry axis
|
||||
cv::Point2f axis =
|
||||
cv::Point2f(pca.eigenvectors.at<float>(0, 0), pca.eigenvectors.at<float>(0, 1));
|
||||
|
||||
// Normalize the axis
|
||||
axis = axis / cv::norm(axis);
|
||||
|
||||
if (axis.y > 0) {
|
||||
axis = -axis;
|
||||
}
|
||||
|
||||
return SymmetryAxis{.centroid = centroid, .direction = axis, .mean_val = mean_val};
|
||||
}
|
||||
|
||||
cv::Point2f LightCornerCorrector::findCorner(const cv::Mat &gray_img,
|
||||
const Light &light,
|
||||
const SymmetryAxis &axis,
|
||||
std::string order) {
|
||||
constexpr float START = 0.8 / 2;
|
||||
constexpr float END = 1.2 / 2;
|
||||
|
||||
auto inImage = [&gray_img](const cv::Point &point) -> bool {
|
||||
return point.x >= 0 && point.x < gray_img.cols && point.y >= 0 && point.y < gray_img.rows;
|
||||
};
|
||||
|
||||
auto distance = [](float x0, float y0, float x1, float y1) -> float {
|
||||
return std::sqrt((x0 - x1) * (x0 - x1) + (y0 - y1) * (y0 - y1));
|
||||
};
|
||||
|
||||
int oper = order == "top" ? 1 : -1;
|
||||
float L = light.length;
|
||||
float dx = axis.direction.x * oper;
|
||||
float dy = axis.direction.y * oper;
|
||||
|
||||
std::vector<cv::Point2f> candidates;
|
||||
|
||||
// Select multiple corner candidates and take the average as the final corner
|
||||
int n = light.width - 2;
|
||||
int half_n = std::round(n / 2);
|
||||
for (int i = -half_n; i <= half_n; i++) {
|
||||
float x0 = axis.centroid.x + L * START * dx + i;
|
||||
float y0 = axis.centroid.y + L * START * dy;
|
||||
|
||||
cv::Point2f prev = cv::Point2f(x0, y0);
|
||||
cv::Point2f corner = cv::Point2f(x0, y0);
|
||||
float max_brightness_diff = 0;
|
||||
bool has_corner = false;
|
||||
// Search along the symmetry axis to find the corner that has the maximum brightness difference
|
||||
for (float x = x0 + dx, y = y0 + dy; distance(x, y, x0, y0) < L * (END - START);
|
||||
x += dx, y += dy) {
|
||||
cv::Point2f cur = cv::Point2f(x, y);
|
||||
if (!inImage(cv::Point(cur))) {
|
||||
break;
|
||||
}
|
||||
|
||||
float brightness_diff = gray_img.at<uchar>(prev) - gray_img.at<uchar>(cur);
|
||||
if (brightness_diff > max_brightness_diff && gray_img.at<uchar>(prev) > axis.mean_val) {
|
||||
max_brightness_diff = brightness_diff;
|
||||
corner = prev;
|
||||
has_corner = true;
|
||||
}
|
||||
|
||||
prev = cur;
|
||||
}
|
||||
|
||||
if (has_corner) {
|
||||
candidates.emplace_back(corner);
|
||||
}
|
||||
}
|
||||
if (!candidates.empty()) {
|
||||
cv::Point2f result = std::accumulate(candidates.begin(), candidates.end(), cv::Point2f(0, 0));
|
||||
return result / static_cast<float>(candidates.size());
|
||||
}
|
||||
|
||||
return cv::Point2f(-1, -1);
|
||||
}
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
157
src/rm_auto_aim/armor_detector/src/number_classifier.cpp
Normal file
@@ -0,0 +1,157 @@
|
||||
// Copyright Chen Jun 2023. Licensed under the MIT License.
|
||||
//
|
||||
// Additional modifications and features by Chengfu Zou, Labor. Licensed under Apache License 2.0.
|
||||
//
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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.
|
||||
|
||||
// OpenCV
|
||||
#include <opencv2/core.hpp>
|
||||
#include <opencv2/core/mat.hpp>
|
||||
#include <opencv2/core/types.hpp>
|
||||
#include <opencv2/dnn.hpp>
|
||||
#include <opencv2/highgui.hpp>
|
||||
#include <opencv2/imgcodecs.hpp>
|
||||
#include <opencv2/imgproc.hpp>
|
||||
#include <opencv2/opencv.hpp>
|
||||
// std
|
||||
#include <algorithm>
|
||||
#include <cstddef>
|
||||
#include <execution>
|
||||
#include <fstream>
|
||||
#include <future>
|
||||
#include <map>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
// 3rd party
|
||||
#include <fmt/format.h>
|
||||
// project
|
||||
#include "armor_detector/number_classifier.hpp"
|
||||
#include "armor_detector/types.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
NumberClassifier::NumberClassifier(const std::string &model_path,
|
||||
const std::string &label_path,
|
||||
const double thre,
|
||||
const std::vector<std::string> &ignore_classes)
|
||||
: threshold(thre), ignore_classes_(ignore_classes) {
|
||||
net_ = cv::dnn::readNetFromONNX(model_path);
|
||||
std::ifstream label_file(label_path);
|
||||
std::string line;
|
||||
while (std::getline(label_file, line)) {
|
||||
class_names_.push_back(line);
|
||||
}
|
||||
}
|
||||
|
||||
cv::Mat NumberClassifier::extractNumber(const cv::Mat &src, const Armor &armor) const noexcept {
|
||||
// Light length in image
|
||||
static const int light_length = 12;
|
||||
// Image size after warp
|
||||
static const int warp_height = 28;
|
||||
static const int small_armor_width = 32;
|
||||
static const int large_armor_width = 54;
|
||||
// Number ROI size
|
||||
static const cv::Size roi_size(20, 28);
|
||||
static const cv::Size input_size(28, 28);
|
||||
|
||||
// Warp perspective transform
|
||||
cv::Point2f lights_vertices[4] = {
|
||||
armor.left_light.bottom, armor.left_light.top, armor.right_light.top, armor.right_light.bottom};
|
||||
|
||||
const int top_light_y = (warp_height - light_length) / 2 - 1;
|
||||
const int bottom_light_y = top_light_y + light_length;
|
||||
const int warp_width = armor.type == ArmorType::SMALL ? small_armor_width : large_armor_width;
|
||||
cv::Point2f target_vertices[4] = {
|
||||
cv::Point(0, bottom_light_y),
|
||||
cv::Point(0, top_light_y),
|
||||
cv::Point(warp_width - 1, top_light_y),
|
||||
cv::Point(warp_width - 1, bottom_light_y),
|
||||
};
|
||||
cv::Mat number_image;
|
||||
auto rotation_matrix = cv::getPerspectiveTransform(lights_vertices, target_vertices);
|
||||
cv::warpPerspective(src, number_image, rotation_matrix, cv::Size(warp_width, warp_height));
|
||||
|
||||
// Get ROI
|
||||
number_image = number_image(cv::Rect(cv::Point((warp_width - roi_size.width) / 2, 0), roi_size));
|
||||
|
||||
// Binarize
|
||||
cv::cvtColor(number_image, number_image, cv::COLOR_RGB2GRAY);
|
||||
cv::threshold(number_image, number_image, 0, 255, cv::THRESH_BINARY | cv::THRESH_OTSU);
|
||||
cv::resize(number_image, number_image, input_size);
|
||||
return number_image;
|
||||
}
|
||||
|
||||
void NumberClassifier::classify(const cv::Mat &src, Armor &armor) noexcept {
|
||||
// Normalize
|
||||
cv::Mat input = armor.number_img / 255.0;
|
||||
|
||||
// Create blob from image
|
||||
cv::Mat blob;
|
||||
cv::dnn::blobFromImage(input, blob);
|
||||
|
||||
// Set the input blob for the neural network
|
||||
mutex_.lock();
|
||||
net_.setInput(blob);
|
||||
|
||||
// Forward pass the image blob through the model
|
||||
cv::Mat outputs = net_.forward().clone();
|
||||
mutex_.unlock();
|
||||
|
||||
// Decode the output
|
||||
double confidence;
|
||||
cv::Point class_id_point;
|
||||
minMaxLoc(outputs.reshape(1, 1), nullptr, &confidence, nullptr, &class_id_point);
|
||||
int label_id = class_id_point.x;
|
||||
|
||||
armor.confidence = confidence;
|
||||
armor.number = class_names_[label_id];
|
||||
|
||||
if (armor.number == "2" || armor.number == "outpost" || armor.number == "guard" ||
|
||||
armor.number == "depth") {
|
||||
armor.type = ArmorType::SMALL;
|
||||
} else if (armor.number == "1" || armor.number == "base") {
|
||||
armor.type = ArmorType::LARGE;
|
||||
}
|
||||
|
||||
armor.classfication_result = fmt::format("{}:{:.1f}%", armor.number, armor.confidence * 100.0);
|
||||
}
|
||||
|
||||
void NumberClassifier::eraseIgnoreClasses(std::vector<Armor> &armors) noexcept {
|
||||
armors.erase(
|
||||
std::remove_if(armors.begin(),
|
||||
armors.end(),
|
||||
[this](const Armor &armor) {
|
||||
if (armor.confidence < threshold) {
|
||||
return true;
|
||||
}
|
||||
|
||||
for (const auto &ignore_class : ignore_classes_) {
|
||||
if (armor.number == ignore_class) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
bool mismatch_armor_type = false;
|
||||
if (armor.type == ArmorType::LARGE) {
|
||||
mismatch_armor_type = armor.number == "outpost" || armor.number == "2" ||
|
||||
armor.number == "sentry";
|
||||
} else if (armor.type == ArmorType::SMALL) {
|
||||
mismatch_armor_type = armor.number == "1" || armor.number == "base";
|
||||
}
|
||||
return mismatch_armor_type;
|
||||
}),
|
||||
armors.end());
|
||||
}
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
76
src/rm_auto_aim/armor_detector/test/test_detector.cpp
Normal file
@@ -0,0 +1,76 @@
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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.
|
||||
|
||||
// gest
|
||||
#include <gtest/gtest.h>
|
||||
// ros2
|
||||
#include <opencv2/imgproc.hpp>
|
||||
#include <rclcpp/executors.hpp>
|
||||
#include <rclcpp/node_options.hpp>
|
||||
#include <rclcpp/utilities.hpp>
|
||||
// std
|
||||
#include <memory>
|
||||
// opencv
|
||||
#include <opencv2/opencv.hpp>
|
||||
// project
|
||||
#include "armor_detector/armor_detector.hpp"
|
||||
#include "rm_utils/common.hpp"
|
||||
#include "rm_utils/url_resolver.hpp"
|
||||
|
||||
using namespace fyt;
|
||||
using namespace fyt::auto_aim;
|
||||
TEST(ArmorDetectorNodeTest, NodeStartupTest) {
|
||||
// Init detector
|
||||
int binary_thres = 160;
|
||||
Detector::LightParams l_params = {
|
||||
.min_ratio = 0.08, .max_ratio = 0.4, .max_angle = 40.0, .color_diff_thresh = 25};
|
||||
Detector::ArmorParams a_params = {.min_light_ratio = 0.6,
|
||||
.min_small_center_distance = 0.8,
|
||||
.max_small_center_distance = 3.2,
|
||||
.min_large_center_distance = 3.2,
|
||||
.max_large_center_distance = 5.0,
|
||||
.max_angle = 35.0};
|
||||
|
||||
auto detector = std::make_unique<Detector>(binary_thres, EnemyColor::RED, l_params, a_params);
|
||||
|
||||
// Init classifier
|
||||
namespace fs = std::filesystem;
|
||||
fs::path model_path =
|
||||
utils::URLResolver::getResolvedPath("package://armor_detector/model/lenet.onnx");
|
||||
fs::path label_path =
|
||||
utils::URLResolver::getResolvedPath("package://armor_detector/model/label.txt");
|
||||
detector->classifier = std::make_unique<NumberClassifier>(
|
||||
model_path, label_path, 0.6, std::vector<std::string>{"negative"});
|
||||
|
||||
// Load test image
|
||||
fs::path test_image_path =
|
||||
utils::URLResolver::getResolvedPath("package://armor_detector/docs/test.png");
|
||||
cv::Mat test_image = cv::imread(test_image_path.string(), cv::IMREAD_COLOR);
|
||||
cv::cvtColor(test_image, test_image, cv::COLOR_BGR2RGB);
|
||||
|
||||
// Detect
|
||||
std::vector<Armor> armors = detector->detect(test_image);
|
||||
|
||||
std::sort(armors.begin(), armors.end(), [](const Armor &a, const Armor &b) {
|
||||
return a.number < b.number;
|
||||
});
|
||||
|
||||
EXPECT_EQ(armors.size(), static_cast<size_t>(6));
|
||||
EXPECT_EQ(armors[0].number, "2");
|
||||
EXPECT_EQ(armors[1].number, "3");
|
||||
EXPECT_EQ(armors[2].number, "4");
|
||||
EXPECT_EQ(armors[3].number, "5");
|
||||
EXPECT_EQ(armors[4].number, "outpost");
|
||||
EXPECT_EQ(armors[5].number, "sentry");
|
||||
}
|
||||
56
src/rm_auto_aim/armor_solver/CMakeLists.txt
Normal file
@@ -0,0 +1,56 @@
|
||||
cmake_minimum_required(VERSION 3.10)
|
||||
project(armor_solver)
|
||||
|
||||
## Use C++14
|
||||
set(CMAKE_CXX_STANDARD 17)
|
||||
set(CMAKE_CXX_STANDARD_REQUIRED ON)
|
||||
|
||||
## By adding -Wall and -Werror, the compiler does not ignore warnings anymore,
|
||||
## enforcing cleaner code.
|
||||
add_definitions(-Wall -Werror -O3)
|
||||
|
||||
## Export compile commands for clangd
|
||||
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
|
||||
|
||||
#######################
|
||||
## Find dependencies ##
|
||||
#######################
|
||||
|
||||
find_package(ament_cmake_auto REQUIRED)
|
||||
ament_auto_find_build_dependencies()
|
||||
|
||||
###########
|
||||
## Build ##
|
||||
###########
|
||||
|
||||
ament_auto_add_library(${PROJECT_NAME} SHARED
|
||||
DIRECTORY src
|
||||
)
|
||||
|
||||
rclcpp_components_register_node(${PROJECT_NAME}
|
||||
PLUGIN fyt::auto_aim::ArmorSolverNode
|
||||
EXECUTABLE ${PROJECT_NAME}_node
|
||||
)
|
||||
|
||||
#############
|
||||
## Testing ##
|
||||
#############
|
||||
|
||||
if(BUILD_TESTING)
|
||||
find_package(ament_lint_auto REQUIRED)
|
||||
list(APPEND AMENT_LINT_AUTO_EXCLUDE
|
||||
ament_cmake_copyright
|
||||
ament_cmake_uncrustify
|
||||
ament_cmake_cpplint
|
||||
)
|
||||
ament_lint_auto_find_test_dependencies()
|
||||
|
||||
find_package(ament_cmake_gtest)
|
||||
|
||||
endif()
|
||||
|
||||
#############
|
||||
## Install ##
|
||||
#############
|
||||
|
||||
ament_auto_package()
|
||||
118
src/rm_auto_aim/armor_solver/README.md
Normal file
@@ -0,0 +1,118 @@
|
||||
# armor_solver
|
||||
|
||||
## fyt::ArmorSolverNode
|
||||
|
||||
装甲板识别节点
|
||||
|
||||
### 发布话题
|
||||
|
||||
* `armor_solver/target` (`rm_interfaces/msg/Target`) - 整车估计的状态
|
||||
* `armor_solver/measurement` (`rm_interfaces/msg/Measurement`) - EKF的输入观测量
|
||||
* `armor_solver/cmd_gimbal` (`rm_interfaces/msg/GimbalCmd`) - 云台控制指令
|
||||
|
||||
### 订阅话题
|
||||
|
||||
* `armor_detector/armors` (`rm_interfaces/msg/Armors`) - 识别到的装甲板信息
|
||||
|
||||
|
||||
### 参数
|
||||
|
||||
* `debug` (`bool`, default: false) - 是否开启调试模式
|
||||
* `target_frame` (`string`, default: "odom") - 目标坐标系
|
||||
* `ekf.sigma2_q_xyz` (`double`, default: 0.05) - 状态转移噪声方差 (x,y,z)
|
||||
* `ekf.sigma2_q_yaw` (`double`, default: 1.0) - 状态转移噪声方差 (yaw)
|
||||
* `ekf.sigma2_q_r` (`double`, default: 80.0) - 状态转移噪声方差 (r)
|
||||
* `r_xyz_factor` (`double`, default: 1.0) - 位置观测噪声方差系数 (x,y,z)
|
||||
* `r_yaw_factor` (`double`, default: 1.0) - 位置观测噪声方差系数 (yaw)
|
||||
* `tracker.max_match_distance` (`double`, default: 0.5) - 两帧间目标可匹配的最大距离
|
||||
* `tracker.max_match_yaw_diff` (`double`, default: 0.5) - 两帧间目标同一块装甲板可匹配的最大yaw角差(大于这个值则认为装甲板发生跳变)
|
||||
* `tracker.tracking_thres` (`int`, default: 2) - `DETECTING` 状态进入 `TRACKING` 状态需要连续识别到的帧数
|
||||
* `tracker.lost_thres` (`double`, default: 1.0) - `TRACKING` 状态进入 `LOST` 状态需要连续丢失的时间(s)
|
||||
* `solver.prediction_delay` (`double`, default: 0.0) - 预测延迟时间(s),会影响选版
|
||||
* `solver.controller_delay` (`double`, default: 0.0) - 控制延迟时间(s),不会影响选版
|
||||
* `solver.max_tracking_v_yaw` (`double`, default: 60.0) - 转速大于这个值时,瞄准中心
|
||||
* `solver.side_angle` (`double`, default: 15.0) - 跳转到下一装甲板的角度阈值
|
||||
* `solver.bullet_speed` (`double`, default: 25.0) - 子弹速度
|
||||
* `solver.gravity` (`double`, default: 9.8) - 重力加速度
|
||||
* `solver.compensator_type` (`string`, default: "ideal") - 补偿器类型
|
||||
* `solver.resistance` (`double`, default: 0.001) - 空气阻力
|
||||
|
||||
|
||||
## ArmorSolverNode
|
||||
装甲板处理节点
|
||||
|
||||
订阅识别节点发布的装甲板三维位置及机器人的坐标转换信息,将装甲板三维位置变换到指定惯性系(一般是以云台中心为原点,IMU 上电时的 Yaw 朝向为 X 轴的惯性系)下,然后将装甲板目标送入跟踪器中,输出跟踪机器人在指定惯性系下的状态
|
||||
|
||||
订阅:
|
||||
- 已识别到的装甲板 `/detector/armors`
|
||||
- 机器人的坐标转换信息 `/tf` `/tf_static`
|
||||
|
||||
发布:
|
||||
- 最终锁定的目标 `/tracker/target`
|
||||
|
||||
参数:
|
||||
- 跟踪器参数 tracker
|
||||
- 两帧间目标可匹配的最大距离 max_match_distance
|
||||
- `DETECTING` 状态进入 `TRACKING` 状态的阈值 tracking_threshold
|
||||
- `TRACKING` 状态进入 `LOST` 状态的阈值 lost_threshold
|
||||
|
||||
## ExtendedKalmanFilter
|
||||
|
||||
$$ x_c = x_a + r * cos (\theta) $$
|
||||
$$ y_c = y_a + r * sin (\theta) $$
|
||||
|
||||
$$ x = [x_c, y_c,z, yaw, v_{xc}, v_{yc},v_z, v_{yaw}, r]^T $$
|
||||
|
||||
参考 OpenCV 中的卡尔曼滤波器使用 Eigen 进行了实现
|
||||
|
||||
[卡尔曼滤波器](https://zh.wikipedia.org/wiki/%E5%8D%A1%E5%B0%94%E6%9B%BC%E6%BB%A4%E6%B3%A2)
|
||||
|
||||

|
||||
|
||||
考虑到自瞄任务中对于目标只有观测没有控制,所以输入-控制模型 $B$ 和控制器向量 $u$ 可忽略。
|
||||
|
||||
预测及更新的公式如下:
|
||||
|
||||
预测:
|
||||
|
||||
$$ x_{k|k-1} = F * x_{k-1|k-1} $$
|
||||
|
||||
$$ P_{k|k-1} = F * P_{k-1|k-1}* F^T + Q $$
|
||||
|
||||
更新:
|
||||
|
||||
$$ K = P_{k|k-1} * H^T * (H * P_{k|k-1} * H^T + R)^{-1} $$
|
||||
|
||||
$$ x_{k|k} = x_{k|k-1} + K * (z_k - H * x_{k|k-1}) $$
|
||||
|
||||
$$ P_{k|k} = (I - K * H) * P_{k|k-1} $$
|
||||
|
||||
## Tracker
|
||||
|
||||
参考 [SORT(Simple online and realtime tracking)](https://ieeexplore.ieee.org/abstract/document/7533003/) 中对于目标匹配的方法,使用卡尔曼滤波器对单目标在三维空间中进行跟踪
|
||||
|
||||
在此跟踪器中,卡尔曼滤波器观测量为目标在指定惯性系中的位置(xyz),状态量为目标位置及速度(xyz+vx vy vz)
|
||||
|
||||
在对目标的运动模型建模为在指定惯性系中的匀速线性运动,即状态转移为 $x_{pre} = x_{post} + v_{post} * dt$
|
||||
|
||||
目标关联的判断依据为三维位置的 L2 欧式距离
|
||||
|
||||
跟踪器共有四个状态:
|
||||
- `DETECTING` :短暂识别到目标,需要更多帧识别信息才能进入跟踪状态
|
||||
- `TRACKING` :跟踪器正常跟踪目标中
|
||||
- `TEMP_LOST` :跟踪器短暂丢失目标,通过卡尔曼滤波器预测目标
|
||||
- `LOST` :跟踪器完全丢失目标
|
||||
|
||||
工作流程:
|
||||
|
||||
- init:
|
||||
|
||||
跟踪器默认选择离相机光心最近的目标作为跟踪对象,选择目标后初始化卡尔曼滤波器,初始状态设为当前目标位置,速度设为 0
|
||||
|
||||
- update:
|
||||
|
||||
首先由卡尔曼滤波器得到目标在当前帧的预测位置,然后遍历当前帧中的目标位置与预测位置进行匹配,若当前帧不存在目标或所有目标位置与预测位置的偏差都过大则认为目标丢失,重置卡尔曼滤波器。
|
||||
|
||||
最后选取位置相差最小的目标作为最佳匹配项,更新卡尔曼滤波器,将更新后的状态作为跟踪器的结果输出
|
||||
|
||||
|
||||
BIN
src/rm_auto_aim/armor_solver/docs/Kalman_filter_model.png
Normal file
|
After Width: | Height: | Size: 21 KiB |
@@ -0,0 +1,122 @@
|
||||
// Created by Chengfu Zou
|
||||
// Maintained by Chengfu Zou, Labor
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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 ARMOR_SOLVER_SOLVER_HPP_
|
||||
#define ARMOR_SOLVER_SOLVER_HPP_
|
||||
|
||||
// std
|
||||
#include <memory>
|
||||
// ros2
|
||||
#include <angles/angles.h>
|
||||
#include <tf2_ros/buffer.h>
|
||||
|
||||
#include <rclcpp/time.hpp>
|
||||
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
|
||||
// 3rd party
|
||||
#include <Eigen/Dense>
|
||||
// project
|
||||
#include "rm_interfaces/msg/gimbal_cmd.hpp"
|
||||
#include "rm_interfaces/msg/target.hpp"
|
||||
#include "rm_utils/math/manual_compensator.hpp"
|
||||
#include "rm_utils/math/trajectory_compensator.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
// Solver class used to solve the gimbal command from tracked target
|
||||
class Solver {
|
||||
public:
|
||||
explicit Solver(std::weak_ptr<rclcpp::Node> node);
|
||||
// explicit Solver(std::string trajectory_compensator_type, float max_tracking_v_yaw);
|
||||
~Solver() = default;
|
||||
|
||||
// Solve the gimbal command from tracked target
|
||||
// Throw: tf2::TransformException if the transform from "odom" to "pitch_link" is not available
|
||||
rm_interfaces::msg::GimbalCmd solve(const rm_interfaces::msg::Target &target_msg,
|
||||
const rclcpp::Time ¤t_time,
|
||||
std::shared_ptr<tf2_ros::Buffer> tf2_buffer_);
|
||||
|
||||
enum State { TRACKING_ARMOR = 0, TRACKING_CENTER = 1 } state;
|
||||
|
||||
std::vector<std::pair<double, double>> getTrajectory() const noexcept;
|
||||
void setBulletSpeed(double bullet_speed) noexcept;
|
||||
void updateRuntimeParams(double max_tracking_v_yaw,
|
||||
double prediction_delay,
|
||||
double controller_delay,
|
||||
double side_angle,
|
||||
double min_switching_v_yaw,
|
||||
double shooting_range_w,
|
||||
double shooting_range_h) noexcept;
|
||||
|
||||
private:
|
||||
// Get the armor positions from the target robot
|
||||
std::vector<Eigen::Vector3d> getArmorPositions(const Eigen::Vector3d &target_center,
|
||||
const double yaw,
|
||||
const double r1,
|
||||
const double r2,
|
||||
const double d_zc,
|
||||
const double d_za,
|
||||
const size_t armors_num) const noexcept;
|
||||
|
||||
// Select the best armor to shoot
|
||||
// Return: selected idx in {0, 1, ..., armors_num - 1}
|
||||
int selectBestArmor(const std::vector<Eigen::Vector3d> &armor_positions,
|
||||
const Eigen::Vector3d &target_center,
|
||||
const double target_yaw,
|
||||
const double target_v_yaw,
|
||||
const size_t armors_num) const noexcept;
|
||||
|
||||
void calcYawAndPitch(const Eigen::Vector3d &p,
|
||||
const Eigen::Vector3d &barrel_pos_in_odom,
|
||||
double &yaw,
|
||||
double &pitch) const noexcept;
|
||||
|
||||
// Transform target position from odom frame to barrel frame for trajectory calculation
|
||||
Eigen::Vector3d transformToBarrelFrame(const Eigen::Vector3d &target_in_odom,
|
||||
std::shared_ptr<tf2_ros::Buffer> tf2_buffer) const;
|
||||
|
||||
bool isOnTarget(const double cur_yaw,
|
||||
const double cur_pitch,
|
||||
const double target_yaw,
|
||||
const double target_pitch,
|
||||
const double distance) const noexcept;
|
||||
|
||||
std::unique_ptr<TrajectoryCompensator> trajectory_compensator_;
|
||||
std::unique_ptr<ManualCompensator> manual_compensator_;
|
||||
|
||||
std::array<double, 3> rpy_;
|
||||
|
||||
double prediction_delay_;
|
||||
double controller_delay_;
|
||||
|
||||
double shooting_range_w_;
|
||||
double shooting_range_h_;
|
||||
|
||||
double max_tracking_v_yaw_;
|
||||
int overflow_count_;
|
||||
int transfer_thresh_;
|
||||
|
||||
double side_angle_;
|
||||
double min_switching_v_yaw_;
|
||||
|
||||
// Barrel frame for trajectory calculation
|
||||
bool use_barrel_frame_;
|
||||
bool barrel_offset_initialized_; // Whether barrel_offset has been initialized from TF
|
||||
Eigen::Vector3d barrel_offset_; // Barrel offset relative to pitch_link (from TF tree)
|
||||
|
||||
std::weak_ptr<rclcpp::Node> node_;
|
||||
};
|
||||
} // namespace fyt::auto_aim
|
||||
#endif // ARMOR_SOLVER_SOLVER_HPP_
|
||||
|
||||
@@ -0,0 +1,134 @@
|
||||
// Copyright Chen Jun 2023. Licensed under the MIT License.
|
||||
//
|
||||
// Additional modifications and features by Chengfu Zou, Labor. Licensed under Apache License 2.0.
|
||||
//
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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 ARMOR_SOLVER_SOLVER_NODE_HPP_
|
||||
#define ARMOR_SOLVER_SOLVER_NODE_HPP_
|
||||
|
||||
// ros2
|
||||
#include <message_filters/subscriber.h>
|
||||
#include <tf2_ros/buffer.h>
|
||||
#include <tf2_ros/create_timer_ros.h>
|
||||
#include <tf2_ros/message_filter.h>
|
||||
#include <tf2_ros/transform_listener.h>
|
||||
|
||||
#include <rcl_interfaces/msg/set_parameters_result.hpp>
|
||||
#include <rclcpp/rclcpp.hpp>
|
||||
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
|
||||
#include <visualization_msgs/msg/marker_array.hpp>
|
||||
// std
|
||||
#include <atomic>
|
||||
#include <memory>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
// project
|
||||
#include "armor_solver/armor_solver.hpp"
|
||||
#include "armor_solver/armor_tracker.hpp"
|
||||
#include "rm_interfaces/msg/armors.hpp"
|
||||
#include "rm_interfaces/msg/measurement.hpp"
|
||||
#include "rm_interfaces/msg/serial_receive_data.hpp"
|
||||
#include "rm_interfaces/msg/target.hpp"
|
||||
#include "rm_interfaces/srv/set_mode.hpp"
|
||||
#include "rm_utils/heartbeat.hpp"
|
||||
#include "rm_utils/logger/log.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
using tf2_filter = tf2_ros::MessageFilter<rm_interfaces::msg::Armors>;
|
||||
class ArmorSolverNode : public rclcpp::Node {
|
||||
public:
|
||||
explicit ArmorSolverNode(const rclcpp::NodeOptions &options);
|
||||
|
||||
private:
|
||||
rcl_interfaces::msg::SetParametersResult onSetParameters(
|
||||
const std::vector<rclcpp::Parameter> ¶meters);
|
||||
|
||||
void armorsCallback(const rm_interfaces::msg::Armors::SharedPtr armors_ptr);
|
||||
|
||||
void initMarkers() noexcept;
|
||||
|
||||
void publishMarkers(const rm_interfaces::msg::Target &target_msg,
|
||||
const rm_interfaces::msg::GimbalCmd &gimbal_cmd) noexcept;
|
||||
|
||||
|
||||
void setModeCallback(const std::shared_ptr<rm_interfaces::srv::SetMode::Request> request,
|
||||
std::shared_ptr<rm_interfaces::srv::SetMode::Response> response);
|
||||
|
||||
bool debug_mode_;
|
||||
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr
|
||||
on_set_parameters_callback_handle_;
|
||||
|
||||
// Heartbeat
|
||||
HeartBeatPublisher::SharedPtr heartbeat_;
|
||||
|
||||
// The time when the last message was received
|
||||
rclcpp::Time last_time_;
|
||||
double dt_;
|
||||
|
||||
// Armor tracker
|
||||
// Adaptive Q matrix parameters
|
||||
double s2qxyz_max_, s2qxyz_min_; // Position noise range
|
||||
double s2qyaw_max_, s2qyaw_min_; // Yaw noise range
|
||||
double s2qr_, s2qd_zc_; // Radius and height offset noise
|
||||
// R matrix parameters
|
||||
double r_x_, r_y_, r_z_, r_yaw_;
|
||||
double lost_time_thres_;
|
||||
std::unique_ptr<Tracker> tracker_;
|
||||
|
||||
// Armor Solver
|
||||
std::unique_ptr<Solver> solver_;
|
||||
|
||||
// Subscriber with tf2 message_filter
|
||||
std::string target_frame_;
|
||||
std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
|
||||
std::shared_ptr<tf2_ros::TransformListener> tf2_listener_;
|
||||
message_filters::Subscriber<rm_interfaces::msg::Armors> armors_sub_;
|
||||
rm_interfaces::msg::Target armor_target_;
|
||||
std::shared_ptr<tf2_filter> tf2_filter_;
|
||||
|
||||
// Measurement publisher
|
||||
rclcpp::Publisher<rm_interfaces::msg::Measurement>::SharedPtr measure_pub_;
|
||||
|
||||
// Publisher
|
||||
rclcpp::Publisher<rm_interfaces::msg::Target>::SharedPtr target_pub_;
|
||||
rclcpp::Publisher<rm_interfaces::msg::GimbalCmd>::SharedPtr gimbal_pub_;
|
||||
rclcpp::Subscription<rm_interfaces::msg::SerialReceiveData>::SharedPtr serial_sub_;
|
||||
rclcpp::TimerBase::SharedPtr pub_timer_;
|
||||
void timerCallback();
|
||||
std::atomic<double> bullet_speed_{0.0};
|
||||
std::atomic<double> bullet_speed_param_{20.0};
|
||||
std::atomic<bool> bullet_speed_debug_{false};
|
||||
std::atomic<int> shoot_rate_{3};
|
||||
|
||||
// Enable/Disable Armor Solver
|
||||
bool enable_;
|
||||
rclcpp::Service<rm_interfaces::srv::SetMode>::SharedPtr set_mode_srv_;
|
||||
|
||||
// Visualization marker publisher
|
||||
visualization_msgs::msg::Marker position_marker_;
|
||||
visualization_msgs::msg::Marker linear_v_marker_;
|
||||
visualization_msgs::msg::Marker angular_v_marker_;
|
||||
visualization_msgs::msg::Marker trajectory_marker_;
|
||||
visualization_msgs::msg::Marker armors_marker_;
|
||||
visualization_msgs::msg::Marker selection_marker_;
|
||||
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr marker_pub_;
|
||||
rm_interfaces::msg::GimbalCmd control_msg_last; //保存上一次的角度
|
||||
};
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
|
||||
#endif // ARMOR_SOLVER_SOLVER_NODE_HPP_
|
||||
@@ -0,0 +1,99 @@
|
||||
// Copyright Chen Jun 2023. Licensed under the MIT License.
|
||||
//
|
||||
// Additional modifications and features by Chengfu Zou, Labor. Licensed under Apache License 2.0.
|
||||
//
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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 ARMOR_SOLVER_TRACKER_HPP_
|
||||
#define ARMOR_SOLVER_TRACKER_HPP_
|
||||
|
||||
// std
|
||||
#include <memory>
|
||||
#include <string>
|
||||
// ros2
|
||||
#include <geometry_msgs/msg/point.hpp>
|
||||
#include <geometry_msgs/msg/quaternion.hpp>
|
||||
#include <geometry_msgs/msg/vector3.hpp>
|
||||
// third party
|
||||
#include <Eigen/Eigen>
|
||||
// project
|
||||
#include "rm_interfaces/msg/armors.hpp"
|
||||
#include "rm_interfaces/msg/target.hpp"
|
||||
#include "rm_utils/math/extended_kalman_filter.hpp"
|
||||
#include "armor_solver/motion_model.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
|
||||
enum class ArmorsNum { NORMAL_4 = 4, BALANCE_2 = 2, OUTPOST_3 = 3 };
|
||||
|
||||
class Tracker {
|
||||
public:
|
||||
Tracker(double max_match_distance, double max_match_yaw);
|
||||
|
||||
using Armors = rm_interfaces::msg::Armors;
|
||||
using Armor = rm_interfaces::msg::Armor;
|
||||
|
||||
void init(const Armors::SharedPtr &armors_msg) noexcept;
|
||||
|
||||
void update(const Armors::SharedPtr &armors_msg) noexcept;
|
||||
|
||||
void setMatchThreshold(double max_match_distance, double max_match_yaw_diff) noexcept;
|
||||
|
||||
enum State {
|
||||
LOST,
|
||||
DETECTING,
|
||||
TRACKING,
|
||||
TEMP_LOST,
|
||||
} tracker_state;
|
||||
|
||||
std::unique_ptr<RobotStateEKF> ekf;
|
||||
|
||||
int tracking_thres; // frame
|
||||
int lost_thres; // second
|
||||
|
||||
Armor tracked_armor;
|
||||
std::string tracked_id;
|
||||
ArmorsNum tracked_armors_num;
|
||||
Eigen::VectorXd measurement;
|
||||
Eigen::VectorXd target_state;
|
||||
|
||||
// To store another pair of armors message
|
||||
double d_za, another_r;
|
||||
|
||||
// To store offset relative to the reference plane
|
||||
double d_zc;
|
||||
|
||||
private:
|
||||
void initEKF(const Armor &a) noexcept;
|
||||
|
||||
void handleArmorJump(const Armor &a) noexcept;
|
||||
|
||||
double orientationToYaw(const geometry_msgs::msg::Quaternion &q) noexcept;
|
||||
|
||||
static Eigen::Vector3d getArmorPositionFromState(const Eigen::VectorXd &x) noexcept;
|
||||
|
||||
double max_match_distance_;
|
||||
double max_match_yaw_diff_;
|
||||
|
||||
int detect_count_;
|
||||
int lost_count_;
|
||||
|
||||
double last_yaw_;
|
||||
};
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
|
||||
#endif // ARMOR_SOLVER_ARMOR_TRACKER_HPP_
|
||||
@@ -0,0 +1,84 @@
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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 ARMOR_SOLVER_MOTION_MODEL_HPP_
|
||||
#define ARMOR_SOLVER_MOTION_MODEL_HPP_
|
||||
|
||||
// ceres
|
||||
#include <ceres/ceres.h>
|
||||
// project
|
||||
#include "rm_utils/math/extended_kalman_filter.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
|
||||
enum class MotionModel {
|
||||
CONSTANT_VELOCITY = 0, // Constant velocity
|
||||
CONSTANT_ROTATION = 1, // Constant rotation velocity
|
||||
CONSTANT_VEL_ROT = 2 // Constant velocity and rotation velocity
|
||||
};
|
||||
|
||||
// X_N: state dimension, Z_N: measurement dimension
|
||||
constexpr int X_N = 10, Z_N = 4;
|
||||
|
||||
struct Predict {
|
||||
explicit Predict(double dt, MotionModel model = MotionModel::CONSTANT_VEL_ROT)
|
||||
: dt(dt), model(model) {}
|
||||
|
||||
template <typename T>
|
||||
void operator()(const T x0[X_N], T x1[X_N]) {
|
||||
for (int i = 0; i < X_N; i++) {
|
||||
x1[i] = x0[i];
|
||||
}
|
||||
|
||||
// v_xyz
|
||||
if (model == MotionModel::CONSTANT_VEL_ROT || model == MotionModel::CONSTANT_VELOCITY) {
|
||||
// linear velocity
|
||||
x1[0] += x0[1] * dt;
|
||||
x1[2] += x0[3] * dt;
|
||||
x1[4] += x0[5] * dt;
|
||||
} else {
|
||||
// no velocity
|
||||
x1[1] *= 0.;
|
||||
x1[3] *= 0.;
|
||||
x1[5] *= 0.;
|
||||
}
|
||||
|
||||
// v_yaw
|
||||
if (model == MotionModel::CONSTANT_VEL_ROT || model == MotionModel::CONSTANT_ROTATION) {
|
||||
// angular velocity
|
||||
x1[6] += x0[7] * dt;
|
||||
} else {
|
||||
// no rotation
|
||||
x1[7] *= 0.;
|
||||
}
|
||||
}
|
||||
|
||||
double dt;
|
||||
MotionModel model;
|
||||
};
|
||||
|
||||
struct Measure {
|
||||
template <typename T>
|
||||
void operator()(const T x[Z_N], T z[Z_N]) {
|
||||
z[0] = x[0] - ceres::cos(x[6]) * x[8];
|
||||
z[1] = x[2] - ceres::sin(x[6]) * x[8];
|
||||
z[2] = x[4] + x[9];
|
||||
z[3] = x[6];
|
||||
}
|
||||
};
|
||||
|
||||
using RobotStateEKF = ExtendedKalmanFilter<X_N, Z_N, Predict, Measure>;
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
#endif
|
||||
37
src/rm_auto_aim/armor_solver/package.xml
Normal file
@@ -0,0 +1,37 @@
|
||||
<?xml version="1.0"?>
|
||||
<?xml-model
|
||||
href="http://download.ros.org/schema/package_format3.xsd"
|
||||
schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<package format="3">
|
||||
<name>armor_solver</name>
|
||||
<version>0.1.0</version>
|
||||
<description>A template for ROS packages.</description>
|
||||
<maintainer email="chen.junn@outlook.com">Chen Jun</maintainer>
|
||||
<license>BSD</license>
|
||||
<url type="website">https://github.com/chenjunnn/rm_auto_aim</url>
|
||||
<url type="bugtracker">https://github.com/chenjunnn/rm_auto_aim/issues</url>
|
||||
<author email="chen.junn@outlook.com">Chen Jun</author>
|
||||
|
||||
<!-- buildtool_depend: dependencies of the build process -->
|
||||
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||
|
||||
<!-- depend: build, export, and execution dependency -->
|
||||
<depend>rclcpp</depend>
|
||||
<depend>rclcpp_components</depend>
|
||||
<depend>eigen</depend>
|
||||
<depend>angles</depend>
|
||||
<depend>geometry_msgs</depend>
|
||||
<depend>visualization_msgs</depend>
|
||||
<depend>message_filters</depend>
|
||||
<depend>tf2_geometry_msgs</depend>
|
||||
<depend>rm_interfaces</depend>
|
||||
<depend>rm_utils</depend>
|
||||
|
||||
<test_depend>ament_lint_auto</test_depend>
|
||||
<test_depend>ament_lint_common</test_depend>
|
||||
<test_depend>ament_cmake_clang_format</test_depend>
|
||||
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
</export>
|
||||
</package>
|
||||
393
src/rm_auto_aim/armor_solver/src/armor_solver.cpp
Normal file
@@ -0,0 +1,393 @@
|
||||
// Created by Chengfu Zou
|
||||
// Maintained by Chengfu Zou, Labor
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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.
|
||||
|
||||
#include "armor_solver/armor_solver.hpp"
|
||||
// std
|
||||
#include <cmath>
|
||||
#include <cstddef>
|
||||
#include <stdexcept>
|
||||
// project
|
||||
#include "armor_solver/armor_solver_node.hpp"
|
||||
#include "rm_utils/logger/log.hpp"
|
||||
#include "rm_utils/math/utils.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
Solver::Solver(std::weak_ptr<rclcpp::Node> n) : node_(n) {
|
||||
auto node = node_.lock();
|
||||
|
||||
shooting_range_w_ = node->declare_parameter("solver.shooting_range_width", 0.135);
|
||||
shooting_range_h_ = node->declare_parameter("solver.shooting_range_height", 0.135);
|
||||
max_tracking_v_yaw_ = node->declare_parameter("solver.max_tracking_v_yaw", 6.0);
|
||||
prediction_delay_ = node->declare_parameter("solver.prediction_delay", 0.0);
|
||||
controller_delay_ = node->declare_parameter("solver.controller_delay", 0.0);
|
||||
side_angle_ = node->declare_parameter("solver.side_angle", 15.0);
|
||||
min_switching_v_yaw_ = node->declare_parameter("solver.min_switching_v_yaw", 1.0);
|
||||
|
||||
std::string compenstator_type = node->declare_parameter("solver.compensator_type", "ideal");
|
||||
trajectory_compensator_ = CompensatorFactory::createCompensator(compenstator_type);
|
||||
trajectory_compensator_->iteration_times = node->declare_parameter("solver.iteration_times", 20);
|
||||
if (node->has_parameter("solver.bullet_speed")) {
|
||||
trajectory_compensator_->velocity = node->get_parameter("solver.bullet_speed").as_double();
|
||||
} else {
|
||||
trajectory_compensator_->velocity = node->declare_parameter("solver.bullet_speed", 20.0);
|
||||
}
|
||||
trajectory_compensator_->gravity = node->declare_parameter("solver.gravity", 9.8);
|
||||
trajectory_compensator_->resistance = node->declare_parameter("solver.resistance", 0.001);
|
||||
|
||||
manual_compensator_ = std::make_unique<ManualCompensator>();
|
||||
auto angle_offset = node->declare_parameter("solver.angle_offset", std::vector<std::string>{});
|
||||
if (!manual_compensator_->updateMapFlow(angle_offset)) {
|
||||
FYT_WARN("armor_solver", "Manual compensator update failed!");
|
||||
}
|
||||
|
||||
// Barrel frame parameters for trajectory calculation
|
||||
// barrel_offset will be initialized from TF tree (barrel_link -> pitch_link)
|
||||
use_barrel_frame_ = node->declare_parameter("solver.use_barrel_frame", true);
|
||||
barrel_offset_ = Eigen::Vector3d(0.0, 0.0, 0.0);
|
||||
barrel_offset_initialized_ = false;
|
||||
FYT_INFO("armor_solver",
|
||||
"Barrel frame enabled: {}, offset will be loaded from TF (barrel_link -> pitch_link)",
|
||||
use_barrel_frame_);
|
||||
|
||||
state = State::TRACKING_ARMOR;
|
||||
overflow_count_ = 0;
|
||||
transfer_thresh_ = 5;
|
||||
|
||||
node.reset();
|
||||
}
|
||||
|
||||
rm_interfaces::msg::GimbalCmd Solver::solve(const rm_interfaces::msg::Target &target,
|
||||
const rclcpp::Time ¤t_time,
|
||||
std::shared_ptr<tf2_ros::Buffer> tf2_buffer_) {
|
||||
Eigen::Vector3d gimbal_pos_in_odom = Eigen::Vector3d::Zero();
|
||||
Eigen::Vector3d barrel_pos_in_odom = Eigen::Vector3d::Zero();
|
||||
Eigen::Matrix3d R_gimbal_to_odom = Eigen::Matrix3d::Identity();
|
||||
|
||||
// Get current roll, yaw and pitch of gimbal
|
||||
try {
|
||||
auto gimbal_tf =
|
||||
tf2_buffer_->lookupTransform(target.header.frame_id, "pitch_link", tf2::TimePointZero);
|
||||
auto msg_q = gimbal_tf.transform.rotation;
|
||||
|
||||
tf2::Quaternion tf_q;
|
||||
tf2::fromMsg(msg_q, tf_q);
|
||||
tf2::Matrix3x3 tf_mat(tf_q);
|
||||
tf_mat.getRPY(rpy_[0], rpy_[1], rpy_[2]);
|
||||
rpy_[1] = -rpy_[1];
|
||||
R_gimbal_to_odom << tf_mat[0][0], tf_mat[0][1], tf_mat[0][2], tf_mat[1][0], tf_mat[1][1],
|
||||
tf_mat[1][2], tf_mat[2][0], tf_mat[2][1], tf_mat[2][2];
|
||||
gimbal_pos_in_odom = Eigen::Vector3d(gimbal_tf.transform.translation.x,
|
||||
gimbal_tf.transform.translation.y,
|
||||
gimbal_tf.transform.translation.z);
|
||||
} catch (tf2::TransformException &ex) {
|
||||
FYT_ERROR("armor_solver", "{}", ex.what());
|
||||
throw ex;
|
||||
}
|
||||
|
||||
// Initialize barrel_offset from TF tree (only once)
|
||||
if (use_barrel_frame_ && !barrel_offset_initialized_) {
|
||||
try {
|
||||
auto barrel_tf =
|
||||
tf2_buffer_->lookupTransform("pitch_link", "barrel_link", tf2::TimePointZero);
|
||||
barrel_offset_ = Eigen::Vector3d(barrel_tf.transform.translation.x,
|
||||
barrel_tf.transform.translation.y,
|
||||
barrel_tf.transform.translation.z);
|
||||
barrel_offset_initialized_ = true;
|
||||
FYT_INFO("armor_solver",
|
||||
"Barrel offset initialized from TF: [{:.3f}, {:.3f}, {:.3f}]",
|
||||
barrel_offset_.x(),
|
||||
barrel_offset_.y(),
|
||||
barrel_offset_.z());
|
||||
} catch (tf2::TransformException &ex) {
|
||||
FYT_WARN(
|
||||
"armor_solver", "Failed to get barrel_link transform: {}, using default offset", ex.what());
|
||||
barrel_offset_ = Eigen::Vector3d(0.20, 0.0, -0.02);
|
||||
barrel_offset_initialized_ = true;
|
||||
}
|
||||
}
|
||||
|
||||
// Use flying time to approximately predict the position of target
|
||||
Eigen::Vector3d target_position(target.position.x, target.position.y, target.position.z);
|
||||
double target_yaw = target.yaw;
|
||||
|
||||
// Calculate flying time considering barrel offset for more accurate prediction
|
||||
Eigen::Vector3d target_for_flying_time = target_position;
|
||||
if (use_barrel_frame_) {
|
||||
// Approximate barrel position in odom frame for flying time calculation
|
||||
barrel_pos_in_odom = gimbal_pos_in_odom + R_gimbal_to_odom * barrel_offset_;
|
||||
target_for_flying_time = target_position - barrel_pos_in_odom;
|
||||
}
|
||||
|
||||
double flying_time = trajectory_compensator_->getFlyingTime(target_for_flying_time);
|
||||
double dt =
|
||||
(current_time - rclcpp::Time(target.header.stamp)).seconds() + flying_time + prediction_delay_;
|
||||
target_position.x() += dt * target.velocity.x;
|
||||
target_position.y() += dt * target.velocity.y;
|
||||
target_position.z() += dt * target.velocity.z;
|
||||
target_yaw += dt * target.v_yaw;
|
||||
|
||||
// Choose the best armor to shoot
|
||||
std::vector<Eigen::Vector3d> armor_positions = getArmorPositions(target_position,
|
||||
target_yaw,
|
||||
target.radius_1,
|
||||
target.radius_2,
|
||||
target.d_zc,
|
||||
target.d_za,
|
||||
target.armors_num);
|
||||
int idx =
|
||||
selectBestArmor(armor_positions, target_position, target_yaw, target.v_yaw, target.armors_num);
|
||||
auto chosen_armor_position = armor_positions.at(idx);
|
||||
if (chosen_armor_position.norm() < 0.1) {
|
||||
throw std::runtime_error("No valid armor to shoot");
|
||||
}
|
||||
|
||||
// Calculate yaw, pitch, distance
|
||||
double yaw, pitch;
|
||||
calcYawAndPitch(chosen_armor_position, barrel_pos_in_odom, yaw, pitch);
|
||||
double distance = chosen_armor_position.norm();
|
||||
|
||||
// Initialize gimbal_cmd
|
||||
rm_interfaces::msg::GimbalCmd gimbal_cmd;
|
||||
gimbal_cmd.header = target.header;
|
||||
gimbal_cmd.distance = distance;
|
||||
gimbal_cmd.fire_advice = isOnTarget(rpy_[2], rpy_[1], yaw, pitch, distance);
|
||||
|
||||
switch (state) {
|
||||
case TRACKING_ARMOR: {
|
||||
if (std::abs(target.v_yaw) > max_tracking_v_yaw_) {
|
||||
overflow_count_++;
|
||||
} else {
|
||||
overflow_count_ = 0;
|
||||
}
|
||||
|
||||
if (overflow_count_ > transfer_thresh_) {
|
||||
state = TRACKING_CENTER;
|
||||
}
|
||||
|
||||
// If isOnTarget() never returns true, adjust controller_delay to force the gimbal to move
|
||||
if (controller_delay_ != 0) {
|
||||
target_position.x() += controller_delay_ * target.velocity.x;
|
||||
target_position.y() += controller_delay_ * target.velocity.y;
|
||||
target_position.z() += controller_delay_ * target.velocity.z;
|
||||
target_yaw += controller_delay_ * target.v_yaw;
|
||||
armor_positions = getArmorPositions(target_position,
|
||||
target_yaw,
|
||||
target.radius_1,
|
||||
target.radius_2,
|
||||
target.d_zc,
|
||||
target.d_za,
|
||||
target.armors_num);
|
||||
chosen_armor_position = armor_positions.at(idx);
|
||||
gimbal_cmd.distance = chosen_armor_position.norm();
|
||||
if (chosen_armor_position.norm() < 0.1) {
|
||||
throw std::runtime_error("No valid armor to shoot");
|
||||
}
|
||||
calcYawAndPitch(chosen_armor_position, barrel_pos_in_odom, yaw, pitch);
|
||||
}
|
||||
break;
|
||||
}
|
||||
case TRACKING_CENTER: {
|
||||
if (std::abs(target.v_yaw) < max_tracking_v_yaw_) {
|
||||
overflow_count_++;
|
||||
} else {
|
||||
overflow_count_ = 0;
|
||||
}
|
||||
|
||||
if (overflow_count_ > transfer_thresh_) {
|
||||
state = TRACKING_ARMOR;
|
||||
overflow_count_ = 0;
|
||||
}
|
||||
gimbal_cmd.fire_advice = true;
|
||||
calcYawAndPitch(target_position, barrel_pos_in_odom, yaw, pitch);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// Compensate angle by angle_offset_map
|
||||
auto angle_offset =
|
||||
manual_compensator_->angleHardCorrect(target_position.head(2).norm(), target_position.z());
|
||||
double pitch_offset = angle_offset[0] * M_PI / 180;
|
||||
double yaw_offset = angle_offset[1] * M_PI / 180;
|
||||
double cmd_pitch = pitch + pitch_offset;
|
||||
double cmd_yaw = angles::normalize_angle(yaw + yaw_offset);
|
||||
|
||||
gimbal_cmd.yaw = cmd_yaw * 180 / M_PI;
|
||||
gimbal_cmd.pitch = cmd_pitch * 180 / M_PI;
|
||||
gimbal_cmd.yaw_diff = (cmd_yaw - rpy_[2]) * 180 / M_PI;
|
||||
gimbal_cmd.pitch_diff = (cmd_pitch - rpy_[1]) * 180 / M_PI;
|
||||
|
||||
if (gimbal_cmd.fire_advice) {
|
||||
FYT_DEBUG("armor_solver", "You Need Fire!");
|
||||
}
|
||||
return gimbal_cmd;
|
||||
}
|
||||
|
||||
void Solver::updateRuntimeParams(double max_tracking_v_yaw,
|
||||
double prediction_delay,
|
||||
double controller_delay,
|
||||
double side_angle,
|
||||
double min_switching_v_yaw,
|
||||
double shooting_range_w,
|
||||
double shooting_range_h) noexcept {
|
||||
max_tracking_v_yaw_ = max_tracking_v_yaw;
|
||||
prediction_delay_ = prediction_delay;
|
||||
controller_delay_ = controller_delay;
|
||||
side_angle_ = side_angle;
|
||||
min_switching_v_yaw_ = min_switching_v_yaw;
|
||||
shooting_range_w_ = shooting_range_w;
|
||||
shooting_range_h_ = shooting_range_h;
|
||||
}
|
||||
|
||||
bool Solver::isOnTarget(const double cur_yaw,
|
||||
const double cur_pitch,
|
||||
const double target_yaw,
|
||||
const double target_pitch,
|
||||
const double distance) const noexcept {
|
||||
// Judge whether to shoot
|
||||
double shooting_range_yaw = std::abs(atan2(shooting_range_w_ / 2, distance));
|
||||
double shooting_range_pitch = std::abs(atan2(shooting_range_h_ / 2, distance));
|
||||
// Limit the shooting area to 1 degree to avoid not shooting when distance is
|
||||
// too large
|
||||
shooting_range_yaw = std::max(shooting_range_yaw, 1.0 * M_PI / 180);
|
||||
shooting_range_pitch = std::max(shooting_range_pitch, 1.0 * M_PI / 180);
|
||||
if (std::abs(cur_yaw - target_yaw) < shooting_range_yaw &&
|
||||
std::abs(cur_pitch - target_pitch) < shooting_range_pitch) {
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
std::vector<Eigen::Vector3d> Solver::getArmorPositions(const Eigen::Vector3d &target_center,
|
||||
const double target_yaw,
|
||||
const double r1,
|
||||
const double r2,
|
||||
const double d_zc,
|
||||
const double d_za,
|
||||
const size_t armors_num) const noexcept {
|
||||
auto armor_positions = std::vector<Eigen::Vector3d>(armors_num, Eigen::Vector3d::Zero());
|
||||
// Calculate the position of each armor
|
||||
bool is_current_pair = true;
|
||||
double r = 0., target_dz = 0.;
|
||||
for (size_t i = 0; i < armors_num; i++) {
|
||||
double temp_yaw = target_yaw + i * (2 * M_PI / armors_num);
|
||||
if (armors_num == 4) {
|
||||
r = is_current_pair ? r1 : r2;
|
||||
target_dz = d_zc + (is_current_pair ? 0 : d_za);
|
||||
is_current_pair = !is_current_pair;
|
||||
} else {
|
||||
r = r1;
|
||||
target_dz = d_zc;
|
||||
}
|
||||
armor_positions[i] =
|
||||
target_center + Eigen::Vector3d(-r * cos(temp_yaw), -r * sin(temp_yaw), target_dz);
|
||||
}
|
||||
return armor_positions;
|
||||
}
|
||||
|
||||
int Solver::selectBestArmor(const std::vector<Eigen::Vector3d> &armor_positions,
|
||||
const Eigen::Vector3d &target_center,
|
||||
const double target_yaw,
|
||||
const double target_v_yaw,
|
||||
const size_t armors_num) const noexcept {
|
||||
// Angle between the car's center and the X-axis
|
||||
double alpha = std::atan2(target_center.y(), target_center.x());
|
||||
// Angle between the front of observed armor and the X-axis
|
||||
double beta = target_yaw;
|
||||
|
||||
// clang-format off
|
||||
Eigen::Matrix2d R_odom2center;
|
||||
Eigen::Matrix2d R_odom2armor;
|
||||
R_odom2center << std::cos(alpha), std::sin(alpha),
|
||||
-std::sin(alpha), std::cos(alpha);
|
||||
R_odom2armor << std::cos(beta), std::sin(beta),
|
||||
-std::sin(beta), std::cos(beta);
|
||||
// clang-format on
|
||||
Eigen::Matrix2d R_center2armor = R_odom2center.transpose() * R_odom2armor;
|
||||
|
||||
// Equal to (alpha - beta) in most cases
|
||||
double decision_angle = -std::asin(R_center2armor(0, 1));
|
||||
|
||||
// Angle thresh of the armor jump
|
||||
double theta = (target_v_yaw > 0 ? side_angle_ : -side_angle_) / 180.0 * M_PI;
|
||||
|
||||
// Avoid the frequent switch between two armor
|
||||
if (std::abs(target_v_yaw) < min_switching_v_yaw_) {
|
||||
theta = 0;
|
||||
}
|
||||
|
||||
double temp_angle = decision_angle + M_PI / armors_num - theta;
|
||||
|
||||
if (temp_angle < 0) {
|
||||
temp_angle += 2 * M_PI;
|
||||
}
|
||||
|
||||
int selected_id = static_cast<int>(temp_angle / (2 * M_PI / armors_num));
|
||||
return selected_id;
|
||||
}
|
||||
|
||||
void Solver::calcYawAndPitch(const Eigen::Vector3d &p,
|
||||
const Eigen::Vector3d &barrel_pos_in_odom,
|
||||
double &yaw,
|
||||
double &pitch) const noexcept {
|
||||
// Calculate yaw and pitch based on target position in odom frame
|
||||
yaw = atan2(p.y(), p.x());
|
||||
pitch = atan2(p.z(), p.head(2).norm());
|
||||
|
||||
// For trajectory compensation, we need to consider the barrel offset
|
||||
// The trajectory compensator calculates based on the distance from barrel to target
|
||||
Eigen::Vector3d target_in_barrel = p;
|
||||
if (use_barrel_frame_) {
|
||||
// Target position relative to barrel in odom frame
|
||||
target_in_barrel = p - barrel_pos_in_odom;
|
||||
|
||||
FYT_DEBUG(
|
||||
"armor_solver",
|
||||
"Barrel compensation: target [{:.3f}, {:.3f}, {:.3f}] -> barrel_rel [{:.3f}, {:.3f}, {:.3f}]",
|
||||
p.x(),
|
||||
p.y(),
|
||||
p.z(),
|
||||
target_in_barrel.x(),
|
||||
target_in_barrel.y(),
|
||||
target_in_barrel.z());
|
||||
}
|
||||
|
||||
if (double temp_pitch = pitch;
|
||||
trajectory_compensator_->compensate(target_in_barrel, temp_pitch)) {
|
||||
pitch = temp_pitch;
|
||||
}
|
||||
}
|
||||
|
||||
std::vector<std::pair<double, double>> Solver::getTrajectory() const noexcept {
|
||||
auto trajectory = trajectory_compensator_->getTrajectory(15, rpy_[1]);
|
||||
// Rotate
|
||||
for (auto &p : trajectory) {
|
||||
double x = p.first;
|
||||
double y = p.second;
|
||||
p.first = x * cos(rpy_[1]) + y * sin(rpy_[1]);
|
||||
p.second = -x * sin(rpy_[1]) + y * cos(rpy_[1]);
|
||||
}
|
||||
return trajectory;
|
||||
}
|
||||
|
||||
void Solver::setBulletSpeed(double bullet_speed) noexcept {
|
||||
if (std::isfinite(bullet_speed) && bullet_speed > 0.0) {
|
||||
trajectory_compensator_->velocity = bullet_speed;
|
||||
}
|
||||
}
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
|
||||
604
src/rm_auto_aim/armor_solver/src/armor_solver_node.cpp
Normal file
@@ -0,0 +1,604 @@
|
||||
// Copyright Chen Jun 2023. Licensed under the MIT License.
|
||||
//
|
||||
// Additional modifications and features by Chengfu Zou, Labor. Licensed under Apache License 2.0.
|
||||
//
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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.
|
||||
|
||||
#include "armor_solver/armor_solver_node.hpp"
|
||||
|
||||
// std
|
||||
#include <memory>
|
||||
#include <vector>
|
||||
// project
|
||||
#include "armor_solver/motion_model.hpp"
|
||||
#include "rm_utils/common.hpp"
|
||||
#include "rm_utils/heartbeat.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
ArmorSolverNode::ArmorSolverNode(const rclcpp::NodeOptions &options)
|
||||
: Node("armor_solver", options), solver_(nullptr) {
|
||||
// Register logger
|
||||
FYT_REGISTER_LOGGER("armor_solver", "~/fyt2024-log", INFO);
|
||||
FYT_INFO("armor_solver", "Starting ArmorSolverNode!");
|
||||
|
||||
debug_mode_ = this->declare_parameter("debug", true);
|
||||
bullet_speed_debug_.store(this->declare_parameter("bullet_speed_debug", false),
|
||||
std::memory_order_relaxed);
|
||||
shoot_rate_.store(this->declare_parameter("solver.shoot_rate", 3), std::memory_order_relaxed);
|
||||
if (this->has_parameter("solver.bullet_speed")) {
|
||||
bullet_speed_param_.store(this->get_parameter("solver.bullet_speed").as_double(),
|
||||
std::memory_order_relaxed);
|
||||
} else {
|
||||
bullet_speed_param_.store(this->declare_parameter("solver.bullet_speed", 20.0),
|
||||
std::memory_order_relaxed);
|
||||
}
|
||||
|
||||
// Tracker
|
||||
double max_match_distance = this->declare_parameter("tracker.max_match_distance", 0.2);
|
||||
double max_match_yaw_diff = this->declare_parameter("tracker.max_match_yaw_diff", 1.0);
|
||||
tracker_ = std::make_unique<Tracker>(max_match_distance, max_match_yaw_diff);
|
||||
tracker_->tracking_thres = this->declare_parameter("tracker.tracking_thres", 5);
|
||||
lost_time_thres_ = this->declare_parameter("tracker.lost_time_thres", 0.3);
|
||||
|
||||
// EKF
|
||||
// xa = x_armor, xc = x_robot_center
|
||||
// state: xc, v_xc, yc, v_yc, zc, v_zc, yaw, v_yaw, r, d_zc
|
||||
// measurement: p, y, d, yaw
|
||||
// f - Process function
|
||||
auto f = Predict(0.005);
|
||||
// h - Observation function
|
||||
auto h = Measure();
|
||||
// update_Q - process noise covariance matrix (Adaptive)
|
||||
// Adaptive parameters: noise varies based on velocity and angular velocity
|
||||
s2qxyz_max_ = declare_parameter("ekf.sigma2_q_xyz_max", 30.0);
|
||||
s2qxyz_min_ = declare_parameter("ekf.sigma2_q_xyz_min", 10.0);
|
||||
s2qyaw_max_ = declare_parameter("ekf.sigma2_q_yaw_max", 150.0);
|
||||
s2qyaw_min_ = declare_parameter("ekf.sigma2_q_yaw_min", 50.0);
|
||||
s2qr_ = declare_parameter("ekf.sigma2_q_r", 800.0);
|
||||
s2qd_zc_ = declare_parameter("ekf.sigma2_q_d_zc", 800.0);
|
||||
|
||||
auto u_q = [this]() {
|
||||
Eigen::Matrix<double, X_N, X_N> q;
|
||||
double t = dt_;
|
||||
|
||||
// Get current state for adaptive calculation
|
||||
const auto &state = tracker_->target_state;
|
||||
double vx = state(1), vy = state(3), v_yaw = state(7);
|
||||
|
||||
// Adaptive noise calculation:
|
||||
// - High angular velocity (spinning) -> lower position noise (trust position measurement more)
|
||||
// - High linear velocity (moving fast) -> lower yaw noise (trust yaw measurement more)
|
||||
double linear_vel = std::sqrt(vx * vx + vy * vy);
|
||||
double angular_vel = std::abs(v_yaw);
|
||||
|
||||
// Exponential decay: when velocity is high, noise approaches min value
|
||||
double s2q_xyz = std::exp(-angular_vel) * (s2qxyz_max_ - s2qxyz_min_) + s2qxyz_min_;
|
||||
double s2q_yaw = std::exp(-linear_vel) * (s2qyaw_max_ - s2qyaw_min_) + s2qyaw_min_;
|
||||
|
||||
double r = s2qr_, d_zc = s2qd_zc_;
|
||||
|
||||
// White noise integral model for position-velocity state
|
||||
double q_x_x = pow(t, 4) / 4 * s2q_xyz, q_x_vx = pow(t, 3) / 2 * s2q_xyz, q_vx_vx = pow(t, 2) * s2q_xyz;
|
||||
double q_y_y = pow(t, 4) / 4 * s2q_xyz, q_y_vy = pow(t, 3) / 2 * s2q_xyz, q_vy_vy = pow(t, 2) * s2q_xyz;
|
||||
double q_z_z = pow(t, 4) / 4 * s2q_xyz, q_z_vz = pow(t, 3) / 2 * s2q_xyz, q_vz_vz = pow(t, 2) * s2q_xyz;
|
||||
double q_yaw_yaw = pow(t, 4) / 4 * s2q_yaw, q_yaw_vyaw = pow(t, 3) / 2 * s2q_yaw,
|
||||
q_vyaw_vyaw = pow(t, 2) * s2q_yaw;
|
||||
double q_r = pow(t, 4) / 4 * r;
|
||||
double q_d_zc = pow(t, 4) / 4 * d_zc;
|
||||
// clang-format off
|
||||
// xc v_xc yc v_yc zc v_zc yaw v_yaw r d_zc
|
||||
q << q_x_x, q_x_vx, 0, 0, 0, 0, 0, 0, 0, 0,
|
||||
q_x_vx, q_vx_vx,0, 0, 0, 0, 0, 0, 0, 0,
|
||||
0, 0, q_y_y, q_y_vy, 0, 0, 0, 0, 0, 0,
|
||||
0, 0, q_y_vy, q_vy_vy,0, 0, 0, 0, 0, 0,
|
||||
0, 0, 0, 0, q_z_z, q_z_vz, 0, 0, 0, 0,
|
||||
0, 0, 0, 0, q_z_vz, q_vz_vz,0, 0, 0, 0,
|
||||
0, 0, 0, 0, 0, 0, q_yaw_yaw, q_yaw_vyaw, 0, 0,
|
||||
0, 0, 0, 0, 0, 0, q_yaw_vyaw, q_vyaw_vyaw,0, 0,
|
||||
0, 0, 0, 0, 0, 0, 0, 0, q_r, 0,
|
||||
0, 0, 0, 0, 0, 0, 0, 0, 0, q_d_zc;
|
||||
|
||||
// clang-format on
|
||||
return q;
|
||||
};
|
||||
// update_R - measurement noise covariance matrix
|
||||
// R scales with distance: farther target -> larger measurement noise
|
||||
r_x_ = declare_parameter("ekf.r_x", 0.05);
|
||||
r_y_ = declare_parameter("ekf.r_y", 0.05);
|
||||
r_z_ = declare_parameter("ekf.r_z", 0.05);
|
||||
r_yaw_ = declare_parameter("ekf.r_yaw", 0.02);
|
||||
auto u_r = [this](const Eigen::Matrix<double, Z_N, 1> &z) {
|
||||
Eigen::Matrix<double, Z_N, Z_N> r;
|
||||
// Calculate distance for better noise scaling
|
||||
double dist = std::sqrt(z[0] * z[0] + z[1] * z[1] + z[2] * z[2]);
|
||||
// Minimum distance to prevent numerical issues when target is very close
|
||||
dist = std::max(dist, 1.0);
|
||||
// clang-format off
|
||||
r << r_x_ * dist, 0, 0, 0,
|
||||
0, r_y_ * dist, 0, 0,
|
||||
0, 0, r_z_ * dist, 0,
|
||||
0, 0, 0, r_yaw_;
|
||||
// clang-format on
|
||||
return r;
|
||||
};
|
||||
// P - error estimate covariance matrix
|
||||
Eigen::DiagonalMatrix<double, X_N> p0;
|
||||
p0.setIdentity();
|
||||
tracker_->ekf = std::make_unique<RobotStateEKF>(f, h, u_q, u_r, p0);
|
||||
|
||||
// Subscriber with tf2 message_filter
|
||||
// tf2 relevant
|
||||
tf2_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
|
||||
// Create the timer interface before call to waitForTransform,
|
||||
// to avoid a tf2_ros::CreateTimerInterfaceException exception
|
||||
auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
|
||||
this->get_node_base_interface(), this->get_node_timers_interface());
|
||||
tf2_buffer_->setCreateTimerInterface(timer_interface);
|
||||
tf2_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf2_buffer_);
|
||||
// subscriber and filter
|
||||
armors_sub_.subscribe(this, "armor_detector/armors", rmw_qos_profile_sensor_data);
|
||||
target_frame_ = this->declare_parameter("target_frame", "odom");
|
||||
tf2_filter_ = std::make_shared<tf2_filter>(armors_sub_,
|
||||
*tf2_buffer_,
|
||||
target_frame_,
|
||||
10,
|
||||
this->get_node_logging_interface(),
|
||||
this->get_node_clock_interface(),
|
||||
std::chrono::duration<int>(1));
|
||||
// Register a callback with tf2_ros::MessageFilter to be called when
|
||||
// transforms are available
|
||||
tf2_filter_->registerCallback(&ArmorSolverNode::armorsCallback, this);
|
||||
|
||||
// Measurement publisher (for debug usage)
|
||||
measure_pub_ = this->create_publisher<rm_interfaces::msg::Measurement>("armor_solver/measurement",
|
||||
rclcpp::SensorDataQoS());
|
||||
|
||||
// Publisher
|
||||
target_pub_ = this->create_publisher<rm_interfaces::msg::Target>("armor_solver/target",
|
||||
rclcpp::SensorDataQoS());
|
||||
gimbal_pub_ = this->create_publisher<rm_interfaces::msg::GimbalCmd>("armor_solver/cmd_gimbal",
|
||||
rclcpp::SensorDataQoS());
|
||||
serial_sub_ = this->create_subscription<rm_interfaces::msg::SerialReceiveData>(
|
||||
"serial/receive",
|
||||
rclcpp::SensorDataQoS(),
|
||||
[this](const rm_interfaces::msg::SerialReceiveData::SharedPtr msg) {
|
||||
bullet_speed_.store(msg->bullet_speed, std::memory_order_relaxed);
|
||||
});
|
||||
// Timer 250 Hz
|
||||
pub_timer_ = this->create_wall_timer(std::chrono::milliseconds(4),
|
||||
std::bind(&ArmorSolverNode::timerCallback, this));
|
||||
armor_target_.header.frame_id = "";
|
||||
|
||||
// Enable/Disable Armor Solver
|
||||
enable_ = true;
|
||||
set_mode_srv_ = this->create_service<rm_interfaces::srv::SetMode>(
|
||||
"armor_solver/set_mode",
|
||||
std::bind(
|
||||
&ArmorSolverNode::setModeCallback, this, std::placeholders::_1, std::placeholders::_2));
|
||||
|
||||
if (debug_mode_) {
|
||||
initMarkers();
|
||||
}
|
||||
|
||||
on_set_parameters_callback_handle_ = this->add_on_set_parameters_callback(
|
||||
std::bind(&ArmorSolverNode::onSetParameters, this, std::placeholders::_1));
|
||||
|
||||
// Heartbeat
|
||||
heartbeat_ = HeartBeatPublisher::create(this);
|
||||
//初始化control_msg_last
|
||||
control_msg_last.yaw_diff = 0;
|
||||
control_msg_last.pitch_diff = 0;
|
||||
control_msg_last.distance = -1;
|
||||
control_msg_last.pitch = 0;
|
||||
control_msg_last.yaw = 0;
|
||||
control_msg_last.fire_advice = false;
|
||||
control_msg_last.shoot_rate =
|
||||
static_cast<uint8_t>(shoot_rate_.load(std::memory_order_relaxed));
|
||||
|
||||
}
|
||||
|
||||
void ArmorSolverNode::timerCallback() {
|
||||
if (solver_ == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (!enable_) {
|
||||
return;
|
||||
}
|
||||
|
||||
const bool bullet_speed_debug = bullet_speed_debug_.load(std::memory_order_relaxed);
|
||||
const double serial_bullet_speed = bullet_speed_.load(std::memory_order_relaxed);
|
||||
const double param_bullet_speed = bullet_speed_param_.load(std::memory_order_relaxed);
|
||||
if (bullet_speed_debug) {
|
||||
solver_->setBulletSpeed(param_bullet_speed);
|
||||
} else if (serial_bullet_speed > 0.0) {
|
||||
solver_->setBulletSpeed(serial_bullet_speed);
|
||||
} else {
|
||||
solver_->setBulletSpeed(param_bullet_speed);
|
||||
}
|
||||
|
||||
// Init message
|
||||
rm_interfaces::msg::GimbalCmd control_msg;
|
||||
int shoot_rate = shoot_rate_.load(std::memory_order_relaxed);
|
||||
if (shoot_rate < 0)
|
||||
{
|
||||
shoot_rate = 0;
|
||||
}
|
||||
else if (shoot_rate > 8)
|
||||
{
|
||||
shoot_rate = 8;
|
||||
}
|
||||
|
||||
// If target never detected
|
||||
if (armor_target_.header.frame_id.empty()) {
|
||||
control_msg = control_msg_last; //保持上一次的值
|
||||
control_msg.distance = -1; // 默认发送-1
|
||||
control_msg.fire_advice = false;//没识别不开火
|
||||
gimbal_pub_->publish(control_msg);
|
||||
return;
|
||||
}
|
||||
|
||||
if (armor_target_.tracking) {
|
||||
try {
|
||||
control_msg = solver_->solve(armor_target_, this->now(), tf2_buffer_);
|
||||
} catch (...) {
|
||||
FYT_ERROR("armor_solver", "Something went wrong in solver!");
|
||||
control_msg = control_msg_last; //保持上一次的值
|
||||
control_msg.distance = -1; // 默认发送-1
|
||||
control_msg.fire_advice = false;//没识别不开火
|
||||
}
|
||||
} else {
|
||||
control_msg = control_msg_last; //保持上一次的值
|
||||
control_msg.distance = -1; // 默认发送-1
|
||||
control_msg.fire_advice = false;//没识别不开火
|
||||
}
|
||||
control_msg.shoot_rate = static_cast<uint8_t>(shoot_rate);
|
||||
gimbal_pub_->publish(control_msg);
|
||||
control_msg_last = control_msg; //保存上一次的值
|
||||
|
||||
if (debug_mode_) {
|
||||
publishMarkers(armor_target_, control_msg);
|
||||
}
|
||||
}
|
||||
|
||||
void ArmorSolverNode::initMarkers() noexcept {
|
||||
// Visualization Marker Publisher
|
||||
// See http://wiki.ros.org/rviz/DisplayTypes/Marker
|
||||
position_marker_.ns = "position";
|
||||
position_marker_.type = visualization_msgs::msg::Marker::SPHERE;
|
||||
position_marker_.scale.x = position_marker_.scale.y = position_marker_.scale.z = 0.1;
|
||||
position_marker_.color.a = 1.0;
|
||||
position_marker_.color.g = 1.0;
|
||||
linear_v_marker_.type = visualization_msgs::msg::Marker::ARROW;
|
||||
linear_v_marker_.ns = "linear_v";
|
||||
linear_v_marker_.scale.x = 0.03;
|
||||
linear_v_marker_.scale.y = 0.05;
|
||||
linear_v_marker_.color.a = 1.0;
|
||||
linear_v_marker_.color.r = 1.0;
|
||||
linear_v_marker_.color.g = 1.0;
|
||||
angular_v_marker_.type = visualization_msgs::msg::Marker::ARROW;
|
||||
angular_v_marker_.ns = "angular_v";
|
||||
angular_v_marker_.scale.x = 0.03;
|
||||
angular_v_marker_.scale.y = 0.05;
|
||||
angular_v_marker_.color.a = 1.0;
|
||||
angular_v_marker_.color.b = 1.0;
|
||||
angular_v_marker_.color.g = 1.0;
|
||||
armors_marker_.ns = "filtered_armors";
|
||||
armors_marker_.type = visualization_msgs::msg::Marker::CUBE;
|
||||
armors_marker_.scale.x = 0.03;
|
||||
armors_marker_.scale.z = 0.125;
|
||||
armors_marker_.color.a = 1.0;
|
||||
armors_marker_.color.b = 1.0;
|
||||
selection_marker_.ns = "selection";
|
||||
selection_marker_.type = visualization_msgs::msg::Marker::SPHERE;
|
||||
selection_marker_.scale.x = selection_marker_.scale.y = selection_marker_.scale.z = 0.1;
|
||||
selection_marker_.color.a = 1.0;
|
||||
selection_marker_.color.g = 1.0;
|
||||
selection_marker_.color.r = 1.0;
|
||||
trajectory_marker_.ns = "trajectory";
|
||||
trajectory_marker_.type = visualization_msgs::msg::Marker::POINTS;
|
||||
trajectory_marker_.scale.x = 0.01;
|
||||
trajectory_marker_.scale.y = 0.01;
|
||||
trajectory_marker_.color.a = 1.0;
|
||||
trajectory_marker_.color.r = 1.0;
|
||||
trajectory_marker_.color.g = 0.75;
|
||||
trajectory_marker_.color.b = 0.79;
|
||||
trajectory_marker_.points.clear();
|
||||
|
||||
marker_pub_ =
|
||||
this->create_publisher<visualization_msgs::msg::MarkerArray>("armor_solver/marker", 10);
|
||||
}
|
||||
|
||||
void ArmorSolverNode::armorsCallback(const rm_interfaces::msg::Armors::SharedPtr armors_msg) {
|
||||
// Lazy initialize solver owing to weak_from_this() can't be called in constructor
|
||||
if (solver_ == nullptr) {
|
||||
solver_ = std::make_unique<Solver>(weak_from_this());
|
||||
solver_->updateRuntimeParams(this->get_parameter("solver.max_tracking_v_yaw").as_double(),
|
||||
this->get_parameter("solver.prediction_delay").as_double(),
|
||||
this->get_parameter("solver.controller_delay").as_double(),
|
||||
this->get_parameter("solver.side_angle").as_double(),
|
||||
this->get_parameter("solver.min_switching_v_yaw").as_double(),
|
||||
this->get_parameter("solver.shooting_range_width").as_double(),
|
||||
this->get_parameter("solver.shooting_range_height").as_double());
|
||||
solver_->setBulletSpeed(bullet_speed_param_.load(std::memory_order_relaxed));
|
||||
}
|
||||
|
||||
// Tranform armor position from image frame to world coordinate
|
||||
for (auto &armor : armors_msg->armors) {
|
||||
geometry_msgs::msg::PoseStamped ps;
|
||||
ps.header = armors_msg->header;
|
||||
ps.pose = armor.pose;
|
||||
try {
|
||||
armor.pose = tf2_buffer_->transform(ps, target_frame_).pose;
|
||||
} catch (const tf2::TransformException &ex) {
|
||||
FYT_ERROR("armor_solver", "Transform error: {}", ex.what());
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
// Filter abnormal armors
|
||||
armors_msg->armors.erase(std::remove_if(armors_msg->armors.begin(),
|
||||
armors_msg->armors.end(),
|
||||
[](const rm_interfaces::msg::Armor &armor) {
|
||||
return abs(armor.pose.position.z) > 2;
|
||||
}),
|
||||
armors_msg->armors.end());
|
||||
|
||||
// Init message
|
||||
rm_interfaces::msg::Measurement measure_msg;
|
||||
rm_interfaces::msg::Target target_msg;
|
||||
rclcpp::Time time = armors_msg->header.stamp;
|
||||
target_msg.header.stamp = time;
|
||||
target_msg.header.frame_id = target_frame_;
|
||||
|
||||
// Update tracker
|
||||
if (tracker_->tracker_state == Tracker::LOST) {
|
||||
tracker_->init(armors_msg);
|
||||
target_msg.tracking = false;
|
||||
} else {
|
||||
dt_ = (time - last_time_).seconds();
|
||||
tracker_->lost_thres = std::abs(static_cast<int>(lost_time_thres_ / dt_));
|
||||
if (tracker_->tracked_id == "outpost") {
|
||||
tracker_->ekf->setPredictFunc(Predict{dt_, MotionModel::CONSTANT_ROTATION});
|
||||
} else {
|
||||
tracker_->ekf->setPredictFunc(Predict{dt_, MotionModel::CONSTANT_VEL_ROT});
|
||||
}
|
||||
tracker_->update(armors_msg);
|
||||
// Publish measurement
|
||||
measure_msg.x = tracker_->measurement(0);
|
||||
measure_msg.y = tracker_->measurement(1);
|
||||
measure_msg.z = tracker_->measurement(2);
|
||||
measure_msg.yaw = tracker_->measurement(3);
|
||||
if (measure_pub_->get_subscription_count() > 0) {
|
||||
measure_pub_->publish(measure_msg);
|
||||
}
|
||||
|
||||
if (tracker_->tracker_state == Tracker::DETECTING) {
|
||||
target_msg.tracking = false;
|
||||
} else if (tracker_->tracker_state == Tracker::TRACKING ||
|
||||
tracker_->tracker_state == Tracker::TEMP_LOST) {
|
||||
target_msg.tracking = true;
|
||||
// Fill target message
|
||||
const auto &state = tracker_->target_state;
|
||||
target_msg.id = tracker_->tracked_id;
|
||||
target_msg.armors_num = static_cast<int>(tracker_->tracked_armors_num);
|
||||
target_msg.position.x = state(0);
|
||||
target_msg.velocity.x = state(1);
|
||||
target_msg.position.y = state(2);
|
||||
target_msg.velocity.y = state(3);
|
||||
target_msg.position.z = state(4);
|
||||
target_msg.velocity.z = state(5);
|
||||
target_msg.yaw = state(6);
|
||||
target_msg.v_yaw = state(7);
|
||||
target_msg.radius_1 = state(8);
|
||||
target_msg.radius_2 = tracker_->another_r;
|
||||
target_msg.d_zc = state(9);
|
||||
target_msg.d_za = tracker_->d_za;
|
||||
}
|
||||
}
|
||||
|
||||
// Store and Publish the target_msg
|
||||
armor_target_ = target_msg;
|
||||
target_pub_->publish(target_msg);
|
||||
|
||||
last_time_ = time;
|
||||
}
|
||||
|
||||
void ArmorSolverNode::publishMarkers(const rm_interfaces::msg::Target &target_msg,
|
||||
const rm_interfaces::msg::GimbalCmd &gimbal_cmd) noexcept {
|
||||
position_marker_.header = target_msg.header;
|
||||
linear_v_marker_.header = target_msg.header;
|
||||
angular_v_marker_.header = target_msg.header;
|
||||
armors_marker_.header = target_msg.header;
|
||||
selection_marker_.header = target_msg.header;
|
||||
trajectory_marker_.header = target_msg.header;
|
||||
|
||||
visualization_msgs::msg::MarkerArray marker_array;
|
||||
|
||||
if (target_msg.tracking) {
|
||||
double yaw = target_msg.yaw, r1 = target_msg.radius_1, r2 = target_msg.radius_2;
|
||||
double xc = target_msg.position.x, yc = target_msg.position.y, zc = target_msg.position.z;
|
||||
double vx = target_msg.velocity.x, vy = target_msg.velocity.y, vz = target_msg.velocity.z;
|
||||
double d_za = target_msg.d_za, d_zc = target_msg.d_zc;
|
||||
position_marker_.action = visualization_msgs::msg::Marker::ADD;
|
||||
position_marker_.pose.position.x = xc;
|
||||
position_marker_.pose.position.y = yc;
|
||||
position_marker_.pose.position.z = zc;
|
||||
|
||||
linear_v_marker_.action = visualization_msgs::msg::Marker::ADD;
|
||||
linear_v_marker_.points.clear();
|
||||
linear_v_marker_.points.emplace_back(position_marker_.pose.position);
|
||||
geometry_msgs::msg::Point arrow_end = position_marker_.pose.position;
|
||||
arrow_end.x += vx;
|
||||
arrow_end.y += vy;
|
||||
arrow_end.z += vz;
|
||||
linear_v_marker_.points.emplace_back(arrow_end);
|
||||
|
||||
angular_v_marker_.action = visualization_msgs::msg::Marker::ADD;
|
||||
angular_v_marker_.points.clear();
|
||||
angular_v_marker_.points.emplace_back(position_marker_.pose.position);
|
||||
arrow_end = position_marker_.pose.position;
|
||||
arrow_end.z += target_msg.v_yaw / M_PI;
|
||||
angular_v_marker_.points.emplace_back(arrow_end);
|
||||
|
||||
armors_marker_.action = visualization_msgs::msg::Marker::ADD;
|
||||
armors_marker_.scale.y = tracker_->tracked_armor.type == "small" ? 0.135 : 0.23;
|
||||
// Draw armors
|
||||
bool is_current_pair = true;
|
||||
size_t a_n = target_msg.armors_num;
|
||||
geometry_msgs::msg::Point p_a;
|
||||
double r = 0;
|
||||
for (size_t i = 0; i < a_n; i++) {
|
||||
double tmp_yaw = yaw + i * (2 * M_PI / a_n);
|
||||
// Only 4 armors has 2 radius and height
|
||||
if (a_n == 4) {
|
||||
r = is_current_pair ? r1 : r2;
|
||||
p_a.z = zc + d_zc + (is_current_pair ? 0 : d_za);
|
||||
is_current_pair = !is_current_pair;
|
||||
} else {
|
||||
r = r1;
|
||||
p_a.z = zc;
|
||||
}
|
||||
p_a.x = xc - r * cos(tmp_yaw);
|
||||
p_a.y = yc - r * sin(tmp_yaw);
|
||||
|
||||
armors_marker_.id = i;
|
||||
armors_marker_.pose.position = p_a;
|
||||
tf2::Quaternion q;
|
||||
q.setRPY(0, target_msg.id == "outpost" ? -0.2618 : 0.2618, tmp_yaw);
|
||||
armors_marker_.pose.orientation = tf2::toMsg(q);
|
||||
marker_array.markers.emplace_back(armors_marker_);
|
||||
}
|
||||
|
||||
selection_marker_.action = visualization_msgs::msg::Marker::ADD;
|
||||
selection_marker_.points.clear();
|
||||
selection_marker_.pose.position.y = gimbal_cmd.distance * sin(gimbal_cmd.yaw * M_PI / 180);
|
||||
selection_marker_.pose.position.x = gimbal_cmd.distance * cos(gimbal_cmd.yaw * M_PI / 180);
|
||||
selection_marker_.pose.position.z = gimbal_cmd.distance * sin(gimbal_cmd.pitch * M_PI / 180);
|
||||
|
||||
trajectory_marker_.action = visualization_msgs::msg::Marker::ADD;
|
||||
trajectory_marker_.points.clear();
|
||||
trajectory_marker_.header.frame_id = "pitch_link";
|
||||
for (const auto &point : solver_->getTrajectory()) {
|
||||
geometry_msgs::msg::Point p;
|
||||
p.x = point.first;
|
||||
p.z = point.second;
|
||||
trajectory_marker_.points.emplace_back(p);
|
||||
}
|
||||
if (gimbal_cmd.fire_advice) {
|
||||
trajectory_marker_.color.r = 0;
|
||||
trajectory_marker_.color.g = 1;
|
||||
trajectory_marker_.color.b = 0;
|
||||
} else {
|
||||
trajectory_marker_.color.r = 1;
|
||||
trajectory_marker_.color.g = 1;
|
||||
trajectory_marker_.color.b = 1;
|
||||
}
|
||||
|
||||
} else {
|
||||
position_marker_.action = visualization_msgs::msg::Marker::DELETE;
|
||||
linear_v_marker_.action = visualization_msgs::msg::Marker::DELETE;
|
||||
angular_v_marker_.action = visualization_msgs::msg::Marker::DELETE;
|
||||
armors_marker_.action = visualization_msgs::msg::Marker::DELETE;
|
||||
trajectory_marker_.action = visualization_msgs::msg::Marker::DELETE;
|
||||
selection_marker_.action = visualization_msgs::msg::Marker::DELETE;
|
||||
}
|
||||
|
||||
marker_array.markers.emplace_back(position_marker_);
|
||||
marker_array.markers.emplace_back(trajectory_marker_);
|
||||
marker_array.markers.emplace_back(linear_v_marker_);
|
||||
marker_array.markers.emplace_back(angular_v_marker_);
|
||||
marker_array.markers.emplace_back(armors_marker_);
|
||||
marker_array.markers.emplace_back(selection_marker_);
|
||||
marker_pub_->publish(marker_array);
|
||||
}
|
||||
|
||||
void ArmorSolverNode::setModeCallback(
|
||||
const std::shared_ptr<rm_interfaces::srv::SetMode::Request> request,
|
||||
std::shared_ptr<rm_interfaces::srv::SetMode::Response> response) {
|
||||
response->success = true;
|
||||
|
||||
VisionMode mode = static_cast<VisionMode>(request->mode);
|
||||
std::string mode_name = visionModeToString(mode);
|
||||
if (mode_name == "UNKNOWN") {
|
||||
FYT_ERROR("armor_solver", "Invalid mode: {}", request->mode);
|
||||
return;
|
||||
}
|
||||
|
||||
switch (mode) {
|
||||
case VisionMode::AUTO_AIM_RED:
|
||||
case VisionMode::AUTO_AIM_BLUE: {
|
||||
enable_ = true;
|
||||
break;
|
||||
}
|
||||
default: {
|
||||
enable_ = false;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
FYT_WARN("armor_solver", "Set Mode to {}", visionModeToString(mode));
|
||||
}
|
||||
|
||||
rcl_interfaces::msg::SetParametersResult ArmorSolverNode::onSetParameters(
|
||||
const std::vector<rclcpp::Parameter> ¶meters) {
|
||||
rcl_interfaces::msg::SetParametersResult result;
|
||||
result.successful = true;
|
||||
|
||||
for (const auto ¶m : parameters) {
|
||||
if (param.get_name() == "debug") {
|
||||
debug_mode_ = param.as_bool();
|
||||
} else if (param.get_name() == "bullet_speed_debug") {
|
||||
bullet_speed_debug_.store(param.as_bool(), std::memory_order_relaxed);
|
||||
} else if (param.get_name() == "solver.bullet_speed") {
|
||||
bullet_speed_param_.store(param.as_double(), std::memory_order_relaxed);
|
||||
} else if (param.get_name() == "solver.shoot_rate") {
|
||||
shoot_rate_.store(param.as_int(), std::memory_order_relaxed);
|
||||
} else if (param.get_name() == "tracker.max_match_distance") {
|
||||
const double max_match_distance = param.as_double();
|
||||
tracker_->setMatchThreshold(max_match_distance, this->get_parameter("tracker.max_match_yaw_diff").as_double());
|
||||
} else if (param.get_name() == "tracker.max_match_yaw_diff") {
|
||||
const double max_match_yaw_diff = param.as_double();
|
||||
tracker_->setMatchThreshold(this->get_parameter("tracker.max_match_distance").as_double(), max_match_yaw_diff);
|
||||
} else if (param.get_name() == "tracker.tracking_thres") {
|
||||
tracker_->tracking_thres = param.as_int();
|
||||
} else if (param.get_name() == "tracker.lost_time_thres") {
|
||||
lost_time_thres_ = param.as_double();
|
||||
}
|
||||
}
|
||||
|
||||
if (solver_ != nullptr) {
|
||||
solver_->updateRuntimeParams(this->get_parameter("solver.max_tracking_v_yaw").as_double(),
|
||||
this->get_parameter("solver.prediction_delay").as_double(),
|
||||
this->get_parameter("solver.controller_delay").as_double(),
|
||||
this->get_parameter("solver.side_angle").as_double(),
|
||||
this->get_parameter("solver.min_switching_v_yaw").as_double(),
|
||||
this->get_parameter("solver.shooting_range_width").as_double(),
|
||||
this->get_parameter("solver.shooting_range_height").as_double());
|
||||
solver_->setBulletSpeed(bullet_speed_param_.load(std::memory_order_relaxed));
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
|
||||
#include "rclcpp_components/register_node_macro.hpp"
|
||||
|
||||
// Register the component with class_loader.
|
||||
// This acts as a sort of entry point, allowing the component to be discoverable
|
||||
// when its library is being loaded into a running process.
|
||||
RCLCPP_COMPONENTS_REGISTER_NODE(fyt::auto_aim::ArmorSolverNode)
|
||||
|
||||
272
src/rm_auto_aim/armor_solver/src/armor_tracker.cpp
Normal file
@@ -0,0 +1,272 @@
|
||||
// Copyright Chen Jun 2023. Licensed under the MIT License.
|
||||
//
|
||||
// Additional modifications and features by Chengfu Zou, Labor. Licensed under Apache License 2.0.
|
||||
//
|
||||
// Copyright (C) FYT Vision Group. All rights reserved.
|
||||
//
|
||||
// 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.
|
||||
|
||||
#include "armor_solver/armor_tracker.hpp"
|
||||
// std
|
||||
#include <cfloat>
|
||||
#include <memory>
|
||||
#include <string>
|
||||
// ros2
|
||||
#include <tf2/LinearMath/Matrix3x3.h>
|
||||
#include <tf2/LinearMath/Quaternion.h>
|
||||
#include <tf2/convert.h>
|
||||
|
||||
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
|
||||
// third party
|
||||
#include <angles/angles.h>
|
||||
// project
|
||||
#include "rm_utils/logger/log.hpp"
|
||||
|
||||
namespace fyt::auto_aim {
|
||||
Tracker::Tracker(double max_match_distance, double max_match_yaw_diff)
|
||||
: tracker_state(LOST)
|
||||
, tracked_id(std::string(""))
|
||||
, measurement(Eigen::VectorXd::Zero(4))
|
||||
, target_state(Eigen::VectorXd::Zero(9))
|
||||
, max_match_distance_(max_match_distance)
|
||||
, max_match_yaw_diff_(max_match_yaw_diff)
|
||||
, detect_count_(0)
|
||||
, lost_count_(0)
|
||||
, last_yaw_(0) {}
|
||||
|
||||
void Tracker::setMatchThreshold(double max_match_distance, double max_match_yaw_diff) noexcept {
|
||||
max_match_distance_ = max_match_distance;
|
||||
max_match_yaw_diff_ = max_match_yaw_diff;
|
||||
}
|
||||
|
||||
void Tracker::init(const Armors::SharedPtr &armors_msg) noexcept {
|
||||
if (armors_msg->armors.empty()) {
|
||||
return;
|
||||
}
|
||||
|
||||
// Simply choose the armor that is closest to image center
|
||||
double min_distance = DBL_MAX;
|
||||
tracked_armor = armors_msg->armors[0];
|
||||
for (const auto &armor : armors_msg->armors) {
|
||||
if (armor.distance_to_image_center < min_distance) {
|
||||
min_distance = armor.distance_to_image_center;
|
||||
tracked_armor = armor;
|
||||
}
|
||||
}
|
||||
|
||||
initEKF(tracked_armor);
|
||||
FYT_INFO("armor_solver", "Init EKF!");
|
||||
|
||||
tracked_id = tracked_armor.number;
|
||||
tracker_state = DETECTING;
|
||||
|
||||
if (tracked_armor.type == "large" &&
|
||||
(tracked_id == "3" || tracked_id == "4" || tracked_id == "5")) {
|
||||
tracked_armors_num = ArmorsNum::BALANCE_2;
|
||||
} else if (tracked_id == "outpost") {
|
||||
tracked_armors_num = ArmorsNum::OUTPOST_3;
|
||||
} else {
|
||||
tracked_armors_num = ArmorsNum::NORMAL_4;
|
||||
}
|
||||
}
|
||||
|
||||
void Tracker::update(const Armors::SharedPtr &armors_msg) noexcept {
|
||||
// KF predict
|
||||
Eigen::VectorXd ekf_prediction = ekf->predict();
|
||||
|
||||
bool matched = false;
|
||||
// Use KF prediction as default target state if no matched armor is found
|
||||
target_state = ekf_prediction;
|
||||
|
||||
if (!armors_msg->armors.empty()) {
|
||||
// Find the closest armor with the same id
|
||||
Armor same_id_armor;
|
||||
int same_id_armors_count = 0;
|
||||
auto predicted_position = getArmorPositionFromState(ekf_prediction);
|
||||
double min_position_diff = DBL_MAX;
|
||||
double yaw_diff = DBL_MAX;
|
||||
for (const auto &armor : armors_msg->armors) {
|
||||
// Only consider armors with the same id
|
||||
if (armor.number == tracked_id) {
|
||||
same_id_armor = armor;
|
||||
same_id_armors_count++;
|
||||
// Calculate the difference between the predicted position and the
|
||||
// current armor position
|
||||
auto p = armor.pose.position;
|
||||
Eigen::Vector3d position_vec(p.x, p.y, p.z);
|
||||
double position_diff = (predicted_position - position_vec).norm();
|
||||
if (position_diff < min_position_diff) {
|
||||
// Find the closest armor
|
||||
min_position_diff = position_diff;
|
||||
yaw_diff = abs(orientationToYaw(armor.pose.orientation) - ekf_prediction(6));
|
||||
tracked_armor = armor;
|
||||
// Update tracked armor type
|
||||
if (tracked_armor.type == "large" &&
|
||||
(tracked_id == "3" || tracked_id == "4" || tracked_id == "5")) {
|
||||
tracked_armors_num = ArmorsNum::BALANCE_2;
|
||||
} else if (tracked_id == "outpost") {
|
||||
tracked_armors_num = ArmorsNum::OUTPOST_3;
|
||||
} else {
|
||||
tracked_armors_num = ArmorsNum::NORMAL_4;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Check if the distance and yaw difference of closest armor are within the
|
||||
// threshold
|
||||
if (min_position_diff < max_match_distance_ && yaw_diff < max_match_yaw_diff_) {
|
||||
// Matched armor found
|
||||
matched = true;
|
||||
auto p = tracked_armor.pose.position;
|
||||
// Update EKF
|
||||
double measured_yaw = orientationToYaw(tracked_armor.pose.orientation);
|
||||
measurement = Eigen::Vector4d(p.x, p.y, p.z, measured_yaw);
|
||||
target_state = ekf->update(measurement);
|
||||
} else if (same_id_armors_count == 1 && yaw_diff > max_match_yaw_diff_) {
|
||||
// Matched armor not found, but there is only one armor with the same id
|
||||
// and yaw has jumped, take this case as the target is spinning and armor
|
||||
// jumped
|
||||
handleArmorJump(same_id_armor);
|
||||
} else {
|
||||
// No matched armor found
|
||||
FYT_WARN("armor_solver", "No matched armor found!");
|
||||
}
|
||||
}
|
||||
|
||||
// Prevent radius from spreading
|
||||
if (target_state(8) < 0.12) {
|
||||
target_state(8) = 0.12;
|
||||
ekf->setState(target_state);
|
||||
} else if (target_state(8) > 0.4) {
|
||||
target_state(8) = 0.4;
|
||||
ekf->setState(target_state);
|
||||
}
|
||||
|
||||
// Tracking state machine
|
||||
if (tracker_state == DETECTING) {
|
||||
if (matched) {
|
||||
detect_count_++;
|
||||
if (detect_count_ > tracking_thres) {
|
||||
detect_count_ = 0;
|
||||
tracker_state = TRACKING;
|
||||
FYT_DEBUG("armor_solver", "Tracker state: TRACKING {}", tracked_id);
|
||||
}
|
||||
} else {
|
||||
detect_count_ = 0;
|
||||
tracker_state = LOST;
|
||||
FYT_DEBUG("armor_solver", "Tracker state: LOST {}", tracked_id);
|
||||
}
|
||||
} else if (tracker_state == TRACKING) {
|
||||
if (!matched) {
|
||||
tracker_state = TEMP_LOST;
|
||||
lost_count_++;
|
||||
FYT_DEBUG("armor_solver", "Tracker state: TEMP_LOST {}", tracked_id);
|
||||
}
|
||||
} else if (tracker_state == TEMP_LOST) {
|
||||
if (!matched) {
|
||||
lost_count_++;
|
||||
if (lost_count_ > lost_thres) {
|
||||
lost_count_ = 0;
|
||||
tracker_state = LOST;
|
||||
FYT_DEBUG("armor_solver", "Tracker state: LOST {}", tracked_id);
|
||||
}
|
||||
} else {
|
||||
tracker_state = TRACKING;
|
||||
lost_count_ = 0;
|
||||
FYT_DEBUG("armor_solver", "Tracker state: TRACKING {}", tracked_id);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void Tracker::initEKF(const Armor &a) noexcept {
|
||||
double xa = a.pose.position.x;
|
||||
double ya = a.pose.position.y;
|
||||
double za = a.pose.position.z;
|
||||
last_yaw_ = 0;
|
||||
double yaw = orientationToYaw(a.pose.orientation);
|
||||
|
||||
// Set initial position at 0.2m behind the target
|
||||
target_state = Eigen::VectorXd::Zero(X_N);
|
||||
double r = 0.26;
|
||||
double xc = xa + r * cos(yaw);
|
||||
double yc = ya + r * sin(yaw);
|
||||
double zc = za;
|
||||
d_za = 0, d_zc = 0, another_r = r;
|
||||
target_state << xc, 0, yc, 0, zc, 0, yaw, 0, r, d_zc;
|
||||
|
||||
ekf->setState(target_state);
|
||||
}
|
||||
|
||||
void Tracker::handleArmorJump(const Armor ¤t_armor) noexcept {
|
||||
double last_yaw = target_state(6);
|
||||
double yaw = orientationToYaw(current_armor.pose.orientation);
|
||||
|
||||
if (abs(yaw - last_yaw) > 0.4) {
|
||||
// Armor angle also jumped, take this case as target spinning
|
||||
target_state(6) = yaw;
|
||||
// Only 4 armors has 2 radius and height
|
||||
if (tracked_armors_num == ArmorsNum::NORMAL_4) {
|
||||
d_za = target_state(4) + target_state(9) - current_armor.pose.position.z;
|
||||
std::swap(target_state(8), another_r);
|
||||
d_zc = d_zc == 0 ? -d_za : 0;
|
||||
target_state(9) = d_zc;
|
||||
}
|
||||
FYT_DEBUG("armor_solver", "Armor Jump!");
|
||||
}
|
||||
|
||||
auto p = current_armor.pose.position;
|
||||
Eigen::Vector3d current_p(p.x, p.y, p.z);
|
||||
Eigen::Vector3d infer_p = getArmorPositionFromState(target_state);
|
||||
|
||||
if ((current_p - infer_p).norm() > max_match_distance_) {
|
||||
// If the distance between the current armor and the inferred armor is too
|
||||
// large, the state is wrong, reset center position and velocity in the
|
||||
// state
|
||||
d_zc = 0;
|
||||
double r = target_state(8);
|
||||
target_state(0) = p.x + r * cos(yaw); // xc
|
||||
target_state(1) = 0; // vxc
|
||||
target_state(2) = p.y + r * sin(yaw); // yc
|
||||
target_state(3) = 0; // vyc
|
||||
target_state(4) = p.z; // zc
|
||||
target_state(5) = 0; // vzc
|
||||
target_state(9) = d_zc; // d_zc
|
||||
FYT_WARN("armor_solver", "State wrong!");
|
||||
}
|
||||
|
||||
ekf->setState(target_state);
|
||||
}
|
||||
|
||||
double Tracker::orientationToYaw(const geometry_msgs::msg::Quaternion &q) noexcept {
|
||||
// Get armor yaw
|
||||
tf2::Quaternion tf_q;
|
||||
tf2::fromMsg(q, tf_q);
|
||||
double roll, pitch, yaw;
|
||||
tf2::Matrix3x3(tf_q).getRPY(roll, pitch, yaw);
|
||||
// Make yaw change continuous (-pi~pi to -inf~inf)
|
||||
yaw = last_yaw_ + angles::shortest_angular_distance(last_yaw_, yaw);
|
||||
last_yaw_ = yaw;
|
||||
return yaw;
|
||||
}
|
||||
|
||||
Eigen::Vector3d Tracker::getArmorPositionFromState(const Eigen::VectorXd &x) noexcept {
|
||||
// Calculate predicted position of the current armor
|
||||
double xc = x(0), yc = x(2), za = x(4) + x(9);
|
||||
double yaw = x(6), r = x(8);
|
||||
double xa = xc - r * cos(yaw);
|
||||
double ya = yc - r * sin(yaw);
|
||||
return Eigen::Vector3d(xa, ya, za);
|
||||
}
|
||||
|
||||
} // namespace fyt::auto_aim
|
||||
BIN
src/rm_auto_aim/armor_yolo_detect.zip
Normal file
BIN
src/rm_auto_aim/armor_yolo_detect/.DS_Store
vendored
Normal file
112
src/rm_auto_aim/armor_yolo_detect/CMakeLists.txt
Normal file
@@ -0,0 +1,112 @@
|
||||
cmake_minimum_required(VERSION 3.10)
|
||||
project(armor_yolo_detect)
|
||||
|
||||
## Set CMake policy to suppress OpenGL warning
|
||||
cmake_policy(SET CMP0072 NEW)
|
||||
|
||||
## Use C++17
|
||||
set(CMAKE_CXX_STANDARD 17)
|
||||
set(CMAKE_CXX_STANDARD_REQUIRED ON)
|
||||
|
||||
## Export compile commands for clangd
|
||||
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
|
||||
|
||||
#######################
|
||||
## Find dependencies ##
|
||||
#######################
|
||||
|
||||
find_package(ament_cmake_auto REQUIRED)
|
||||
find_package(OpenCV REQUIRED)
|
||||
find_package(fmt REQUIRED)
|
||||
find_package(Sophus REQUIRED)
|
||||
ament_auto_find_build_dependencies()
|
||||
|
||||
# TensorRT
|
||||
find_package(CUDA REQUIRED)
|
||||
|
||||
###########
|
||||
## Build ##
|
||||
###########
|
||||
|
||||
ament_auto_add_library(${PROJECT_NAME} SHARED
|
||||
src/armor_yolo_detector.cpp
|
||||
src/armor_yolo_detector_node.cpp
|
||||
src/trt_logger.cpp
|
||||
src/yolo_tensorrt.cpp
|
||||
)
|
||||
|
||||
ament_auto_add_executable(trt_inference_test
|
||||
trt_inference/trt_inference_test.cpp
|
||||
)
|
||||
|
||||
set(ONNXRUNTIME_ROOT ${CMAKE_CURRENT_SOURCE_DIR}/third_party/onnxruntime)
|
||||
set(ONNXRUNTIME_INCLUDE_DIR ${ONNXRUNTIME_ROOT}/include)
|
||||
set(ONNXRUNTIME_LIB_DIR ${ONNXRUNTIME_ROOT}/lib)
|
||||
|
||||
target_include_directories(trt_inference_test PRIVATE
|
||||
${ONNXRUNTIME_INCLUDE_DIR}
|
||||
)
|
||||
|
||||
target_link_directories(trt_inference_test PRIVATE
|
||||
${ONNXRUNTIME_LIB_DIR}
|
||||
)
|
||||
|
||||
target_link_libraries(trt_inference_test
|
||||
${PROJECT_NAME}
|
||||
${OpenCV_LIBS}
|
||||
onnxruntime
|
||||
)
|
||||
|
||||
set_target_properties(trt_inference_test PROPERTIES
|
||||
BUILD_RPATH "${ONNXRUNTIME_LIB_DIR}"
|
||||
INSTALL_RPATH "\$ORIGIN/../../share/${PROJECT_NAME}/third_party/onnxruntime/lib"
|
||||
)
|
||||
|
||||
target_include_directories(${PROJECT_NAME} PUBLIC
|
||||
${OpenCV_INCLUDE_DIRS}
|
||||
${EIGEN3_INCLUDE_DIRS}
|
||||
${Sophus_INCLUDE_DIRS}
|
||||
${CUDA_INCLUDE_DIRS}
|
||||
)
|
||||
|
||||
target_link_libraries(${PROJECT_NAME}
|
||||
${OpenCV_LIBS}
|
||||
${CUDA_LIBRARIES}
|
||||
nvinfer
|
||||
nvinfer_plugin
|
||||
nvonnxparser
|
||||
fmt::fmt
|
||||
)
|
||||
|
||||
rclcpp_components_register_node(${PROJECT_NAME}
|
||||
PLUGIN armor_yolo_detect::ArmorYoloDetectorNode
|
||||
EXECUTABLE armor_yolo_detector_node
|
||||
)
|
||||
|
||||
#############
|
||||
## Testing ##
|
||||
#############
|
||||
|
||||
if(BUILD_TESTING)
|
||||
find_package(ament_lint_auto REQUIRED)
|
||||
list(APPEND AMENT_LINT_AUTO_EXCLUDE
|
||||
ament_cmake_copyright
|
||||
ament_cmake_uncrustify
|
||||
ament_cmake_cpplint
|
||||
ament_cmake_lint_cmake
|
||||
)
|
||||
ament_lint_auto_find_test_dependencies()
|
||||
endif()
|
||||
|
||||
#############
|
||||
## Install ##
|
||||
#############
|
||||
|
||||
ament_auto_package(
|
||||
USE_SCOPED_HEADER_INSTALL_DIR
|
||||
INSTALL_TO_SHARE
|
||||
config
|
||||
model
|
||||
launch
|
||||
third_party
|
||||
)
|
||||
423
src/rm_auto_aim/armor_yolo_detect/README.md
Normal file
@@ -0,0 +1,423 @@
|
||||
# Armor YOLO Detect
|
||||
|
||||
基于 **YOLOv5** 和 **TensorRT** 的装甲板检测节点,用于 RoboMaster 机甲大师竞赛的自瞄系统。
|
||||
|
||||
本节点作为原始二值化+灯条匹配方案(`armor_detector`)的替代方案,使用深度学习模型直接检测装甲板,提供更好的泛化能力和检测精度。
|
||||
|
||||
---
|
||||
|
||||
## 目录
|
||||
|
||||
- [简介](#简介)
|
||||
- [目录结构](#目录结构)
|
||||
- [模型说明](#模型说明)
|
||||
- [快速开始](#快速开始)
|
||||
- [环境依赖](#环境依赖)
|
||||
- [模型转换](#模型转换)
|
||||
- [编译项目](#编译项目)
|
||||
- [运行节点](#运行节点)
|
||||
- [详细使用](#详细使用)
|
||||
- [参数说明](#参数说明)
|
||||
- [与原始方案对比](#与原始方案对比)
|
||||
- [调试方法](#调试方法)
|
||||
- [常见问题](#常见问题)
|
||||
|
||||
---
|
||||
|
||||
## 简介
|
||||
|
||||
本项目使用 RobotDetectionModel 中的 0526 版本 ONNX 模型,该模型:
|
||||
- **网络结构**: 魔改 YOLOv5,backbone 采用 MobileNetV3
|
||||
- **训练数据**: 约 15K 张高质量数据集
|
||||
- **输入**: 640x640 RGB 彩色图像
|
||||
- **输出**: 25200x85 矩阵,包含四个角点、置信度、颜色分类和数字分类
|
||||
- **推理设备**: Jetson NX (TensorRT 加速)
|
||||
|
||||
---
|
||||
|
||||
## 目录结构
|
||||
|
||||
```
|
||||
armor_yolo_detect/
|
||||
├── include/armor_yolo_detect/
|
||||
│ ├── types.hpp # 数据结构:Armor, YoloObject, NumberClass 等
|
||||
│ ├── yolo_tensorrt.hpp/cpp # TensorRT 推理引擎封装
|
||||
│ ├── trt_logger.hpp/cpp # TensorRT 日志工具
|
||||
│ ├── armor_yolo_detector.hpp/cpp # 检测器类封装
|
||||
│ └── armor_yolo_detector_node.hpp/cpp # ROS2 节点实现
|
||||
├── src/ # 源文件
|
||||
├── config/
|
||||
│ └── params.yaml # 默认参数配置
|
||||
├── model/
|
||||
│ └── label.yaml # 类别标签定义
|
||||
└── launch/
|
||||
└── armor_yolo_detector.launch.py # 启动文件
|
||||
```
|
||||
|
||||
---
|
||||
|
||||
## 模型说明
|
||||
|
||||
### 输入格式
|
||||
|
||||
| 属性 | 值 |
|
||||
|------|-----|
|
||||
| 尺寸 | 640 x 640 |
|
||||
| 通道 | 3 (RGB 彩色图) |
|
||||
| 数据类型 | float32 |
|
||||
| 归一化 | [0, 1] |
|
||||
| 格式 | NCHW (TensorRT) |
|
||||
|
||||
### 输出格式 (25200 x 85)
|
||||
|
||||
每行代表一个检测候选框,85 个通道含义如下:
|
||||
|
||||
| 索引 | 含义 | 说明 |
|
||||
|------|------|------|
|
||||
| 0-7 | 四个角点坐标 | (x1,y1,x2,y2,x3,y3,x4,y4),左上角开始逆时针 |
|
||||
| 8 | 置信度 | sigmoid 激活 |
|
||||
| 9-12 | 颜色分类 | 红0, 蓝1, 灰2, 紫3 |
|
||||
| 13-21 | 数字分类 | 0:G, 1:1, 2:2, 3:3, 4:4, 5:5, 6:O, 7:Bs, 8:Bb |
|
||||
|
||||
### 类别定义
|
||||
|
||||
**数字类别 (13-21):**
|
||||
- `0`: G (哨兵 Guard)
|
||||
- `1`: 1 (一号步兵)
|
||||
- `2`: 2 (二号步兵)
|
||||
- `3`: 3 (三号步兵)
|
||||
- `4`: 4 (四号步兵)
|
||||
- `5`: 5 (五号步兵)
|
||||
- `6`: O (前哨站 Outpost)
|
||||
- `7`: Bs (基地小装甲)
|
||||
- `8`: Bb (基地大装甲)
|
||||
|
||||
**颜色类别 (9-12):**
|
||||
- `0`: RED (红色敌方)
|
||||
- `1`: BLUE (蓝色敌方)
|
||||
- `2`: GRAY (灰色-无威胁)
|
||||
- `3`: PURPLE (紫色-无威胁)
|
||||
|
||||
---
|
||||
|
||||
## 快速开始
|
||||
|
||||
### 环境依赖
|
||||
|
||||
#### Jetson NX 平台
|
||||
|
||||
Jetson NX 已预装 CUDA,需要安装 TensorRT:
|
||||
|
||||
```bash
|
||||
# 1. 安装 Python TensorRT 和相关包
|
||||
sudo apt update
|
||||
sudo apt install python3-libnvinfer-dev tensorrt
|
||||
|
||||
# 2. 验证安装
|
||||
python3 -c "import tensorrt; print(tensorrt.__version__)"
|
||||
|
||||
# 3. 确保 CUDA 环境变量
|
||||
echo 'export LD_LIBRARY_PATH=/usr/lib/aarch64-linux-gnu:$LD_LIBRARY_PATH' >> ~/.bashrc
|
||||
source ~/.bashrc
|
||||
```
|
||||
|
||||
#### 其他依赖
|
||||
|
||||
```bash
|
||||
# OpenCV (通常已预装)
|
||||
sudo apt install libopencv-dev python3-opencv
|
||||
|
||||
# ROS2 Humble (参考 rm_auto_aim 原有配置)
|
||||
# 确保已正确安装并 source
|
||||
source /opt/ros/humble/setup.bash
|
||||
```
|
||||
|
||||
### 模型转换
|
||||
|
||||
**注意**: 模型转换需要在有 NVIDIA GPU 的机器上进行(可以是 Jetson NX 本身)
|
||||
|
||||
```bash
|
||||
# 进入工作空间
|
||||
cd ~/colcon_ws
|
||||
|
||||
# 一键转换(推荐)
|
||||
# 语法: ./scripts/build_engine.sh --onnx <onnx路径> --engine <输出engine路径> [选项]
|
||||
./tools/scripts/build_engine.sh \
|
||||
--onnx ../RobotDetectionModel/Model/0526.onnx \
|
||||
--engine src/rm_auto_aim/armor_yolo_detect/model/yolov5_0526.engine \
|
||||
--fp16
|
||||
|
||||
# 完整参数说明:
|
||||
# --onnx 输入 ONNX 模型路径
|
||||
# --engine 输出 TensorRT engine 路径
|
||||
# --batch-size 批处理大小,默认 1
|
||||
# --workspace 工作空间大小(GB),默认 4
|
||||
# --fp16 启用 FP16 加速(Jetson NX 推荐)
|
||||
# --int8 启用 INT8 加速(需要校准)
|
||||
# --verbose 显示详细日志
|
||||
```
|
||||
|
||||
**转换成功标志**:
|
||||
```
|
||||
Building TensorRT engine from ONNX...
|
||||
[TensorRT] INFO: [MemUsageChange] Init CUDA engine for native input sizes...
|
||||
Engine built successfully!
|
||||
Engine saved to: /path/to/engine
|
||||
Conversion completed!
|
||||
```
|
||||
|
||||
### 编译项目
|
||||
|
||||
```bash
|
||||
cd ~/colcon_ws
|
||||
|
||||
# 编译 armor_yolo_detect 包
|
||||
colcon build --packages-select armor_yolo_detect
|
||||
|
||||
# 如果需要编译依赖
|
||||
colcon build --packages-select armor_yolo_detect rm_interfaces rm_utils
|
||||
|
||||
# source 环境
|
||||
source install/setup.bash
|
||||
```
|
||||
|
||||
### 运行节点
|
||||
|
||||
```bash
|
||||
# 启动 YOLO 检测节点(红色敌方)
|
||||
ros2 launch armor_yolo_detect armor_yolo_detector.launch.py detect_color:=0
|
||||
|
||||
# 蓝色敌方
|
||||
ros2 launch armor_yolo_detect armor_yolo_detector.launch.py detect_color:=1
|
||||
|
||||
# 启用调试模式
|
||||
ros2 launch armor_yolo_detect armor_yolo_detector.launch.py debug:=true
|
||||
```
|
||||
|
||||
---
|
||||
|
||||
## 详细使用
|
||||
|
||||
### 完整启动示例
|
||||
|
||||
```bash
|
||||
# 1. Source 环境
|
||||
source /opt/ros/humble/setup.bash
|
||||
source ~/colcon_ws/install/setup.bash
|
||||
|
||||
# 2. 启动相机节点(如有需要)
|
||||
# ros2 launch hik_camera hik_camera.launch.py
|
||||
|
||||
# 3. 启动 YOLO 检测节点
|
||||
ros2 launch armor_yolo_detect armor_yolo_detector.launch.py \
|
||||
detect_color:=0 \
|
||||
conf_threshold:=0.7 \
|
||||
nms_threshold:=0.5 \
|
||||
debug:=true
|
||||
```
|
||||
|
||||
### 参数配置
|
||||
|
||||
可以在 `config/params.yaml` 中修改默认参数:
|
||||
|
||||
```yaml
|
||||
/**:
|
||||
ros__parameters:
|
||||
# 检测参数
|
||||
conf_threshold: 0.65 # 置信度阈值 (0.0-1.0)
|
||||
nms_threshold: 0.45 # NMS 阈值 (0.0-1.0)
|
||||
detect_color: 0 # 0=红色, 1=蓝色
|
||||
|
||||
# 处理参数
|
||||
max_queue_size: 3 # 图像队列大小
|
||||
process_every_n_frames: 1 # 每N帧处理一次
|
||||
|
||||
# PnP 和 BA
|
||||
use_ba: true # 是否使用 BA 优化
|
||||
|
||||
# 坐标系
|
||||
target_frame: "odom" # TF 目标坐标系
|
||||
|
||||
# 调试
|
||||
debug: false
|
||||
debug:
|
||||
enable_terminal_log: true
|
||||
enable_markers: true
|
||||
enable_result_img: true
|
||||
debug_log_interval_frames: 30
|
||||
```
|
||||
|
||||
### 动态调参
|
||||
|
||||
运行时可以通过命令行调整参数:
|
||||
|
||||
```bash
|
||||
# 降低置信度阈值(检测更多目标)
|
||||
ros2 param set /armor_yolo_detector conf_threshold 0.5
|
||||
|
||||
# 提高 NMS 阈值(合并更近的目标)
|
||||
ros2 param set /armor_yolo_detector nms_threshold 0.6
|
||||
|
||||
# 切换敌方颜色
|
||||
ros2 service call /armor_detector/set_mode rm_interfaces/srv/SetMode "{mode: 0}" # 红
|
||||
ros2 service call /armor_detector/set_mode rm_interfaces/srv/SetMode "{mode: 1}" # 蓝
|
||||
```
|
||||
|
||||
---
|
||||
|
||||
## 参数说明
|
||||
|
||||
| 参数 | 类型 | 默认值 | 说明 |
|
||||
|------|------|--------|------|
|
||||
| `conf_threshold` | float | 0.65 | 置信度阈值,低于此值的检测框将被丢弃 |
|
||||
| `nms_threshold` | float | 0.45 | NMS(非极大值抑制)阈值,用于去除重叠框 |
|
||||
| `detect_color` | int | 0 | 0=红色敌方, 1=蓝色敌方 |
|
||||
| `max_queue_size` | int | 3 | 图像队列最大长度 |
|
||||
| `process_every_n_frames` | int | 1 | 每 N 帧处理一次,用于降低帧率 |
|
||||
| `use_ba` | bool | true | 启用 BA(束调整)优化位姿 |
|
||||
| `target_frame` | string | "odom" | TF 变换的目标坐标系 |
|
||||
| `debug` | bool | false | 是否启用调试模式 |
|
||||
|
||||
### 建议参数调整
|
||||
|
||||
- **低光照环境**: 降低 `conf_threshold` 到 0.5-0.6
|
||||
- **误检测多**: 提高 `conf_threshold` 到 0.7-0.8
|
||||
- **目标频繁切换**: 提高 `nms_threshold` 到 0.5-0.6
|
||||
|
||||
---
|
||||
|
||||
## 与原始方案对比
|
||||
|
||||
| 特性 | armor_detector (原始) | armor_yolo_detect (本项目) |
|
||||
|------|----------------------|---------------------------|
|
||||
| 检测方式 | 二值化 + 灯条匹配 | YOLOv5 深度学习 |
|
||||
| 输入 | 灰度图 | RGB 彩色图 |
|
||||
| 泛化能力 | 依赖阈值参数 | 模型自适应 |
|
||||
| 计算量 | 较低 | 较高 |
|
||||
| 依赖 | OpenCV | TensorRT + CUDA |
|
||||
| 输出话题 | `/armor_detector/armors` | `/armor_detector/armors` |
|
||||
| 消息类型 | `rm_interfaces::msg::Armors` | `rm_interfaces::msg::Armors` |
|
||||
|
||||
**切换方案**:
|
||||
```bash
|
||||
# 原始二值化方案
|
||||
ros2 launch rm_bringup bringup.launch.py detector:=binary
|
||||
|
||||
# YOLO 方案
|
||||
ros2 launch rm_bringup bringup.launch.py detector:=yolo
|
||||
```
|
||||
|
||||
---
|
||||
|
||||
## 调试方法
|
||||
|
||||
### 启用调试输出
|
||||
|
||||
```bash
|
||||
ros2 launch armor_yolo_detect armor_yolo_detector.launch.py debug:=true
|
||||
```
|
||||
|
||||
### 查看话题
|
||||
|
||||
```bash
|
||||
# 查看检测结果图像
|
||||
ros2 topic echo /armor_yolo_detector/result_img
|
||||
|
||||
# 查看原始图像(需要 remap)
|
||||
ros2 run image_view image_view --image /armor_yolo_detector/result_img
|
||||
|
||||
# 查看检测到的装甲板
|
||||
ros2 topic echo /armor_detector/armors
|
||||
|
||||
# 查看可视化标记
|
||||
ros2 topic echo /armor_detector/marker
|
||||
```
|
||||
|
||||
### Rviz2 可视化
|
||||
|
||||
```bash
|
||||
# 启动 rviz2
|
||||
rviz2
|
||||
|
||||
# 添加 Display:
|
||||
# - Image: /armor_yolo_detector/result_img
|
||||
# - Marker: /armor_detector/marker
|
||||
```
|
||||
|
||||
### 发表话题重映射
|
||||
|
||||
如果相机话题名称不同,需要重映射:
|
||||
|
||||
```bash
|
||||
ros2 launch armor_yolo_detect armor_yolo_detector.launch.py \
|
||||
remappings:="[('/image_raw', '/your_camera/image_raw'), ('/camera_info', '/your_camera/camera_info')]"
|
||||
```
|
||||
|
||||
---
|
||||
|
||||
## 常见问题
|
||||
|
||||
### Q1: 编译报错 "TensorRT not found"
|
||||
|
||||
```bash
|
||||
# 确保安装了 TensorRT 开发包
|
||||
sudo apt install tensorrt libnvinfer-dev python3-libnvinfer-dev
|
||||
|
||||
# 验证
|
||||
dpkg -l | grep TensorRT
|
||||
```
|
||||
|
||||
### Q2: 运行时报错 "Engine file not found"
|
||||
|
||||
```bash
|
||||
# 检查 engine 文件是否存在
|
||||
ls -la ~/colcon_ws/src/rm_auto_aim/armor_yolo_detect/model/
|
||||
|
||||
# 如果没有,执行模型转换
|
||||
./tools/scripts/build_engine.sh --onnx ../RobotDetectionModel/Model/0526.onnx --engine src/rm_auto_aim/armor_yolo_detect/model/yolov5_0526.engine --fp16
|
||||
```
|
||||
|
||||
### Q3: 检测框错位或翻转
|
||||
|
||||
检查图像输入格式,确保是 RGB 输入:
|
||||
```bash
|
||||
# 查看图像编码
|
||||
ros2 topic echo /hik_camera/image_raw --field encoding
|
||||
```
|
||||
如果是 `mono8`(灰度),需要修改代码中的预处理逻辑。
|
||||
|
||||
### Q4: Jetson NX 上推理速度慢
|
||||
|
||||
```bash
|
||||
# 1. 确保使用 FP16
|
||||
./tools/scripts/build_engine.sh --onnx model.onnx --engine model.engine --fp16
|
||||
|
||||
# 2. 检查电源模式(JetPack 4.6+)
|
||||
sudo nvpmodel -m 0 # 最大性能模式
|
||||
|
||||
# 3. 查看推理时间
|
||||
ros2 run rqt_top rqt_top
|
||||
```
|
||||
|
||||
### Q5: 如何同时运行多个检测器进行对比?
|
||||
|
||||
```bash
|
||||
# 终端 1: 运行原始方案
|
||||
ros2 launch armor_detector armor_detector.launch.py
|
||||
|
||||
# 终端 2: 运行 YOLO 方案(修改节点名避免冲突)
|
||||
ros2 launch armor_yolo_detect armor_yolo_detector.launch.py \
|
||||
--remap /armor_detector/armors:=/armor_detector/armors_yolo
|
||||
```
|
||||
|
||||
---
|
||||
|
||||
## 维护者
|
||||
|
||||
- **开发者**: chenyy
|
||||
- **邮箱**: 3289288508@qq.com
|
||||
- **开源**: https://github.com/chenjunnn/rm_auto_aim
|
||||
|
||||
## 协议
|
||||
|
||||
本项目基于 Apache 2.0 协议开源。
|
||||
1
src/rm_auto_aim/armor_yolo_detect/build/.built_by
Normal file
@@ -0,0 +1 @@
|
||||
colcon
|
||||
@@ -0,0 +1,97 @@
|
||||
{
|
||||
"configurations" :
|
||||
[
|
||||
{
|
||||
"directories" :
|
||||
[
|
||||
{
|
||||
"build" : ".",
|
||||
"hasInstallRule" : true,
|
||||
"jsonFile" : "directory-.-cdda605c8f0fc3a94bdb.json",
|
||||
"minimumCMakeVersion" :
|
||||
{
|
||||
"string" : "3.12"
|
||||
},
|
||||
"projectIndex" : 0,
|
||||
"source" : ".",
|
||||
"targetIndexes" :
|
||||
[
|
||||
0,
|
||||
1,
|
||||
2,
|
||||
3,
|
||||
4
|
||||
]
|
||||
}
|
||||
],
|
||||
"name" : "",
|
||||
"projects" :
|
||||
[
|
||||
{
|
||||
"directoryIndexes" :
|
||||
[
|
||||
0
|
||||
],
|
||||
"name" : "armor_yolo_detect",
|
||||
"targetIndexes" :
|
||||
[
|
||||
0,
|
||||
1,
|
||||
2,
|
||||
3,
|
||||
4
|
||||
]
|
||||
}
|
||||
],
|
||||
"targets" :
|
||||
[
|
||||
{
|
||||
"directoryIndex" : 0,
|
||||
"id" : "armor_yolo_detect::@6890427a1f51a3e7e1df",
|
||||
"jsonFile" : "target-armor_yolo_detect-c59ff32f9b5cff5c0a75.json",
|
||||
"name" : "armor_yolo_detect",
|
||||
"projectIndex" : 0
|
||||
},
|
||||
{
|
||||
"directoryIndex" : 0,
|
||||
"id" : "armor_yolo_detect_uninstall::@6890427a1f51a3e7e1df",
|
||||
"jsonFile" : "target-armor_yolo_detect_uninstall-7f4bd7e3de607a0ee4c2.json",
|
||||
"name" : "armor_yolo_detect_uninstall",
|
||||
"projectIndex" : 0
|
||||
},
|
||||
{
|
||||
"directoryIndex" : 0,
|
||||
"id" : "armor_yolo_detector_node::@6890427a1f51a3e7e1df",
|
||||
"jsonFile" : "target-armor_yolo_detector_node-a828a80270a5533985cb.json",
|
||||
"name" : "armor_yolo_detector_node",
|
||||
"projectIndex" : 0
|
||||
},
|
||||
{
|
||||
"directoryIndex" : 0,
|
||||
"id" : "trt_inference_test::@6890427a1f51a3e7e1df",
|
||||
"jsonFile" : "target-trt_inference_test-eca372c678304d0a96b7.json",
|
||||
"name" : "trt_inference_test",
|
||||
"projectIndex" : 0
|
||||
},
|
||||
{
|
||||
"directoryIndex" : 0,
|
||||
"id" : "uninstall::@6890427a1f51a3e7e1df",
|
||||
"jsonFile" : "target-uninstall-b7ab4eaa92f8931a51e0.json",
|
||||
"name" : "uninstall",
|
||||
"projectIndex" : 0
|
||||
}
|
||||
]
|
||||
}
|
||||
],
|
||||
"kind" : "codemodel",
|
||||
"paths" :
|
||||
{
|
||||
"build" : "/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect",
|
||||
"source" : "/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect"
|
||||
},
|
||||
"version" :
|
||||
{
|
||||
"major" : 2,
|
||||
"minor" : 3
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,115 @@
|
||||
{
|
||||
"backtraceGraph" :
|
||||
{
|
||||
"commands" :
|
||||
[
|
||||
"_install",
|
||||
"install",
|
||||
"include",
|
||||
"find_package"
|
||||
],
|
||||
"files" :
|
||||
[
|
||||
"/opt/ros/humble/share/ament_cmake_core/cmake/symlink_install/install.cmake",
|
||||
"/opt/ros/humble/share/ament_cmake_core/cmake/ament_cmake_symlink_install-extras.cmake",
|
||||
"/opt/ros/humble/share/ament_cmake_core/cmake/ament_cmake_coreConfig.cmake",
|
||||
"/opt/ros/humble/share/ament_cmake/cmake/ament_cmake_export_dependencies-extras.cmake",
|
||||
"/opt/ros/humble/share/ament_cmake/cmake/ament_cmakeConfig.cmake",
|
||||
"/opt/ros/humble/share/ament_cmake_auto/cmake/ament_cmake_auto-extras.cmake",
|
||||
"/opt/ros/humble/share/ament_cmake_auto/cmake/ament_cmake_autoConfig.cmake",
|
||||
"CMakeLists.txt"
|
||||
],
|
||||
"nodes" :
|
||||
[
|
||||
{
|
||||
"file" : 7
|
||||
},
|
||||
{
|
||||
"command" : 3,
|
||||
"file" : 7,
|
||||
"line" : 18,
|
||||
"parent" : 0
|
||||
},
|
||||
{
|
||||
"file" : 6,
|
||||
"parent" : 1
|
||||
},
|
||||
{
|
||||
"command" : 2,
|
||||
"file" : 6,
|
||||
"line" : 41,
|
||||
"parent" : 2
|
||||
},
|
||||
{
|
||||
"file" : 5,
|
||||
"parent" : 3
|
||||
},
|
||||
{
|
||||
"command" : 3,
|
||||
"file" : 5,
|
||||
"line" : 17,
|
||||
"parent" : 4
|
||||
},
|
||||
{
|
||||
"file" : 4,
|
||||
"parent" : 5
|
||||
},
|
||||
{
|
||||
"command" : 2,
|
||||
"file" : 4,
|
||||
"line" : 41,
|
||||
"parent" : 6
|
||||
},
|
||||
{
|
||||
"file" : 3,
|
||||
"parent" : 7
|
||||
},
|
||||
{
|
||||
"command" : 3,
|
||||
"file" : 3,
|
||||
"line" : 15,
|
||||
"parent" : 8
|
||||
},
|
||||
{
|
||||
"file" : 2,
|
||||
"parent" : 9
|
||||
},
|
||||
{
|
||||
"command" : 2,
|
||||
"file" : 2,
|
||||
"line" : 41,
|
||||
"parent" : 10
|
||||
},
|
||||
{
|
||||
"file" : 1,
|
||||
"parent" : 11
|
||||
},
|
||||
{
|
||||
"command" : 1,
|
||||
"file" : 1,
|
||||
"line" : 47,
|
||||
"parent" : 12
|
||||
},
|
||||
{
|
||||
"command" : 0,
|
||||
"file" : 0,
|
||||
"line" : 43,
|
||||
"parent" : 13
|
||||
}
|
||||
]
|
||||
},
|
||||
"installers" :
|
||||
[
|
||||
{
|
||||
"backtrace" : 14,
|
||||
"component" : "Unspecified",
|
||||
"scriptFile" : "build/armor_yolo_detect/ament_cmake_symlink_install/ament_cmake_symlink_install.cmake",
|
||||
"type" : "script"
|
||||
}
|
||||
],
|
||||
"paths" :
|
||||
{
|
||||
"build" : ".",
|
||||
"source" : "."
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,54 @@
|
||||
{
|
||||
"cmake" :
|
||||
{
|
||||
"generator" :
|
||||
{
|
||||
"multiConfig" : false,
|
||||
"name" : "Unix Makefiles"
|
||||
},
|
||||
"paths" :
|
||||
{
|
||||
"cmake" : "/usr/bin/cmake",
|
||||
"cpack" : "/usr/bin/cpack",
|
||||
"ctest" : "/usr/bin/ctest",
|
||||
"root" : "/usr/share/cmake-3.22"
|
||||
},
|
||||
"version" :
|
||||
{
|
||||
"isDirty" : false,
|
||||
"major" : 3,
|
||||
"minor" : 22,
|
||||
"patch" : 1,
|
||||
"string" : "3.22.1",
|
||||
"suffix" : ""
|
||||
}
|
||||
},
|
||||
"objects" :
|
||||
[
|
||||
{
|
||||
"jsonFile" : "codemodel-v2-27f63d19a4af901a6613.json",
|
||||
"kind" : "codemodel",
|
||||
"version" :
|
||||
{
|
||||
"major" : 2,
|
||||
"minor" : 3
|
||||
}
|
||||
}
|
||||
],
|
||||
"reply" :
|
||||
{
|
||||
"client-colcon-cmake" :
|
||||
{
|
||||
"codemodel-v2" :
|
||||
{
|
||||
"jsonFile" : "codemodel-v2-27f63d19a4af901a6613.json",
|
||||
"kind" : "codemodel",
|
||||
"version" :
|
||||
{
|
||||
"major" : 2,
|
||||
"minor" : 3
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,134 @@
|
||||
{
|
||||
"backtrace" : 13,
|
||||
"backtraceGraph" :
|
||||
{
|
||||
"commands" :
|
||||
[
|
||||
"add_custom_target",
|
||||
"include",
|
||||
"find_package"
|
||||
],
|
||||
"files" :
|
||||
[
|
||||
"/opt/ros/humble/share/ament_cmake_core/cmake/ament_cmake_uninstall_target-extras.cmake",
|
||||
"/opt/ros/humble/share/ament_cmake_core/cmake/ament_cmake_coreConfig.cmake",
|
||||
"/opt/ros/humble/share/ament_cmake/cmake/ament_cmake_export_dependencies-extras.cmake",
|
||||
"/opt/ros/humble/share/ament_cmake/cmake/ament_cmakeConfig.cmake",
|
||||
"/opt/ros/humble/share/ament_cmake_auto/cmake/ament_cmake_auto-extras.cmake",
|
||||
"/opt/ros/humble/share/ament_cmake_auto/cmake/ament_cmake_autoConfig.cmake",
|
||||
"CMakeLists.txt"
|
||||
],
|
||||
"nodes" :
|
||||
[
|
||||
{
|
||||
"file" : 6
|
||||
},
|
||||
{
|
||||
"command" : 2,
|
||||
"file" : 6,
|
||||
"line" : 18,
|
||||
"parent" : 0
|
||||
},
|
||||
{
|
||||
"file" : 5,
|
||||
"parent" : 1
|
||||
},
|
||||
{
|
||||
"command" : 1,
|
||||
"file" : 5,
|
||||
"line" : 41,
|
||||
"parent" : 2
|
||||
},
|
||||
{
|
||||
"file" : 4,
|
||||
"parent" : 3
|
||||
},
|
||||
{
|
||||
"command" : 2,
|
||||
"file" : 4,
|
||||
"line" : 17,
|
||||
"parent" : 4
|
||||
},
|
||||
{
|
||||
"file" : 3,
|
||||
"parent" : 5
|
||||
},
|
||||
{
|
||||
"command" : 1,
|
||||
"file" : 3,
|
||||
"line" : 41,
|
||||
"parent" : 6
|
||||
},
|
||||
{
|
||||
"file" : 2,
|
||||
"parent" : 7
|
||||
},
|
||||
{
|
||||
"command" : 2,
|
||||
"file" : 2,
|
||||
"line" : 15,
|
||||
"parent" : 8
|
||||
},
|
||||
{
|
||||
"file" : 1,
|
||||
"parent" : 9
|
||||
},
|
||||
{
|
||||
"command" : 1,
|
||||
"file" : 1,
|
||||
"line" : 41,
|
||||
"parent" : 10
|
||||
},
|
||||
{
|
||||
"file" : 0,
|
||||
"parent" : 11
|
||||
},
|
||||
{
|
||||
"command" : 0,
|
||||
"file" : 0,
|
||||
"line" : 40,
|
||||
"parent" : 12
|
||||
}
|
||||
]
|
||||
},
|
||||
"id" : "armor_yolo_detect_uninstall::@6890427a1f51a3e7e1df",
|
||||
"name" : "armor_yolo_detect_uninstall",
|
||||
"paths" :
|
||||
{
|
||||
"build" : ".",
|
||||
"source" : "."
|
||||
},
|
||||
"sourceGroups" :
|
||||
[
|
||||
{
|
||||
"name" : "",
|
||||
"sourceIndexes" :
|
||||
[
|
||||
0
|
||||
]
|
||||
},
|
||||
{
|
||||
"name" : "CMake Rules",
|
||||
"sourceIndexes" :
|
||||
[
|
||||
1
|
||||
]
|
||||
}
|
||||
],
|
||||
"sources" :
|
||||
[
|
||||
{
|
||||
"backtrace" : 13,
|
||||
"isGenerated" : true,
|
||||
"path" : "build/armor_yolo_detect/CMakeFiles/armor_yolo_detect_uninstall",
|
||||
"sourceGroupIndex" : 0
|
||||
},
|
||||
{
|
||||
"backtrace" : 0,
|
||||
"isGenerated" : true,
|
||||
"path" : "build/armor_yolo_detect/CMakeFiles/armor_yolo_detect_uninstall.rule",
|
||||
"sourceGroupIndex" : 1
|
||||
}
|
||||
],
|
||||
"type" : "UTILITY"
|
||||
}
|
||||
@@ -0,0 +1,551 @@
|
||||
{
|
||||
"artifacts" :
|
||||
[
|
||||
{
|
||||
"path" : "armor_yolo_detector_node"
|
||||
}
|
||||
],
|
||||
"backtrace" : 2,
|
||||
"backtraceGraph" :
|
||||
{
|
||||
"commands" :
|
||||
[
|
||||
"add_executable",
|
||||
"rclcpp_components_register_node",
|
||||
"target_link_libraries",
|
||||
"ament_target_dependencies",
|
||||
"target_include_directories"
|
||||
],
|
||||
"files" :
|
||||
[
|
||||
"/opt/ros/humble/share/rclcpp_components/cmake/rclcpp_components_register_node.cmake",
|
||||
"CMakeLists.txt",
|
||||
"/opt/ros/humble/share/ament_cmake_target_dependencies/cmake/ament_target_dependencies.cmake"
|
||||
],
|
||||
"nodes" :
|
||||
[
|
||||
{
|
||||
"file" : 1
|
||||
},
|
||||
{
|
||||
"command" : 1,
|
||||
"file" : 1,
|
||||
"line" : 81,
|
||||
"parent" : 0
|
||||
},
|
||||
{
|
||||
"command" : 0,
|
||||
"file" : 0,
|
||||
"line" : 72,
|
||||
"parent" : 1
|
||||
},
|
||||
{
|
||||
"command" : 3,
|
||||
"file" : 0,
|
||||
"line" : 73,
|
||||
"parent" : 1
|
||||
},
|
||||
{
|
||||
"command" : 2,
|
||||
"file" : 2,
|
||||
"line" : 145,
|
||||
"parent" : 3
|
||||
},
|
||||
{
|
||||
"command" : 4,
|
||||
"file" : 2,
|
||||
"line" : 141,
|
||||
"parent" : 3
|
||||
}
|
||||
]
|
||||
},
|
||||
"compileGroups" :
|
||||
[
|
||||
{
|
||||
"compileCommandFragments" :
|
||||
[
|
||||
{
|
||||
"fragment" : "-std=gnu++17"
|
||||
}
|
||||
],
|
||||
"defines" :
|
||||
[
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"define" : "DEFAULT_RMW_IMPLEMENTATION=rmw_fastrtps_cpp"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"define" : "RCUTILS_ENABLE_FAULT_INJECTION"
|
||||
}
|
||||
],
|
||||
"includes" :
|
||||
[
|
||||
{
|
||||
"backtrace" : 5,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rclcpp"
|
||||
},
|
||||
{
|
||||
"backtrace" : 5,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/class_loader"
|
||||
},
|
||||
{
|
||||
"backtrace" : 5,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rclcpp_components"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/ament_index_cpp"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/libstatistics_collector"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/builtin_interfaces"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rosidl_runtime_c"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rcutils"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rosidl_typesupport_interface"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/fastcdr"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rosidl_runtime_cpp"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rosidl_typesupport_fastrtps_cpp"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rmw"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rosidl_typesupport_fastrtps_c"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rosidl_typesupport_introspection_c"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rosidl_typesupport_introspection_cpp"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rcl"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rcl_interfaces"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rcl_logging_interface"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rcl_yaml_param_parser"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/libyaml_vendor"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/tracetools"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rcpputils"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/statistics_msgs"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rosgraph_msgs"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rosidl_typesupport_cpp"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/rosidl_typesupport_c"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"isSystem" : true,
|
||||
"path" : "/opt/ros/humble/include/composition_interfaces"
|
||||
}
|
||||
],
|
||||
"language" : "CXX",
|
||||
"languageStandard" :
|
||||
{
|
||||
"backtraces" :
|
||||
[
|
||||
4
|
||||
],
|
||||
"standard" : "17"
|
||||
},
|
||||
"sourceIndexes" :
|
||||
[
|
||||
0
|
||||
]
|
||||
}
|
||||
],
|
||||
"id" : "armor_yolo_detector_node::@6890427a1f51a3e7e1df",
|
||||
"link" :
|
||||
{
|
||||
"commandFragments" :
|
||||
[
|
||||
{
|
||||
"fragment" : "",
|
||||
"role" : "flags"
|
||||
},
|
||||
{
|
||||
"fragment" : "-Wl,-rpath,/opt/ros/humble/lib",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"fragment" : "/opt/ros/humble/lib/libcomponent_manager.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"fragment" : "/opt/ros/humble/lib/librclcpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/liblibstatistics_collector.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librcl.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librmw_implementation.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librcl_logging_spdlog.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librcl_logging_interface.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librcl_yaml_param_parser.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libyaml.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_fastrtps_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_fastrtps_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_introspection_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_introspection_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librosgraph_msgs__rosidl_generator_py.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librosgraph_msgs__rosidl_generator_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_fastrtps_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_fastrtps_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_introspection_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_introspection_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libstatistics_msgs__rosidl_generator_py.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libstatistics_msgs__rosidl_generator_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libtracetools.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"backtrace" : 4,
|
||||
"fragment" : "/opt/ros/humble/lib/libclass_loader.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/usr/lib/aarch64-linux-gnu/libconsole_bridge.so.1.0",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libament_index_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libcomposition_interfaces__rosidl_typesupport_fastrtps_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_fastrtps_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_fastrtps_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librosidl_typesupport_fastrtps_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libcomposition_interfaces__rosidl_typesupport_introspection_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_introspection_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_introspection_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libcomposition_interfaces__rosidl_typesupport_fastrtps_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_fastrtps_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_fastrtps_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librosidl_typesupport_fastrtps_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librmw.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libfastcdr.so.1.0.24",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libcomposition_interfaces__rosidl_typesupport_introspection_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_introspection_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_introspection_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librosidl_typesupport_introspection_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librosidl_typesupport_introspection_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libcomposition_interfaces__rosidl_typesupport_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librosidl_typesupport_cpp.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libcomposition_interfaces__rosidl_generator_py.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librcl_interfaces__rosidl_generator_py.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libbuiltin_interfaces__rosidl_generator_py.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libcomposition_interfaces__rosidl_typesupport_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libcomposition_interfaces__rosidl_generator_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librcl_interfaces__rosidl_generator_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/libbuiltin_interfaces__rosidl_generator_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librosidl_typesupport_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librcpputils.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librosidl_runtime_c.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/opt/ros/humble/lib/librcutils.so",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "-ldl",
|
||||
"role" : "libraries"
|
||||
},
|
||||
{
|
||||
"fragment" : "/usr/lib/aarch64-linux-gnu/libpython3.10.so",
|
||||
"role" : "libraries"
|
||||
}
|
||||
],
|
||||
"language" : "CXX"
|
||||
},
|
||||
"name" : "armor_yolo_detector_node",
|
||||
"nameOnDisk" : "armor_yolo_detector_node",
|
||||
"paths" :
|
||||
{
|
||||
"build" : ".",
|
||||
"source" : "."
|
||||
},
|
||||
"sourceGroups" :
|
||||
[
|
||||
{
|
||||
"name" : "Source Files",
|
||||
"sourceIndexes" :
|
||||
[
|
||||
0
|
||||
]
|
||||
}
|
||||
],
|
||||
"sources" :
|
||||
[
|
||||
{
|
||||
"backtrace" : 2,
|
||||
"compileGroupIndex" : 0,
|
||||
"isGenerated" : true,
|
||||
"path" : "build/armor_yolo_detect/rclcpp_components/node_main_armor_yolo_detector_node.cpp",
|
||||
"sourceGroupIndex" : 0
|
||||
}
|
||||
],
|
||||
"type" : "EXECUTABLE"
|
||||
}
|
||||
@@ -0,0 +1,117 @@
|
||||
{
|
||||
"backtrace" : 13,
|
||||
"backtraceGraph" :
|
||||
{
|
||||
"commands" :
|
||||
[
|
||||
"add_custom_target",
|
||||
"include",
|
||||
"find_package",
|
||||
"add_dependencies"
|
||||
],
|
||||
"files" :
|
||||
[
|
||||
"/opt/ros/humble/share/ament_cmake_core/cmake/ament_cmake_uninstall_target-extras.cmake",
|
||||
"/opt/ros/humble/share/ament_cmake_core/cmake/ament_cmake_coreConfig.cmake",
|
||||
"/opt/ros/humble/share/ament_cmake/cmake/ament_cmake_export_dependencies-extras.cmake",
|
||||
"/opt/ros/humble/share/ament_cmake/cmake/ament_cmakeConfig.cmake",
|
||||
"/opt/ros/humble/share/ament_cmake_auto/cmake/ament_cmake_auto-extras.cmake",
|
||||
"/opt/ros/humble/share/ament_cmake_auto/cmake/ament_cmake_autoConfig.cmake",
|
||||
"CMakeLists.txt"
|
||||
],
|
||||
"nodes" :
|
||||
[
|
||||
{
|
||||
"file" : 6
|
||||
},
|
||||
{
|
||||
"command" : 2,
|
||||
"file" : 6,
|
||||
"line" : 18,
|
||||
"parent" : 0
|
||||
},
|
||||
{
|
||||
"file" : 5,
|
||||
"parent" : 1
|
||||
},
|
||||
{
|
||||
"command" : 1,
|
||||
"file" : 5,
|
||||
"line" : 41,
|
||||
"parent" : 2
|
||||
},
|
||||
{
|
||||
"file" : 4,
|
||||
"parent" : 3
|
||||
},
|
||||
{
|
||||
"command" : 2,
|
||||
"file" : 4,
|
||||
"line" : 17,
|
||||
"parent" : 4
|
||||
},
|
||||
{
|
||||
"file" : 3,
|
||||
"parent" : 5
|
||||
},
|
||||
{
|
||||
"command" : 1,
|
||||
"file" : 3,
|
||||
"line" : 41,
|
||||
"parent" : 6
|
||||
},
|
||||
{
|
||||
"file" : 2,
|
||||
"parent" : 7
|
||||
},
|
||||
{
|
||||
"command" : 2,
|
||||
"file" : 2,
|
||||
"line" : 15,
|
||||
"parent" : 8
|
||||
},
|
||||
{
|
||||
"file" : 1,
|
||||
"parent" : 9
|
||||
},
|
||||
{
|
||||
"command" : 1,
|
||||
"file" : 1,
|
||||
"line" : 41,
|
||||
"parent" : 10
|
||||
},
|
||||
{
|
||||
"file" : 0,
|
||||
"parent" : 11
|
||||
},
|
||||
{
|
||||
"command" : 0,
|
||||
"file" : 0,
|
||||
"line" : 35,
|
||||
"parent" : 12
|
||||
},
|
||||
{
|
||||
"command" : 3,
|
||||
"file" : 0,
|
||||
"line" : 42,
|
||||
"parent" : 12
|
||||
}
|
||||
]
|
||||
},
|
||||
"dependencies" :
|
||||
[
|
||||
{
|
||||
"backtrace" : 14,
|
||||
"id" : "armor_yolo_detect_uninstall::@6890427a1f51a3e7e1df"
|
||||
}
|
||||
],
|
||||
"id" : "uninstall::@6890427a1f51a3e7e1df",
|
||||
"name" : "uninstall",
|
||||
"paths" :
|
||||
{
|
||||
"build" : ".",
|
||||
"source" : "."
|
||||
},
|
||||
"sources" : [],
|
||||
"type" : "UTILITY"
|
||||
}
|
||||
@@ -0,0 +1,72 @@
|
||||
set(CMAKE_C_COMPILER "/usr/bin/cc")
|
||||
set(CMAKE_C_COMPILER_ARG1 "")
|
||||
set(CMAKE_C_COMPILER_ID "GNU")
|
||||
set(CMAKE_C_COMPILER_VERSION "11.4.0")
|
||||
set(CMAKE_C_COMPILER_VERSION_INTERNAL "")
|
||||
set(CMAKE_C_COMPILER_WRAPPER "")
|
||||
set(CMAKE_C_STANDARD_COMPUTED_DEFAULT "17")
|
||||
set(CMAKE_C_EXTENSIONS_COMPUTED_DEFAULT "ON")
|
||||
set(CMAKE_C_COMPILE_FEATURES "c_std_90;c_function_prototypes;c_std_99;c_restrict;c_variadic_macros;c_std_11;c_static_assert;c_std_17;c_std_23")
|
||||
set(CMAKE_C90_COMPILE_FEATURES "c_std_90;c_function_prototypes")
|
||||
set(CMAKE_C99_COMPILE_FEATURES "c_std_99;c_restrict;c_variadic_macros")
|
||||
set(CMAKE_C11_COMPILE_FEATURES "c_std_11;c_static_assert")
|
||||
set(CMAKE_C17_COMPILE_FEATURES "c_std_17")
|
||||
set(CMAKE_C23_COMPILE_FEATURES "c_std_23")
|
||||
|
||||
set(CMAKE_C_PLATFORM_ID "Linux")
|
||||
set(CMAKE_C_SIMULATE_ID "")
|
||||
set(CMAKE_C_COMPILER_FRONTEND_VARIANT "")
|
||||
set(CMAKE_C_SIMULATE_VERSION "")
|
||||
|
||||
|
||||
|
||||
|
||||
set(CMAKE_AR "/usr/bin/ar")
|
||||
set(CMAKE_C_COMPILER_AR "/usr/bin/gcc-ar-11")
|
||||
set(CMAKE_RANLIB "/usr/bin/ranlib")
|
||||
set(CMAKE_C_COMPILER_RANLIB "/usr/bin/gcc-ranlib-11")
|
||||
set(CMAKE_LINKER "/usr/bin/ld")
|
||||
set(CMAKE_MT "")
|
||||
set(CMAKE_COMPILER_IS_GNUCC 1)
|
||||
set(CMAKE_C_COMPILER_LOADED 1)
|
||||
set(CMAKE_C_COMPILER_WORKS TRUE)
|
||||
set(CMAKE_C_ABI_COMPILED TRUE)
|
||||
|
||||
set(CMAKE_C_COMPILER_ENV_VAR "CC")
|
||||
|
||||
set(CMAKE_C_COMPILER_ID_RUN 1)
|
||||
set(CMAKE_C_SOURCE_FILE_EXTENSIONS c;m)
|
||||
set(CMAKE_C_IGNORE_EXTENSIONS h;H;o;O;obj;OBJ;def;DEF;rc;RC)
|
||||
set(CMAKE_C_LINKER_PREFERENCE 10)
|
||||
|
||||
# Save compiler ABI information.
|
||||
set(CMAKE_C_SIZEOF_DATA_PTR "8")
|
||||
set(CMAKE_C_COMPILER_ABI "ELF")
|
||||
set(CMAKE_C_BYTE_ORDER "LITTLE_ENDIAN")
|
||||
set(CMAKE_C_LIBRARY_ARCHITECTURE "aarch64-linux-gnu")
|
||||
|
||||
if(CMAKE_C_SIZEOF_DATA_PTR)
|
||||
set(CMAKE_SIZEOF_VOID_P "${CMAKE_C_SIZEOF_DATA_PTR}")
|
||||
endif()
|
||||
|
||||
if(CMAKE_C_COMPILER_ABI)
|
||||
set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_C_COMPILER_ABI}")
|
||||
endif()
|
||||
|
||||
if(CMAKE_C_LIBRARY_ARCHITECTURE)
|
||||
set(CMAKE_LIBRARY_ARCHITECTURE "aarch64-linux-gnu")
|
||||
endif()
|
||||
|
||||
set(CMAKE_C_CL_SHOWINCLUDES_PREFIX "")
|
||||
if(CMAKE_C_CL_SHOWINCLUDES_PREFIX)
|
||||
set(CMAKE_CL_SHOWINCLUDES_PREFIX "${CMAKE_C_CL_SHOWINCLUDES_PREFIX}")
|
||||
endif()
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
set(CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES "/usr/lib/gcc/aarch64-linux-gnu/11/include;/usr/local/include;/usr/include/aarch64-linux-gnu;/usr/include")
|
||||
set(CMAKE_C_IMPLICIT_LINK_LIBRARIES "gcc;gcc_s;c;gcc;gcc_s")
|
||||
set(CMAKE_C_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/aarch64-linux-gnu/11;/usr/lib/aarch64-linux-gnu;/usr/lib;/lib/aarch64-linux-gnu;/lib")
|
||||
set(CMAKE_C_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "")
|
||||
@@ -0,0 +1,83 @@
|
||||
set(CMAKE_CXX_COMPILER "/usr/bin/c++")
|
||||
set(CMAKE_CXX_COMPILER_ARG1 "")
|
||||
set(CMAKE_CXX_COMPILER_ID "GNU")
|
||||
set(CMAKE_CXX_COMPILER_VERSION "11.4.0")
|
||||
set(CMAKE_CXX_COMPILER_VERSION_INTERNAL "")
|
||||
set(CMAKE_CXX_COMPILER_WRAPPER "")
|
||||
set(CMAKE_CXX_STANDARD_COMPUTED_DEFAULT "17")
|
||||
set(CMAKE_CXX_EXTENSIONS_COMPUTED_DEFAULT "ON")
|
||||
set(CMAKE_CXX_COMPILE_FEATURES "cxx_std_98;cxx_template_template_parameters;cxx_std_11;cxx_alias_templates;cxx_alignas;cxx_alignof;cxx_attributes;cxx_auto_type;cxx_constexpr;cxx_decltype;cxx_decltype_incomplete_return_types;cxx_default_function_template_args;cxx_defaulted_functions;cxx_defaulted_move_initializers;cxx_delegating_constructors;cxx_deleted_functions;cxx_enum_forward_declarations;cxx_explicit_conversions;cxx_extended_friend_declarations;cxx_extern_templates;cxx_final;cxx_func_identifier;cxx_generalized_initializers;cxx_inheriting_constructors;cxx_inline_namespaces;cxx_lambdas;cxx_local_type_template_args;cxx_long_long_type;cxx_noexcept;cxx_nonstatic_member_init;cxx_nullptr;cxx_override;cxx_range_for;cxx_raw_string_literals;cxx_reference_qualified_functions;cxx_right_angle_brackets;cxx_rvalue_references;cxx_sizeof_member;cxx_static_assert;cxx_strong_enums;cxx_thread_local;cxx_trailing_return_types;cxx_unicode_literals;cxx_uniform_initialization;cxx_unrestricted_unions;cxx_user_literals;cxx_variadic_macros;cxx_variadic_templates;cxx_std_14;cxx_aggregate_default_initializers;cxx_attribute_deprecated;cxx_binary_literals;cxx_contextual_conversions;cxx_decltype_auto;cxx_digit_separators;cxx_generic_lambdas;cxx_lambda_init_captures;cxx_relaxed_constexpr;cxx_return_type_deduction;cxx_variable_templates;cxx_std_17;cxx_std_20;cxx_std_23")
|
||||
set(CMAKE_CXX98_COMPILE_FEATURES "cxx_std_98;cxx_template_template_parameters")
|
||||
set(CMAKE_CXX11_COMPILE_FEATURES "cxx_std_11;cxx_alias_templates;cxx_alignas;cxx_alignof;cxx_attributes;cxx_auto_type;cxx_constexpr;cxx_decltype;cxx_decltype_incomplete_return_types;cxx_default_function_template_args;cxx_defaulted_functions;cxx_defaulted_move_initializers;cxx_delegating_constructors;cxx_deleted_functions;cxx_enum_forward_declarations;cxx_explicit_conversions;cxx_extended_friend_declarations;cxx_extern_templates;cxx_final;cxx_func_identifier;cxx_generalized_initializers;cxx_inheriting_constructors;cxx_inline_namespaces;cxx_lambdas;cxx_local_type_template_args;cxx_long_long_type;cxx_noexcept;cxx_nonstatic_member_init;cxx_nullptr;cxx_override;cxx_range_for;cxx_raw_string_literals;cxx_reference_qualified_functions;cxx_right_angle_brackets;cxx_rvalue_references;cxx_sizeof_member;cxx_static_assert;cxx_strong_enums;cxx_thread_local;cxx_trailing_return_types;cxx_unicode_literals;cxx_uniform_initialization;cxx_unrestricted_unions;cxx_user_literals;cxx_variadic_macros;cxx_variadic_templates")
|
||||
set(CMAKE_CXX14_COMPILE_FEATURES "cxx_std_14;cxx_aggregate_default_initializers;cxx_attribute_deprecated;cxx_binary_literals;cxx_contextual_conversions;cxx_decltype_auto;cxx_digit_separators;cxx_generic_lambdas;cxx_lambda_init_captures;cxx_relaxed_constexpr;cxx_return_type_deduction;cxx_variable_templates")
|
||||
set(CMAKE_CXX17_COMPILE_FEATURES "cxx_std_17")
|
||||
set(CMAKE_CXX20_COMPILE_FEATURES "cxx_std_20")
|
||||
set(CMAKE_CXX23_COMPILE_FEATURES "cxx_std_23")
|
||||
|
||||
set(CMAKE_CXX_PLATFORM_ID "Linux")
|
||||
set(CMAKE_CXX_SIMULATE_ID "")
|
||||
set(CMAKE_CXX_COMPILER_FRONTEND_VARIANT "")
|
||||
set(CMAKE_CXX_SIMULATE_VERSION "")
|
||||
|
||||
|
||||
|
||||
|
||||
set(CMAKE_AR "/usr/bin/ar")
|
||||
set(CMAKE_CXX_COMPILER_AR "/usr/bin/gcc-ar-11")
|
||||
set(CMAKE_RANLIB "/usr/bin/ranlib")
|
||||
set(CMAKE_CXX_COMPILER_RANLIB "/usr/bin/gcc-ranlib-11")
|
||||
set(CMAKE_LINKER "/usr/bin/ld")
|
||||
set(CMAKE_MT "")
|
||||
set(CMAKE_COMPILER_IS_GNUCXX 1)
|
||||
set(CMAKE_CXX_COMPILER_LOADED 1)
|
||||
set(CMAKE_CXX_COMPILER_WORKS TRUE)
|
||||
set(CMAKE_CXX_ABI_COMPILED TRUE)
|
||||
|
||||
set(CMAKE_CXX_COMPILER_ENV_VAR "CXX")
|
||||
|
||||
set(CMAKE_CXX_COMPILER_ID_RUN 1)
|
||||
set(CMAKE_CXX_SOURCE_FILE_EXTENSIONS C;M;c++;cc;cpp;cxx;m;mm;mpp;CPP;ixx;cppm)
|
||||
set(CMAKE_CXX_IGNORE_EXTENSIONS inl;h;hpp;HPP;H;o;O;obj;OBJ;def;DEF;rc;RC)
|
||||
|
||||
foreach (lang C OBJC OBJCXX)
|
||||
if (CMAKE_${lang}_COMPILER_ID_RUN)
|
||||
foreach(extension IN LISTS CMAKE_${lang}_SOURCE_FILE_EXTENSIONS)
|
||||
list(REMOVE_ITEM CMAKE_CXX_SOURCE_FILE_EXTENSIONS ${extension})
|
||||
endforeach()
|
||||
endif()
|
||||
endforeach()
|
||||
|
||||
set(CMAKE_CXX_LINKER_PREFERENCE 30)
|
||||
set(CMAKE_CXX_LINKER_PREFERENCE_PROPAGATES 1)
|
||||
|
||||
# Save compiler ABI information.
|
||||
set(CMAKE_CXX_SIZEOF_DATA_PTR "8")
|
||||
set(CMAKE_CXX_COMPILER_ABI "ELF")
|
||||
set(CMAKE_CXX_BYTE_ORDER "LITTLE_ENDIAN")
|
||||
set(CMAKE_CXX_LIBRARY_ARCHITECTURE "aarch64-linux-gnu")
|
||||
|
||||
if(CMAKE_CXX_SIZEOF_DATA_PTR)
|
||||
set(CMAKE_SIZEOF_VOID_P "${CMAKE_CXX_SIZEOF_DATA_PTR}")
|
||||
endif()
|
||||
|
||||
if(CMAKE_CXX_COMPILER_ABI)
|
||||
set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_CXX_COMPILER_ABI}")
|
||||
endif()
|
||||
|
||||
if(CMAKE_CXX_LIBRARY_ARCHITECTURE)
|
||||
set(CMAKE_LIBRARY_ARCHITECTURE "aarch64-linux-gnu")
|
||||
endif()
|
||||
|
||||
set(CMAKE_CXX_CL_SHOWINCLUDES_PREFIX "")
|
||||
if(CMAKE_CXX_CL_SHOWINCLUDES_PREFIX)
|
||||
set(CMAKE_CL_SHOWINCLUDES_PREFIX "${CMAKE_CXX_CL_SHOWINCLUDES_PREFIX}")
|
||||
endif()
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
set(CMAKE_CXX_IMPLICIT_INCLUDE_DIRECTORIES "/usr/include/c++/11;/usr/include/aarch64-linux-gnu/c++/11;/usr/include/c++/11/backward;/usr/lib/gcc/aarch64-linux-gnu/11/include;/usr/local/include;/usr/include/aarch64-linux-gnu;/usr/include")
|
||||
set(CMAKE_CXX_IMPLICIT_LINK_LIBRARIES "stdc++;m;gcc_s;gcc;c;gcc_s;gcc")
|
||||
set(CMAKE_CXX_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/aarch64-linux-gnu/11;/usr/lib/aarch64-linux-gnu;/usr/lib;/lib/aarch64-linux-gnu;/lib")
|
||||
set(CMAKE_CXX_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "")
|
||||
@@ -0,0 +1,15 @@
|
||||
set(CMAKE_HOST_SYSTEM "Linux-5.15.148-tegra")
|
||||
set(CMAKE_HOST_SYSTEM_NAME "Linux")
|
||||
set(CMAKE_HOST_SYSTEM_VERSION "5.15.148-tegra")
|
||||
set(CMAKE_HOST_SYSTEM_PROCESSOR "aarch64")
|
||||
|
||||
|
||||
|
||||
set(CMAKE_SYSTEM "Linux-5.15.148-tegra")
|
||||
set(CMAKE_SYSTEM_NAME "Linux")
|
||||
set(CMAKE_SYSTEM_VERSION "5.15.148-tegra")
|
||||
set(CMAKE_SYSTEM_PROCESSOR "aarch64")
|
||||
|
||||
set(CMAKE_CROSSCOMPILING "FALSE")
|
||||
|
||||
set(CMAKE_SYSTEM_LOADED 1)
|
||||
@@ -0,0 +1,803 @@
|
||||
#ifdef __cplusplus
|
||||
# error "A C++ compiler has been selected for C."
|
||||
#endif
|
||||
|
||||
#if defined(__18CXX)
|
||||
# define ID_VOID_MAIN
|
||||
#endif
|
||||
#if defined(__CLASSIC_C__)
|
||||
/* cv-qualifiers did not exist in K&R C */
|
||||
# define const
|
||||
# define volatile
|
||||
#endif
|
||||
|
||||
#if !defined(__has_include)
|
||||
/* If the compiler does not have __has_include, pretend the answer is
|
||||
always no. */
|
||||
# define __has_include(x) 0
|
||||
#endif
|
||||
|
||||
|
||||
/* Version number components: V=Version, R=Revision, P=Patch
|
||||
Version date components: YYYY=Year, MM=Month, DD=Day */
|
||||
|
||||
#if defined(__INTEL_COMPILER) || defined(__ICC)
|
||||
# define COMPILER_ID "Intel"
|
||||
# if defined(_MSC_VER)
|
||||
# define SIMULATE_ID "MSVC"
|
||||
# endif
|
||||
# if defined(__GNUC__)
|
||||
# define SIMULATE_ID "GNU"
|
||||
# endif
|
||||
/* __INTEL_COMPILER = VRP prior to 2021, and then VVVV for 2021 and later,
|
||||
except that a few beta releases use the old format with V=2021. */
|
||||
# if __INTEL_COMPILER < 2021 || __INTEL_COMPILER == 202110 || __INTEL_COMPILER == 202111
|
||||
# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100)
|
||||
# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10)
|
||||
# if defined(__INTEL_COMPILER_UPDATE)
|
||||
# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER_UPDATE)
|
||||
# else
|
||||
# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10)
|
||||
# endif
|
||||
# else
|
||||
# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER)
|
||||
# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER_UPDATE)
|
||||
/* The third version component from --version is an update index,
|
||||
but no macro is provided for it. */
|
||||
# define COMPILER_VERSION_PATCH DEC(0)
|
||||
# endif
|
||||
# if defined(__INTEL_COMPILER_BUILD_DATE)
|
||||
/* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */
|
||||
# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE)
|
||||
# endif
|
||||
# if defined(_MSC_VER)
|
||||
/* _MSC_VER = VVRR */
|
||||
# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
|
||||
# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
|
||||
# endif
|
||||
# if defined(__GNUC__)
|
||||
# define SIMULATE_VERSION_MAJOR DEC(__GNUC__)
|
||||
# elif defined(__GNUG__)
|
||||
# define SIMULATE_VERSION_MAJOR DEC(__GNUG__)
|
||||
# endif
|
||||
# if defined(__GNUC_MINOR__)
|
||||
# define SIMULATE_VERSION_MINOR DEC(__GNUC_MINOR__)
|
||||
# endif
|
||||
# if defined(__GNUC_PATCHLEVEL__)
|
||||
# define SIMULATE_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__)
|
||||
# endif
|
||||
|
||||
#elif (defined(__clang__) && defined(__INTEL_CLANG_COMPILER)) || defined(__INTEL_LLVM_COMPILER)
|
||||
# define COMPILER_ID "IntelLLVM"
|
||||
#if defined(_MSC_VER)
|
||||
# define SIMULATE_ID "MSVC"
|
||||
#endif
|
||||
#if defined(__GNUC__)
|
||||
# define SIMULATE_ID "GNU"
|
||||
#endif
|
||||
/* __INTEL_LLVM_COMPILER = VVVVRP prior to 2021.2.0, VVVVRRPP for 2021.2.0 and
|
||||
* later. Look for 6 digit vs. 8 digit version number to decide encoding.
|
||||
* VVVV is no smaller than the current year when a version is released.
|
||||
*/
|
||||
#if __INTEL_LLVM_COMPILER < 1000000L
|
||||
# define COMPILER_VERSION_MAJOR DEC(__INTEL_LLVM_COMPILER/100)
|
||||
# define COMPILER_VERSION_MINOR DEC(__INTEL_LLVM_COMPILER/10 % 10)
|
||||
# define COMPILER_VERSION_PATCH DEC(__INTEL_LLVM_COMPILER % 10)
|
||||
#else
|
||||
# define COMPILER_VERSION_MAJOR DEC(__INTEL_LLVM_COMPILER/10000)
|
||||
# define COMPILER_VERSION_MINOR DEC(__INTEL_LLVM_COMPILER/100 % 100)
|
||||
# define COMPILER_VERSION_PATCH DEC(__INTEL_LLVM_COMPILER % 100)
|
||||
#endif
|
||||
#if defined(_MSC_VER)
|
||||
/* _MSC_VER = VVRR */
|
||||
# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
|
||||
# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
|
||||
#endif
|
||||
#if defined(__GNUC__)
|
||||
# define SIMULATE_VERSION_MAJOR DEC(__GNUC__)
|
||||
#elif defined(__GNUG__)
|
||||
# define SIMULATE_VERSION_MAJOR DEC(__GNUG__)
|
||||
#endif
|
||||
#if defined(__GNUC_MINOR__)
|
||||
# define SIMULATE_VERSION_MINOR DEC(__GNUC_MINOR__)
|
||||
#endif
|
||||
#if defined(__GNUC_PATCHLEVEL__)
|
||||
# define SIMULATE_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__)
|
||||
#endif
|
||||
|
||||
#elif defined(__PATHCC__)
|
||||
# define COMPILER_ID "PathScale"
|
||||
# define COMPILER_VERSION_MAJOR DEC(__PATHCC__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__)
|
||||
# if defined(__PATHCC_PATCHLEVEL__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__)
|
||||
# endif
|
||||
|
||||
#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__)
|
||||
# define COMPILER_ID "Embarcadero"
|
||||
# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF)
|
||||
# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF)
|
||||
# define COMPILER_VERSION_PATCH DEC(__CODEGEARC_VERSION__ & 0xFFFF)
|
||||
|
||||
#elif defined(__BORLANDC__)
|
||||
# define COMPILER_ID "Borland"
|
||||
/* __BORLANDC__ = 0xVRR */
|
||||
# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8)
|
||||
# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF)
|
||||
|
||||
#elif defined(__WATCOMC__) && __WATCOMC__ < 1200
|
||||
# define COMPILER_ID "Watcom"
|
||||
/* __WATCOMC__ = VVRR */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100)
|
||||
# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10)
|
||||
# if (__WATCOMC__ % 10) > 0
|
||||
# define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10)
|
||||
# endif
|
||||
|
||||
#elif defined(__WATCOMC__)
|
||||
# define COMPILER_ID "OpenWatcom"
|
||||
/* __WATCOMC__ = VVRP + 1100 */
|
||||
# define COMPILER_VERSION_MAJOR DEC((__WATCOMC__ - 1100) / 100)
|
||||
# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10)
|
||||
# if (__WATCOMC__ % 10) > 0
|
||||
# define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10)
|
||||
# endif
|
||||
|
||||
#elif defined(__SUNPRO_C)
|
||||
# define COMPILER_ID "SunPro"
|
||||
# if __SUNPRO_C >= 0x5100
|
||||
/* __SUNPRO_C = 0xVRRP */
|
||||
# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>12)
|
||||
# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xFF)
|
||||
# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF)
|
||||
# else
|
||||
/* __SUNPRO_CC = 0xVRP */
|
||||
# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>8)
|
||||
# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xF)
|
||||
# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF)
|
||||
# endif
|
||||
|
||||
#elif defined(__HP_cc)
|
||||
# define COMPILER_ID "HP"
|
||||
/* __HP_cc = VVRRPP */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__HP_cc/10000)
|
||||
# define COMPILER_VERSION_MINOR DEC(__HP_cc/100 % 100)
|
||||
# define COMPILER_VERSION_PATCH DEC(__HP_cc % 100)
|
||||
|
||||
#elif defined(__DECC)
|
||||
# define COMPILER_ID "Compaq"
|
||||
/* __DECC_VER = VVRRTPPPP */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__DECC_VER/10000000)
|
||||
# define COMPILER_VERSION_MINOR DEC(__DECC_VER/100000 % 100)
|
||||
# define COMPILER_VERSION_PATCH DEC(__DECC_VER % 10000)
|
||||
|
||||
#elif defined(__IBMC__) && defined(__COMPILER_VER__)
|
||||
# define COMPILER_ID "zOS"
|
||||
/* __IBMC__ = VRP */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100)
|
||||
# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10)
|
||||
# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10)
|
||||
|
||||
#elif defined(__ibmxl__) && defined(__clang__)
|
||||
# define COMPILER_ID "XLClang"
|
||||
# define COMPILER_VERSION_MAJOR DEC(__ibmxl_version__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__ibmxl_release__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__ibmxl_modification__)
|
||||
# define COMPILER_VERSION_TWEAK DEC(__ibmxl_ptf_fix_level__)
|
||||
|
||||
|
||||
#elif defined(__IBMC__) && !defined(__COMPILER_VER__) && __IBMC__ >= 800
|
||||
# define COMPILER_ID "XL"
|
||||
/* __IBMC__ = VRP */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100)
|
||||
# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10)
|
||||
# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10)
|
||||
|
||||
#elif defined(__IBMC__) && !defined(__COMPILER_VER__) && __IBMC__ < 800
|
||||
# define COMPILER_ID "VisualAge"
|
||||
/* __IBMC__ = VRP */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100)
|
||||
# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10)
|
||||
# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10)
|
||||
|
||||
#elif defined(__NVCOMPILER)
|
||||
# define COMPILER_ID "NVHPC"
|
||||
# define COMPILER_VERSION_MAJOR DEC(__NVCOMPILER_MAJOR__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__NVCOMPILER_MINOR__)
|
||||
# if defined(__NVCOMPILER_PATCHLEVEL__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__NVCOMPILER_PATCHLEVEL__)
|
||||
# endif
|
||||
|
||||
#elif defined(__PGI)
|
||||
# define COMPILER_ID "PGI"
|
||||
# define COMPILER_VERSION_MAJOR DEC(__PGIC__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__)
|
||||
# if defined(__PGIC_PATCHLEVEL__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__)
|
||||
# endif
|
||||
|
||||
#elif defined(_CRAYC)
|
||||
# define COMPILER_ID "Cray"
|
||||
# define COMPILER_VERSION_MAJOR DEC(_RELEASE_MAJOR)
|
||||
# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR)
|
||||
|
||||
#elif defined(__TI_COMPILER_VERSION__)
|
||||
# define COMPILER_ID "TI"
|
||||
/* __TI_COMPILER_VERSION__ = VVVRRRPPP */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000)
|
||||
# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000)
|
||||
# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000)
|
||||
|
||||
#elif defined(__CLANG_FUJITSU)
|
||||
# define COMPILER_ID "FujitsuClang"
|
||||
# define COMPILER_VERSION_MAJOR DEC(__FCC_major__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__FCC_minor__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__FCC_patchlevel__)
|
||||
# define COMPILER_VERSION_INTERNAL_STR __clang_version__
|
||||
|
||||
|
||||
#elif defined(__FUJITSU)
|
||||
# define COMPILER_ID "Fujitsu"
|
||||
# if defined(__FCC_version__)
|
||||
# define COMPILER_VERSION __FCC_version__
|
||||
# elif defined(__FCC_major__)
|
||||
# define COMPILER_VERSION_MAJOR DEC(__FCC_major__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__FCC_minor__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__FCC_patchlevel__)
|
||||
# endif
|
||||
# if defined(__fcc_version)
|
||||
# define COMPILER_VERSION_INTERNAL DEC(__fcc_version)
|
||||
# elif defined(__FCC_VERSION)
|
||||
# define COMPILER_VERSION_INTERNAL DEC(__FCC_VERSION)
|
||||
# endif
|
||||
|
||||
|
||||
#elif defined(__ghs__)
|
||||
# define COMPILER_ID "GHS"
|
||||
/* __GHS_VERSION_NUMBER = VVVVRP */
|
||||
# ifdef __GHS_VERSION_NUMBER
|
||||
# define COMPILER_VERSION_MAJOR DEC(__GHS_VERSION_NUMBER / 100)
|
||||
# define COMPILER_VERSION_MINOR DEC(__GHS_VERSION_NUMBER / 10 % 10)
|
||||
# define COMPILER_VERSION_PATCH DEC(__GHS_VERSION_NUMBER % 10)
|
||||
# endif
|
||||
|
||||
#elif defined(__TINYC__)
|
||||
# define COMPILER_ID "TinyCC"
|
||||
|
||||
#elif defined(__BCC__)
|
||||
# define COMPILER_ID "Bruce"
|
||||
|
||||
#elif defined(__SCO_VERSION__)
|
||||
# define COMPILER_ID "SCO"
|
||||
|
||||
#elif defined(__ARMCC_VERSION) && !defined(__clang__)
|
||||
# define COMPILER_ID "ARMCC"
|
||||
#if __ARMCC_VERSION >= 1000000
|
||||
/* __ARMCC_VERSION = VRRPPPP */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/1000000)
|
||||
# define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 100)
|
||||
# define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000)
|
||||
#else
|
||||
/* __ARMCC_VERSION = VRPPPP */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/100000)
|
||||
# define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 10)
|
||||
# define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000)
|
||||
#endif
|
||||
|
||||
|
||||
#elif defined(__clang__) && defined(__apple_build_version__)
|
||||
# define COMPILER_ID "AppleClang"
|
||||
# if defined(_MSC_VER)
|
||||
# define SIMULATE_ID "MSVC"
|
||||
# endif
|
||||
# define COMPILER_VERSION_MAJOR DEC(__clang_major__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__clang_minor__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__)
|
||||
# if defined(_MSC_VER)
|
||||
/* _MSC_VER = VVRR */
|
||||
# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
|
||||
# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
|
||||
# endif
|
||||
# define COMPILER_VERSION_TWEAK DEC(__apple_build_version__)
|
||||
|
||||
#elif defined(__clang__) && defined(__ARMCOMPILER_VERSION)
|
||||
# define COMPILER_ID "ARMClang"
|
||||
# define COMPILER_VERSION_MAJOR DEC(__ARMCOMPILER_VERSION/1000000)
|
||||
# define COMPILER_VERSION_MINOR DEC(__ARMCOMPILER_VERSION/10000 % 100)
|
||||
# define COMPILER_VERSION_PATCH DEC(__ARMCOMPILER_VERSION % 10000)
|
||||
# define COMPILER_VERSION_INTERNAL DEC(__ARMCOMPILER_VERSION)
|
||||
|
||||
#elif defined(__clang__)
|
||||
# define COMPILER_ID "Clang"
|
||||
# if defined(_MSC_VER)
|
||||
# define SIMULATE_ID "MSVC"
|
||||
# endif
|
||||
# define COMPILER_VERSION_MAJOR DEC(__clang_major__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__clang_minor__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__)
|
||||
# if defined(_MSC_VER)
|
||||
/* _MSC_VER = VVRR */
|
||||
# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
|
||||
# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
|
||||
# endif
|
||||
|
||||
#elif defined(__GNUC__)
|
||||
# define COMPILER_ID "GNU"
|
||||
# define COMPILER_VERSION_MAJOR DEC(__GNUC__)
|
||||
# if defined(__GNUC_MINOR__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__)
|
||||
# endif
|
||||
# if defined(__GNUC_PATCHLEVEL__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__)
|
||||
# endif
|
||||
|
||||
#elif defined(_MSC_VER)
|
||||
# define COMPILER_ID "MSVC"
|
||||
/* _MSC_VER = VVRR */
|
||||
# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100)
|
||||
# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100)
|
||||
# if defined(_MSC_FULL_VER)
|
||||
# if _MSC_VER >= 1400
|
||||
/* _MSC_FULL_VER = VVRRPPPPP */
|
||||
# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000)
|
||||
# else
|
||||
/* _MSC_FULL_VER = VVRRPPPP */
|
||||
# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000)
|
||||
# endif
|
||||
# endif
|
||||
# if defined(_MSC_BUILD)
|
||||
# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD)
|
||||
# endif
|
||||
|
||||
#elif defined(__VISUALDSPVERSION__) || defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__)
|
||||
# define COMPILER_ID "ADSP"
|
||||
#if defined(__VISUALDSPVERSION__)
|
||||
/* __VISUALDSPVERSION__ = 0xVVRRPP00 */
|
||||
# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24)
|
||||
# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF)
|
||||
# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF)
|
||||
#endif
|
||||
|
||||
#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC)
|
||||
# define COMPILER_ID "IAR"
|
||||
# if defined(__VER__) && defined(__ICCARM__)
|
||||
# define COMPILER_VERSION_MAJOR DEC((__VER__) / 1000000)
|
||||
# define COMPILER_VERSION_MINOR DEC(((__VER__) / 1000) % 1000)
|
||||
# define COMPILER_VERSION_PATCH DEC((__VER__) % 1000)
|
||||
# define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__)
|
||||
# elif defined(__VER__) && (defined(__ICCAVR__) || defined(__ICCRX__) || defined(__ICCRH850__) || defined(__ICCRL78__) || defined(__ICC430__) || defined(__ICCRISCV__) || defined(__ICCV850__) || defined(__ICC8051__) || defined(__ICCSTM8__))
|
||||
# define COMPILER_VERSION_MAJOR DEC((__VER__) / 100)
|
||||
# define COMPILER_VERSION_MINOR DEC((__VER__) - (((__VER__) / 100)*100))
|
||||
# define COMPILER_VERSION_PATCH DEC(__SUBVERSION__)
|
||||
# define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__)
|
||||
# endif
|
||||
|
||||
#elif defined(__SDCC_VERSION_MAJOR) || defined(SDCC)
|
||||
# define COMPILER_ID "SDCC"
|
||||
# if defined(__SDCC_VERSION_MAJOR)
|
||||
# define COMPILER_VERSION_MAJOR DEC(__SDCC_VERSION_MAJOR)
|
||||
# define COMPILER_VERSION_MINOR DEC(__SDCC_VERSION_MINOR)
|
||||
# define COMPILER_VERSION_PATCH DEC(__SDCC_VERSION_PATCH)
|
||||
# else
|
||||
/* SDCC = VRP */
|
||||
# define COMPILER_VERSION_MAJOR DEC(SDCC/100)
|
||||
# define COMPILER_VERSION_MINOR DEC(SDCC/10 % 10)
|
||||
# define COMPILER_VERSION_PATCH DEC(SDCC % 10)
|
||||
# endif
|
||||
|
||||
|
||||
/* These compilers are either not known or too old to define an
|
||||
identification macro. Try to identify the platform and guess that
|
||||
it is the native compiler. */
|
||||
#elif defined(__hpux) || defined(__hpua)
|
||||
# define COMPILER_ID "HP"
|
||||
|
||||
#else /* unknown compiler */
|
||||
# define COMPILER_ID ""
|
||||
#endif
|
||||
|
||||
/* Construct the string literal in pieces to prevent the source from
|
||||
getting matched. Store it in a pointer rather than an array
|
||||
because some compilers will just produce instructions to fill the
|
||||
array rather than assigning a pointer to a static array. */
|
||||
char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]";
|
||||
#ifdef SIMULATE_ID
|
||||
char const* info_simulate = "INFO" ":" "simulate[" SIMULATE_ID "]";
|
||||
#endif
|
||||
|
||||
#ifdef __QNXNTO__
|
||||
char const* qnxnto = "INFO" ":" "qnxnto[]";
|
||||
#endif
|
||||
|
||||
#if defined(__CRAYXT_COMPUTE_LINUX_TARGET)
|
||||
char const *info_cray = "INFO" ":" "compiler_wrapper[CrayPrgEnv]";
|
||||
#endif
|
||||
|
||||
#define STRINGIFY_HELPER(X) #X
|
||||
#define STRINGIFY(X) STRINGIFY_HELPER(X)
|
||||
|
||||
/* Identify known platforms by name. */
|
||||
#if defined(__linux) || defined(__linux__) || defined(linux)
|
||||
# define PLATFORM_ID "Linux"
|
||||
|
||||
#elif defined(__MSYS__)
|
||||
# define PLATFORM_ID "MSYS"
|
||||
|
||||
#elif defined(__CYGWIN__)
|
||||
# define PLATFORM_ID "Cygwin"
|
||||
|
||||
#elif defined(__MINGW32__)
|
||||
# define PLATFORM_ID "MinGW"
|
||||
|
||||
#elif defined(__APPLE__)
|
||||
# define PLATFORM_ID "Darwin"
|
||||
|
||||
#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32)
|
||||
# define PLATFORM_ID "Windows"
|
||||
|
||||
#elif defined(__FreeBSD__) || defined(__FreeBSD)
|
||||
# define PLATFORM_ID "FreeBSD"
|
||||
|
||||
#elif defined(__NetBSD__) || defined(__NetBSD)
|
||||
# define PLATFORM_ID "NetBSD"
|
||||
|
||||
#elif defined(__OpenBSD__) || defined(__OPENBSD)
|
||||
# define PLATFORM_ID "OpenBSD"
|
||||
|
||||
#elif defined(__sun) || defined(sun)
|
||||
# define PLATFORM_ID "SunOS"
|
||||
|
||||
#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__)
|
||||
# define PLATFORM_ID "AIX"
|
||||
|
||||
#elif defined(__hpux) || defined(__hpux__)
|
||||
# define PLATFORM_ID "HP-UX"
|
||||
|
||||
#elif defined(__HAIKU__)
|
||||
# define PLATFORM_ID "Haiku"
|
||||
|
||||
#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS)
|
||||
# define PLATFORM_ID "BeOS"
|
||||
|
||||
#elif defined(__QNX__) || defined(__QNXNTO__)
|
||||
# define PLATFORM_ID "QNX"
|
||||
|
||||
#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__)
|
||||
# define PLATFORM_ID "Tru64"
|
||||
|
||||
#elif defined(__riscos) || defined(__riscos__)
|
||||
# define PLATFORM_ID "RISCos"
|
||||
|
||||
#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__)
|
||||
# define PLATFORM_ID "SINIX"
|
||||
|
||||
#elif defined(__UNIX_SV__)
|
||||
# define PLATFORM_ID "UNIX_SV"
|
||||
|
||||
#elif defined(__bsdos__)
|
||||
# define PLATFORM_ID "BSDOS"
|
||||
|
||||
#elif defined(_MPRAS) || defined(MPRAS)
|
||||
# define PLATFORM_ID "MP-RAS"
|
||||
|
||||
#elif defined(__osf) || defined(__osf__)
|
||||
# define PLATFORM_ID "OSF1"
|
||||
|
||||
#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv)
|
||||
# define PLATFORM_ID "SCO_SV"
|
||||
|
||||
#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX)
|
||||
# define PLATFORM_ID "ULTRIX"
|
||||
|
||||
#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX)
|
||||
# define PLATFORM_ID "Xenix"
|
||||
|
||||
#elif defined(__WATCOMC__)
|
||||
# if defined(__LINUX__)
|
||||
# define PLATFORM_ID "Linux"
|
||||
|
||||
# elif defined(__DOS__)
|
||||
# define PLATFORM_ID "DOS"
|
||||
|
||||
# elif defined(__OS2__)
|
||||
# define PLATFORM_ID "OS2"
|
||||
|
||||
# elif defined(__WINDOWS__)
|
||||
# define PLATFORM_ID "Windows3x"
|
||||
|
||||
# elif defined(__VXWORKS__)
|
||||
# define PLATFORM_ID "VxWorks"
|
||||
|
||||
# else /* unknown platform */
|
||||
# define PLATFORM_ID
|
||||
# endif
|
||||
|
||||
#elif defined(__INTEGRITY)
|
||||
# if defined(INT_178B)
|
||||
# define PLATFORM_ID "Integrity178"
|
||||
|
||||
# else /* regular Integrity */
|
||||
# define PLATFORM_ID "Integrity"
|
||||
# endif
|
||||
|
||||
#else /* unknown platform */
|
||||
# define PLATFORM_ID
|
||||
|
||||
#endif
|
||||
|
||||
/* For windows compilers MSVC and Intel we can determine
|
||||
the architecture of the compiler being used. This is because
|
||||
the compilers do not have flags that can change the architecture,
|
||||
but rather depend on which compiler is being used
|
||||
*/
|
||||
#if defined(_WIN32) && defined(_MSC_VER)
|
||||
# if defined(_M_IA64)
|
||||
# define ARCHITECTURE_ID "IA64"
|
||||
|
||||
# elif defined(_M_ARM64EC)
|
||||
# define ARCHITECTURE_ID "ARM64EC"
|
||||
|
||||
# elif defined(_M_X64) || defined(_M_AMD64)
|
||||
# define ARCHITECTURE_ID "x64"
|
||||
|
||||
# elif defined(_M_IX86)
|
||||
# define ARCHITECTURE_ID "X86"
|
||||
|
||||
# elif defined(_M_ARM64)
|
||||
# define ARCHITECTURE_ID "ARM64"
|
||||
|
||||
# elif defined(_M_ARM)
|
||||
# if _M_ARM == 4
|
||||
# define ARCHITECTURE_ID "ARMV4I"
|
||||
# elif _M_ARM == 5
|
||||
# define ARCHITECTURE_ID "ARMV5I"
|
||||
# else
|
||||
# define ARCHITECTURE_ID "ARMV" STRINGIFY(_M_ARM)
|
||||
# endif
|
||||
|
||||
# elif defined(_M_MIPS)
|
||||
# define ARCHITECTURE_ID "MIPS"
|
||||
|
||||
# elif defined(_M_SH)
|
||||
# define ARCHITECTURE_ID "SHx"
|
||||
|
||||
# else /* unknown architecture */
|
||||
# define ARCHITECTURE_ID ""
|
||||
# endif
|
||||
|
||||
#elif defined(__WATCOMC__)
|
||||
# if defined(_M_I86)
|
||||
# define ARCHITECTURE_ID "I86"
|
||||
|
||||
# elif defined(_M_IX86)
|
||||
# define ARCHITECTURE_ID "X86"
|
||||
|
||||
# else /* unknown architecture */
|
||||
# define ARCHITECTURE_ID ""
|
||||
# endif
|
||||
|
||||
#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC)
|
||||
# if defined(__ICCARM__)
|
||||
# define ARCHITECTURE_ID "ARM"
|
||||
|
||||
# elif defined(__ICCRX__)
|
||||
# define ARCHITECTURE_ID "RX"
|
||||
|
||||
# elif defined(__ICCRH850__)
|
||||
# define ARCHITECTURE_ID "RH850"
|
||||
|
||||
# elif defined(__ICCRL78__)
|
||||
# define ARCHITECTURE_ID "RL78"
|
||||
|
||||
# elif defined(__ICCRISCV__)
|
||||
# define ARCHITECTURE_ID "RISCV"
|
||||
|
||||
# elif defined(__ICCAVR__)
|
||||
# define ARCHITECTURE_ID "AVR"
|
||||
|
||||
# elif defined(__ICC430__)
|
||||
# define ARCHITECTURE_ID "MSP430"
|
||||
|
||||
# elif defined(__ICCV850__)
|
||||
# define ARCHITECTURE_ID "V850"
|
||||
|
||||
# elif defined(__ICC8051__)
|
||||
# define ARCHITECTURE_ID "8051"
|
||||
|
||||
# elif defined(__ICCSTM8__)
|
||||
# define ARCHITECTURE_ID "STM8"
|
||||
|
||||
# else /* unknown architecture */
|
||||
# define ARCHITECTURE_ID ""
|
||||
# endif
|
||||
|
||||
#elif defined(__ghs__)
|
||||
# if defined(__PPC64__)
|
||||
# define ARCHITECTURE_ID "PPC64"
|
||||
|
||||
# elif defined(__ppc__)
|
||||
# define ARCHITECTURE_ID "PPC"
|
||||
|
||||
# elif defined(__ARM__)
|
||||
# define ARCHITECTURE_ID "ARM"
|
||||
|
||||
# elif defined(__x86_64__)
|
||||
# define ARCHITECTURE_ID "x64"
|
||||
|
||||
# elif defined(__i386__)
|
||||
# define ARCHITECTURE_ID "X86"
|
||||
|
||||
# else /* unknown architecture */
|
||||
# define ARCHITECTURE_ID ""
|
||||
# endif
|
||||
|
||||
#elif defined(__TI_COMPILER_VERSION__)
|
||||
# if defined(__TI_ARM__)
|
||||
# define ARCHITECTURE_ID "ARM"
|
||||
|
||||
# elif defined(__MSP430__)
|
||||
# define ARCHITECTURE_ID "MSP430"
|
||||
|
||||
# elif defined(__TMS320C28XX__)
|
||||
# define ARCHITECTURE_ID "TMS320C28x"
|
||||
|
||||
# elif defined(__TMS320C6X__) || defined(_TMS320C6X)
|
||||
# define ARCHITECTURE_ID "TMS320C6x"
|
||||
|
||||
# else /* unknown architecture */
|
||||
# define ARCHITECTURE_ID ""
|
||||
# endif
|
||||
|
||||
#else
|
||||
# define ARCHITECTURE_ID
|
||||
#endif
|
||||
|
||||
/* Convert integer to decimal digit literals. */
|
||||
#define DEC(n) \
|
||||
('0' + (((n) / 10000000)%10)), \
|
||||
('0' + (((n) / 1000000)%10)), \
|
||||
('0' + (((n) / 100000)%10)), \
|
||||
('0' + (((n) / 10000)%10)), \
|
||||
('0' + (((n) / 1000)%10)), \
|
||||
('0' + (((n) / 100)%10)), \
|
||||
('0' + (((n) / 10)%10)), \
|
||||
('0' + ((n) % 10))
|
||||
|
||||
/* Convert integer to hex digit literals. */
|
||||
#define HEX(n) \
|
||||
('0' + ((n)>>28 & 0xF)), \
|
||||
('0' + ((n)>>24 & 0xF)), \
|
||||
('0' + ((n)>>20 & 0xF)), \
|
||||
('0' + ((n)>>16 & 0xF)), \
|
||||
('0' + ((n)>>12 & 0xF)), \
|
||||
('0' + ((n)>>8 & 0xF)), \
|
||||
('0' + ((n)>>4 & 0xF)), \
|
||||
('0' + ((n) & 0xF))
|
||||
|
||||
/* Construct a string literal encoding the version number. */
|
||||
#ifdef COMPILER_VERSION
|
||||
char const* info_version = "INFO" ":" "compiler_version[" COMPILER_VERSION "]";
|
||||
|
||||
/* Construct a string literal encoding the version number components. */
|
||||
#elif defined(COMPILER_VERSION_MAJOR)
|
||||
char const info_version[] = {
|
||||
'I', 'N', 'F', 'O', ':',
|
||||
'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[',
|
||||
COMPILER_VERSION_MAJOR,
|
||||
# ifdef COMPILER_VERSION_MINOR
|
||||
'.', COMPILER_VERSION_MINOR,
|
||||
# ifdef COMPILER_VERSION_PATCH
|
||||
'.', COMPILER_VERSION_PATCH,
|
||||
# ifdef COMPILER_VERSION_TWEAK
|
||||
'.', COMPILER_VERSION_TWEAK,
|
||||
# endif
|
||||
# endif
|
||||
# endif
|
||||
']','\0'};
|
||||
#endif
|
||||
|
||||
/* Construct a string literal encoding the internal version number. */
|
||||
#ifdef COMPILER_VERSION_INTERNAL
|
||||
char const info_version_internal[] = {
|
||||
'I', 'N', 'F', 'O', ':',
|
||||
'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','_',
|
||||
'i','n','t','e','r','n','a','l','[',
|
||||
COMPILER_VERSION_INTERNAL,']','\0'};
|
||||
#elif defined(COMPILER_VERSION_INTERNAL_STR)
|
||||
char const* info_version_internal = "INFO" ":" "compiler_version_internal[" COMPILER_VERSION_INTERNAL_STR "]";
|
||||
#endif
|
||||
|
||||
/* Construct a string literal encoding the version number components. */
|
||||
#ifdef SIMULATE_VERSION_MAJOR
|
||||
char const info_simulate_version[] = {
|
||||
'I', 'N', 'F', 'O', ':',
|
||||
's','i','m','u','l','a','t','e','_','v','e','r','s','i','o','n','[',
|
||||
SIMULATE_VERSION_MAJOR,
|
||||
# ifdef SIMULATE_VERSION_MINOR
|
||||
'.', SIMULATE_VERSION_MINOR,
|
||||
# ifdef SIMULATE_VERSION_PATCH
|
||||
'.', SIMULATE_VERSION_PATCH,
|
||||
# ifdef SIMULATE_VERSION_TWEAK
|
||||
'.', SIMULATE_VERSION_TWEAK,
|
||||
# endif
|
||||
# endif
|
||||
# endif
|
||||
']','\0'};
|
||||
#endif
|
||||
|
||||
/* Construct the string literal in pieces to prevent the source from
|
||||
getting matched. Store it in a pointer rather than an array
|
||||
because some compilers will just produce instructions to fill the
|
||||
array rather than assigning a pointer to a static array. */
|
||||
char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]";
|
||||
char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]";
|
||||
|
||||
|
||||
|
||||
#if !defined(__STDC__) && !defined(__clang__)
|
||||
# if defined(_MSC_VER) || defined(__ibmxl__) || defined(__IBMC__)
|
||||
# define C_VERSION "90"
|
||||
# else
|
||||
# define C_VERSION
|
||||
# endif
|
||||
#elif __STDC_VERSION__ > 201710L
|
||||
# define C_VERSION "23"
|
||||
#elif __STDC_VERSION__ >= 201710L
|
||||
# define C_VERSION "17"
|
||||
#elif __STDC_VERSION__ >= 201000L
|
||||
# define C_VERSION "11"
|
||||
#elif __STDC_VERSION__ >= 199901L
|
||||
# define C_VERSION "99"
|
||||
#else
|
||||
# define C_VERSION "90"
|
||||
#endif
|
||||
const char* info_language_standard_default =
|
||||
"INFO" ":" "standard_default[" C_VERSION "]";
|
||||
|
||||
const char* info_language_extensions_default = "INFO" ":" "extensions_default["
|
||||
/* !defined(_MSC_VER) to exclude Clang's MSVC compatibility mode. */
|
||||
#if (defined(__clang__) || defined(__GNUC__) || \
|
||||
defined(__TI_COMPILER_VERSION__)) && \
|
||||
!defined(__STRICT_ANSI__) && !defined(_MSC_VER)
|
||||
"ON"
|
||||
#else
|
||||
"OFF"
|
||||
#endif
|
||||
"]";
|
||||
|
||||
/*--------------------------------------------------------------------------*/
|
||||
|
||||
#ifdef ID_VOID_MAIN
|
||||
void main() {}
|
||||
#else
|
||||
# if defined(__CLASSIC_C__)
|
||||
int main(argc, argv) int argc; char *argv[];
|
||||
# else
|
||||
int main(int argc, char* argv[])
|
||||
# endif
|
||||
{
|
||||
int require = 0;
|
||||
require += info_compiler[argc];
|
||||
require += info_platform[argc];
|
||||
require += info_arch[argc];
|
||||
#ifdef COMPILER_VERSION_MAJOR
|
||||
require += info_version[argc];
|
||||
#endif
|
||||
#ifdef COMPILER_VERSION_INTERNAL
|
||||
require += info_version_internal[argc];
|
||||
#endif
|
||||
#ifdef SIMULATE_ID
|
||||
require += info_simulate[argc];
|
||||
#endif
|
||||
#ifdef SIMULATE_VERSION_MAJOR
|
||||
require += info_simulate_version[argc];
|
||||
#endif
|
||||
#if defined(__CRAYXT_COMPUTE_LINUX_TARGET)
|
||||
require += info_cray[argc];
|
||||
#endif
|
||||
require += info_language_standard_default[argc];
|
||||
require += info_language_extensions_default[argc];
|
||||
(void)argv;
|
||||
return require;
|
||||
}
|
||||
#endif
|
||||
@@ -0,0 +1,791 @@
|
||||
/* This source file must have a .cpp extension so that all C++ compilers
|
||||
recognize the extension without flags. Borland does not know .cxx for
|
||||
example. */
|
||||
#ifndef __cplusplus
|
||||
# error "A C compiler has been selected for C++."
|
||||
#endif
|
||||
|
||||
#if !defined(__has_include)
|
||||
/* If the compiler does not have __has_include, pretend the answer is
|
||||
always no. */
|
||||
# define __has_include(x) 0
|
||||
#endif
|
||||
|
||||
|
||||
/* Version number components: V=Version, R=Revision, P=Patch
|
||||
Version date components: YYYY=Year, MM=Month, DD=Day */
|
||||
|
||||
#if defined(__COMO__)
|
||||
# define COMPILER_ID "Comeau"
|
||||
/* __COMO_VERSION__ = VRR */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__COMO_VERSION__ / 100)
|
||||
# define COMPILER_VERSION_MINOR DEC(__COMO_VERSION__ % 100)
|
||||
|
||||
#elif defined(__INTEL_COMPILER) || defined(__ICC)
|
||||
# define COMPILER_ID "Intel"
|
||||
# if defined(_MSC_VER)
|
||||
# define SIMULATE_ID "MSVC"
|
||||
# endif
|
||||
# if defined(__GNUC__)
|
||||
# define SIMULATE_ID "GNU"
|
||||
# endif
|
||||
/* __INTEL_COMPILER = VRP prior to 2021, and then VVVV for 2021 and later,
|
||||
except that a few beta releases use the old format with V=2021. */
|
||||
# if __INTEL_COMPILER < 2021 || __INTEL_COMPILER == 202110 || __INTEL_COMPILER == 202111
|
||||
# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100)
|
||||
# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10)
|
||||
# if defined(__INTEL_COMPILER_UPDATE)
|
||||
# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER_UPDATE)
|
||||
# else
|
||||
# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10)
|
||||
# endif
|
||||
# else
|
||||
# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER)
|
||||
# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER_UPDATE)
|
||||
/* The third version component from --version is an update index,
|
||||
but no macro is provided for it. */
|
||||
# define COMPILER_VERSION_PATCH DEC(0)
|
||||
# endif
|
||||
# if defined(__INTEL_COMPILER_BUILD_DATE)
|
||||
/* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */
|
||||
# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE)
|
||||
# endif
|
||||
# if defined(_MSC_VER)
|
||||
/* _MSC_VER = VVRR */
|
||||
# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
|
||||
# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
|
||||
# endif
|
||||
# if defined(__GNUC__)
|
||||
# define SIMULATE_VERSION_MAJOR DEC(__GNUC__)
|
||||
# elif defined(__GNUG__)
|
||||
# define SIMULATE_VERSION_MAJOR DEC(__GNUG__)
|
||||
# endif
|
||||
# if defined(__GNUC_MINOR__)
|
||||
# define SIMULATE_VERSION_MINOR DEC(__GNUC_MINOR__)
|
||||
# endif
|
||||
# if defined(__GNUC_PATCHLEVEL__)
|
||||
# define SIMULATE_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__)
|
||||
# endif
|
||||
|
||||
#elif (defined(__clang__) && defined(__INTEL_CLANG_COMPILER)) || defined(__INTEL_LLVM_COMPILER)
|
||||
# define COMPILER_ID "IntelLLVM"
|
||||
#if defined(_MSC_VER)
|
||||
# define SIMULATE_ID "MSVC"
|
||||
#endif
|
||||
#if defined(__GNUC__)
|
||||
# define SIMULATE_ID "GNU"
|
||||
#endif
|
||||
/* __INTEL_LLVM_COMPILER = VVVVRP prior to 2021.2.0, VVVVRRPP for 2021.2.0 and
|
||||
* later. Look for 6 digit vs. 8 digit version number to decide encoding.
|
||||
* VVVV is no smaller than the current year when a version is released.
|
||||
*/
|
||||
#if __INTEL_LLVM_COMPILER < 1000000L
|
||||
# define COMPILER_VERSION_MAJOR DEC(__INTEL_LLVM_COMPILER/100)
|
||||
# define COMPILER_VERSION_MINOR DEC(__INTEL_LLVM_COMPILER/10 % 10)
|
||||
# define COMPILER_VERSION_PATCH DEC(__INTEL_LLVM_COMPILER % 10)
|
||||
#else
|
||||
# define COMPILER_VERSION_MAJOR DEC(__INTEL_LLVM_COMPILER/10000)
|
||||
# define COMPILER_VERSION_MINOR DEC(__INTEL_LLVM_COMPILER/100 % 100)
|
||||
# define COMPILER_VERSION_PATCH DEC(__INTEL_LLVM_COMPILER % 100)
|
||||
#endif
|
||||
#if defined(_MSC_VER)
|
||||
/* _MSC_VER = VVRR */
|
||||
# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
|
||||
# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
|
||||
#endif
|
||||
#if defined(__GNUC__)
|
||||
# define SIMULATE_VERSION_MAJOR DEC(__GNUC__)
|
||||
#elif defined(__GNUG__)
|
||||
# define SIMULATE_VERSION_MAJOR DEC(__GNUG__)
|
||||
#endif
|
||||
#if defined(__GNUC_MINOR__)
|
||||
# define SIMULATE_VERSION_MINOR DEC(__GNUC_MINOR__)
|
||||
#endif
|
||||
#if defined(__GNUC_PATCHLEVEL__)
|
||||
# define SIMULATE_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__)
|
||||
#endif
|
||||
|
||||
#elif defined(__PATHCC__)
|
||||
# define COMPILER_ID "PathScale"
|
||||
# define COMPILER_VERSION_MAJOR DEC(__PATHCC__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__)
|
||||
# if defined(__PATHCC_PATCHLEVEL__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__)
|
||||
# endif
|
||||
|
||||
#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__)
|
||||
# define COMPILER_ID "Embarcadero"
|
||||
# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF)
|
||||
# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF)
|
||||
# define COMPILER_VERSION_PATCH DEC(__CODEGEARC_VERSION__ & 0xFFFF)
|
||||
|
||||
#elif defined(__BORLANDC__)
|
||||
# define COMPILER_ID "Borland"
|
||||
/* __BORLANDC__ = 0xVRR */
|
||||
# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8)
|
||||
# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF)
|
||||
|
||||
#elif defined(__WATCOMC__) && __WATCOMC__ < 1200
|
||||
# define COMPILER_ID "Watcom"
|
||||
/* __WATCOMC__ = VVRR */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100)
|
||||
# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10)
|
||||
# if (__WATCOMC__ % 10) > 0
|
||||
# define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10)
|
||||
# endif
|
||||
|
||||
#elif defined(__WATCOMC__)
|
||||
# define COMPILER_ID "OpenWatcom"
|
||||
/* __WATCOMC__ = VVRP + 1100 */
|
||||
# define COMPILER_VERSION_MAJOR DEC((__WATCOMC__ - 1100) / 100)
|
||||
# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10)
|
||||
# if (__WATCOMC__ % 10) > 0
|
||||
# define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10)
|
||||
# endif
|
||||
|
||||
#elif defined(__SUNPRO_CC)
|
||||
# define COMPILER_ID "SunPro"
|
||||
# if __SUNPRO_CC >= 0x5100
|
||||
/* __SUNPRO_CC = 0xVRRP */
|
||||
# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>12)
|
||||
# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xFF)
|
||||
# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF)
|
||||
# else
|
||||
/* __SUNPRO_CC = 0xVRP */
|
||||
# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>8)
|
||||
# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xF)
|
||||
# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF)
|
||||
# endif
|
||||
|
||||
#elif defined(__HP_aCC)
|
||||
# define COMPILER_ID "HP"
|
||||
/* __HP_aCC = VVRRPP */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__HP_aCC/10000)
|
||||
# define COMPILER_VERSION_MINOR DEC(__HP_aCC/100 % 100)
|
||||
# define COMPILER_VERSION_PATCH DEC(__HP_aCC % 100)
|
||||
|
||||
#elif defined(__DECCXX)
|
||||
# define COMPILER_ID "Compaq"
|
||||
/* __DECCXX_VER = VVRRTPPPP */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__DECCXX_VER/10000000)
|
||||
# define COMPILER_VERSION_MINOR DEC(__DECCXX_VER/100000 % 100)
|
||||
# define COMPILER_VERSION_PATCH DEC(__DECCXX_VER % 10000)
|
||||
|
||||
#elif defined(__IBMCPP__) && defined(__COMPILER_VER__)
|
||||
# define COMPILER_ID "zOS"
|
||||
/* __IBMCPP__ = VRP */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100)
|
||||
# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10)
|
||||
# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10)
|
||||
|
||||
#elif defined(__ibmxl__) && defined(__clang__)
|
||||
# define COMPILER_ID "XLClang"
|
||||
# define COMPILER_VERSION_MAJOR DEC(__ibmxl_version__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__ibmxl_release__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__ibmxl_modification__)
|
||||
# define COMPILER_VERSION_TWEAK DEC(__ibmxl_ptf_fix_level__)
|
||||
|
||||
|
||||
#elif defined(__IBMCPP__) && !defined(__COMPILER_VER__) && __IBMCPP__ >= 800
|
||||
# define COMPILER_ID "XL"
|
||||
/* __IBMCPP__ = VRP */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100)
|
||||
# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10)
|
||||
# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10)
|
||||
|
||||
#elif defined(__IBMCPP__) && !defined(__COMPILER_VER__) && __IBMCPP__ < 800
|
||||
# define COMPILER_ID "VisualAge"
|
||||
/* __IBMCPP__ = VRP */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100)
|
||||
# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10)
|
||||
# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10)
|
||||
|
||||
#elif defined(__NVCOMPILER)
|
||||
# define COMPILER_ID "NVHPC"
|
||||
# define COMPILER_VERSION_MAJOR DEC(__NVCOMPILER_MAJOR__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__NVCOMPILER_MINOR__)
|
||||
# if defined(__NVCOMPILER_PATCHLEVEL__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__NVCOMPILER_PATCHLEVEL__)
|
||||
# endif
|
||||
|
||||
#elif defined(__PGI)
|
||||
# define COMPILER_ID "PGI"
|
||||
# define COMPILER_VERSION_MAJOR DEC(__PGIC__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__)
|
||||
# if defined(__PGIC_PATCHLEVEL__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__)
|
||||
# endif
|
||||
|
||||
#elif defined(_CRAYC)
|
||||
# define COMPILER_ID "Cray"
|
||||
# define COMPILER_VERSION_MAJOR DEC(_RELEASE_MAJOR)
|
||||
# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR)
|
||||
|
||||
#elif defined(__TI_COMPILER_VERSION__)
|
||||
# define COMPILER_ID "TI"
|
||||
/* __TI_COMPILER_VERSION__ = VVVRRRPPP */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000)
|
||||
# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000)
|
||||
# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000)
|
||||
|
||||
#elif defined(__CLANG_FUJITSU)
|
||||
# define COMPILER_ID "FujitsuClang"
|
||||
# define COMPILER_VERSION_MAJOR DEC(__FCC_major__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__FCC_minor__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__FCC_patchlevel__)
|
||||
# define COMPILER_VERSION_INTERNAL_STR __clang_version__
|
||||
|
||||
|
||||
#elif defined(__FUJITSU)
|
||||
# define COMPILER_ID "Fujitsu"
|
||||
# if defined(__FCC_version__)
|
||||
# define COMPILER_VERSION __FCC_version__
|
||||
# elif defined(__FCC_major__)
|
||||
# define COMPILER_VERSION_MAJOR DEC(__FCC_major__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__FCC_minor__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__FCC_patchlevel__)
|
||||
# endif
|
||||
# if defined(__fcc_version)
|
||||
# define COMPILER_VERSION_INTERNAL DEC(__fcc_version)
|
||||
# elif defined(__FCC_VERSION)
|
||||
# define COMPILER_VERSION_INTERNAL DEC(__FCC_VERSION)
|
||||
# endif
|
||||
|
||||
|
||||
#elif defined(__ghs__)
|
||||
# define COMPILER_ID "GHS"
|
||||
/* __GHS_VERSION_NUMBER = VVVVRP */
|
||||
# ifdef __GHS_VERSION_NUMBER
|
||||
# define COMPILER_VERSION_MAJOR DEC(__GHS_VERSION_NUMBER / 100)
|
||||
# define COMPILER_VERSION_MINOR DEC(__GHS_VERSION_NUMBER / 10 % 10)
|
||||
# define COMPILER_VERSION_PATCH DEC(__GHS_VERSION_NUMBER % 10)
|
||||
# endif
|
||||
|
||||
#elif defined(__SCO_VERSION__)
|
||||
# define COMPILER_ID "SCO"
|
||||
|
||||
#elif defined(__ARMCC_VERSION) && !defined(__clang__)
|
||||
# define COMPILER_ID "ARMCC"
|
||||
#if __ARMCC_VERSION >= 1000000
|
||||
/* __ARMCC_VERSION = VRRPPPP */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/1000000)
|
||||
# define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 100)
|
||||
# define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000)
|
||||
#else
|
||||
/* __ARMCC_VERSION = VRPPPP */
|
||||
# define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/100000)
|
||||
# define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 10)
|
||||
# define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000)
|
||||
#endif
|
||||
|
||||
|
||||
#elif defined(__clang__) && defined(__apple_build_version__)
|
||||
# define COMPILER_ID "AppleClang"
|
||||
# if defined(_MSC_VER)
|
||||
# define SIMULATE_ID "MSVC"
|
||||
# endif
|
||||
# define COMPILER_VERSION_MAJOR DEC(__clang_major__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__clang_minor__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__)
|
||||
# if defined(_MSC_VER)
|
||||
/* _MSC_VER = VVRR */
|
||||
# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
|
||||
# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
|
||||
# endif
|
||||
# define COMPILER_VERSION_TWEAK DEC(__apple_build_version__)
|
||||
|
||||
#elif defined(__clang__) && defined(__ARMCOMPILER_VERSION)
|
||||
# define COMPILER_ID "ARMClang"
|
||||
# define COMPILER_VERSION_MAJOR DEC(__ARMCOMPILER_VERSION/1000000)
|
||||
# define COMPILER_VERSION_MINOR DEC(__ARMCOMPILER_VERSION/10000 % 100)
|
||||
# define COMPILER_VERSION_PATCH DEC(__ARMCOMPILER_VERSION % 10000)
|
||||
# define COMPILER_VERSION_INTERNAL DEC(__ARMCOMPILER_VERSION)
|
||||
|
||||
#elif defined(__clang__)
|
||||
# define COMPILER_ID "Clang"
|
||||
# if defined(_MSC_VER)
|
||||
# define SIMULATE_ID "MSVC"
|
||||
# endif
|
||||
# define COMPILER_VERSION_MAJOR DEC(__clang_major__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__clang_minor__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__)
|
||||
# if defined(_MSC_VER)
|
||||
/* _MSC_VER = VVRR */
|
||||
# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
|
||||
# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
|
||||
# endif
|
||||
|
||||
#elif defined(__GNUC__) || defined(__GNUG__)
|
||||
# define COMPILER_ID "GNU"
|
||||
# if defined(__GNUC__)
|
||||
# define COMPILER_VERSION_MAJOR DEC(__GNUC__)
|
||||
# else
|
||||
# define COMPILER_VERSION_MAJOR DEC(__GNUG__)
|
||||
# endif
|
||||
# if defined(__GNUC_MINOR__)
|
||||
# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__)
|
||||
# endif
|
||||
# if defined(__GNUC_PATCHLEVEL__)
|
||||
# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__)
|
||||
# endif
|
||||
|
||||
#elif defined(_MSC_VER)
|
||||
# define COMPILER_ID "MSVC"
|
||||
/* _MSC_VER = VVRR */
|
||||
# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100)
|
||||
# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100)
|
||||
# if defined(_MSC_FULL_VER)
|
||||
# if _MSC_VER >= 1400
|
||||
/* _MSC_FULL_VER = VVRRPPPPP */
|
||||
# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000)
|
||||
# else
|
||||
/* _MSC_FULL_VER = VVRRPPPP */
|
||||
# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000)
|
||||
# endif
|
||||
# endif
|
||||
# if defined(_MSC_BUILD)
|
||||
# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD)
|
||||
# endif
|
||||
|
||||
#elif defined(__VISUALDSPVERSION__) || defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__)
|
||||
# define COMPILER_ID "ADSP"
|
||||
#if defined(__VISUALDSPVERSION__)
|
||||
/* __VISUALDSPVERSION__ = 0xVVRRPP00 */
|
||||
# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24)
|
||||
# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF)
|
||||
# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF)
|
||||
#endif
|
||||
|
||||
#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC)
|
||||
# define COMPILER_ID "IAR"
|
||||
# if defined(__VER__) && defined(__ICCARM__)
|
||||
# define COMPILER_VERSION_MAJOR DEC((__VER__) / 1000000)
|
||||
# define COMPILER_VERSION_MINOR DEC(((__VER__) / 1000) % 1000)
|
||||
# define COMPILER_VERSION_PATCH DEC((__VER__) % 1000)
|
||||
# define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__)
|
||||
# elif defined(__VER__) && (defined(__ICCAVR__) || defined(__ICCRX__) || defined(__ICCRH850__) || defined(__ICCRL78__) || defined(__ICC430__) || defined(__ICCRISCV__) || defined(__ICCV850__) || defined(__ICC8051__) || defined(__ICCSTM8__))
|
||||
# define COMPILER_VERSION_MAJOR DEC((__VER__) / 100)
|
||||
# define COMPILER_VERSION_MINOR DEC((__VER__) - (((__VER__) / 100)*100))
|
||||
# define COMPILER_VERSION_PATCH DEC(__SUBVERSION__)
|
||||
# define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__)
|
||||
# endif
|
||||
|
||||
|
||||
/* These compilers are either not known or too old to define an
|
||||
identification macro. Try to identify the platform and guess that
|
||||
it is the native compiler. */
|
||||
#elif defined(__hpux) || defined(__hpua)
|
||||
# define COMPILER_ID "HP"
|
||||
|
||||
#else /* unknown compiler */
|
||||
# define COMPILER_ID ""
|
||||
#endif
|
||||
|
||||
/* Construct the string literal in pieces to prevent the source from
|
||||
getting matched. Store it in a pointer rather than an array
|
||||
because some compilers will just produce instructions to fill the
|
||||
array rather than assigning a pointer to a static array. */
|
||||
char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]";
|
||||
#ifdef SIMULATE_ID
|
||||
char const* info_simulate = "INFO" ":" "simulate[" SIMULATE_ID "]";
|
||||
#endif
|
||||
|
||||
#ifdef __QNXNTO__
|
||||
char const* qnxnto = "INFO" ":" "qnxnto[]";
|
||||
#endif
|
||||
|
||||
#if defined(__CRAYXT_COMPUTE_LINUX_TARGET)
|
||||
char const *info_cray = "INFO" ":" "compiler_wrapper[CrayPrgEnv]";
|
||||
#endif
|
||||
|
||||
#define STRINGIFY_HELPER(X) #X
|
||||
#define STRINGIFY(X) STRINGIFY_HELPER(X)
|
||||
|
||||
/* Identify known platforms by name. */
|
||||
#if defined(__linux) || defined(__linux__) || defined(linux)
|
||||
# define PLATFORM_ID "Linux"
|
||||
|
||||
#elif defined(__MSYS__)
|
||||
# define PLATFORM_ID "MSYS"
|
||||
|
||||
#elif defined(__CYGWIN__)
|
||||
# define PLATFORM_ID "Cygwin"
|
||||
|
||||
#elif defined(__MINGW32__)
|
||||
# define PLATFORM_ID "MinGW"
|
||||
|
||||
#elif defined(__APPLE__)
|
||||
# define PLATFORM_ID "Darwin"
|
||||
|
||||
#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32)
|
||||
# define PLATFORM_ID "Windows"
|
||||
|
||||
#elif defined(__FreeBSD__) || defined(__FreeBSD)
|
||||
# define PLATFORM_ID "FreeBSD"
|
||||
|
||||
#elif defined(__NetBSD__) || defined(__NetBSD)
|
||||
# define PLATFORM_ID "NetBSD"
|
||||
|
||||
#elif defined(__OpenBSD__) || defined(__OPENBSD)
|
||||
# define PLATFORM_ID "OpenBSD"
|
||||
|
||||
#elif defined(__sun) || defined(sun)
|
||||
# define PLATFORM_ID "SunOS"
|
||||
|
||||
#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__)
|
||||
# define PLATFORM_ID "AIX"
|
||||
|
||||
#elif defined(__hpux) || defined(__hpux__)
|
||||
# define PLATFORM_ID "HP-UX"
|
||||
|
||||
#elif defined(__HAIKU__)
|
||||
# define PLATFORM_ID "Haiku"
|
||||
|
||||
#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS)
|
||||
# define PLATFORM_ID "BeOS"
|
||||
|
||||
#elif defined(__QNX__) || defined(__QNXNTO__)
|
||||
# define PLATFORM_ID "QNX"
|
||||
|
||||
#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__)
|
||||
# define PLATFORM_ID "Tru64"
|
||||
|
||||
#elif defined(__riscos) || defined(__riscos__)
|
||||
# define PLATFORM_ID "RISCos"
|
||||
|
||||
#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__)
|
||||
# define PLATFORM_ID "SINIX"
|
||||
|
||||
#elif defined(__UNIX_SV__)
|
||||
# define PLATFORM_ID "UNIX_SV"
|
||||
|
||||
#elif defined(__bsdos__)
|
||||
# define PLATFORM_ID "BSDOS"
|
||||
|
||||
#elif defined(_MPRAS) || defined(MPRAS)
|
||||
# define PLATFORM_ID "MP-RAS"
|
||||
|
||||
#elif defined(__osf) || defined(__osf__)
|
||||
# define PLATFORM_ID "OSF1"
|
||||
|
||||
#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv)
|
||||
# define PLATFORM_ID "SCO_SV"
|
||||
|
||||
#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX)
|
||||
# define PLATFORM_ID "ULTRIX"
|
||||
|
||||
#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX)
|
||||
# define PLATFORM_ID "Xenix"
|
||||
|
||||
#elif defined(__WATCOMC__)
|
||||
# if defined(__LINUX__)
|
||||
# define PLATFORM_ID "Linux"
|
||||
|
||||
# elif defined(__DOS__)
|
||||
# define PLATFORM_ID "DOS"
|
||||
|
||||
# elif defined(__OS2__)
|
||||
# define PLATFORM_ID "OS2"
|
||||
|
||||
# elif defined(__WINDOWS__)
|
||||
# define PLATFORM_ID "Windows3x"
|
||||
|
||||
# elif defined(__VXWORKS__)
|
||||
# define PLATFORM_ID "VxWorks"
|
||||
|
||||
# else /* unknown platform */
|
||||
# define PLATFORM_ID
|
||||
# endif
|
||||
|
||||
#elif defined(__INTEGRITY)
|
||||
# if defined(INT_178B)
|
||||
# define PLATFORM_ID "Integrity178"
|
||||
|
||||
# else /* regular Integrity */
|
||||
# define PLATFORM_ID "Integrity"
|
||||
# endif
|
||||
|
||||
#else /* unknown platform */
|
||||
# define PLATFORM_ID
|
||||
|
||||
#endif
|
||||
|
||||
/* For windows compilers MSVC and Intel we can determine
|
||||
the architecture of the compiler being used. This is because
|
||||
the compilers do not have flags that can change the architecture,
|
||||
but rather depend on which compiler is being used
|
||||
*/
|
||||
#if defined(_WIN32) && defined(_MSC_VER)
|
||||
# if defined(_M_IA64)
|
||||
# define ARCHITECTURE_ID "IA64"
|
||||
|
||||
# elif defined(_M_ARM64EC)
|
||||
# define ARCHITECTURE_ID "ARM64EC"
|
||||
|
||||
# elif defined(_M_X64) || defined(_M_AMD64)
|
||||
# define ARCHITECTURE_ID "x64"
|
||||
|
||||
# elif defined(_M_IX86)
|
||||
# define ARCHITECTURE_ID "X86"
|
||||
|
||||
# elif defined(_M_ARM64)
|
||||
# define ARCHITECTURE_ID "ARM64"
|
||||
|
||||
# elif defined(_M_ARM)
|
||||
# if _M_ARM == 4
|
||||
# define ARCHITECTURE_ID "ARMV4I"
|
||||
# elif _M_ARM == 5
|
||||
# define ARCHITECTURE_ID "ARMV5I"
|
||||
# else
|
||||
# define ARCHITECTURE_ID "ARMV" STRINGIFY(_M_ARM)
|
||||
# endif
|
||||
|
||||
# elif defined(_M_MIPS)
|
||||
# define ARCHITECTURE_ID "MIPS"
|
||||
|
||||
# elif defined(_M_SH)
|
||||
# define ARCHITECTURE_ID "SHx"
|
||||
|
||||
# else /* unknown architecture */
|
||||
# define ARCHITECTURE_ID ""
|
||||
# endif
|
||||
|
||||
#elif defined(__WATCOMC__)
|
||||
# if defined(_M_I86)
|
||||
# define ARCHITECTURE_ID "I86"
|
||||
|
||||
# elif defined(_M_IX86)
|
||||
# define ARCHITECTURE_ID "X86"
|
||||
|
||||
# else /* unknown architecture */
|
||||
# define ARCHITECTURE_ID ""
|
||||
# endif
|
||||
|
||||
#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC)
|
||||
# if defined(__ICCARM__)
|
||||
# define ARCHITECTURE_ID "ARM"
|
||||
|
||||
# elif defined(__ICCRX__)
|
||||
# define ARCHITECTURE_ID "RX"
|
||||
|
||||
# elif defined(__ICCRH850__)
|
||||
# define ARCHITECTURE_ID "RH850"
|
||||
|
||||
# elif defined(__ICCRL78__)
|
||||
# define ARCHITECTURE_ID "RL78"
|
||||
|
||||
# elif defined(__ICCRISCV__)
|
||||
# define ARCHITECTURE_ID "RISCV"
|
||||
|
||||
# elif defined(__ICCAVR__)
|
||||
# define ARCHITECTURE_ID "AVR"
|
||||
|
||||
# elif defined(__ICC430__)
|
||||
# define ARCHITECTURE_ID "MSP430"
|
||||
|
||||
# elif defined(__ICCV850__)
|
||||
# define ARCHITECTURE_ID "V850"
|
||||
|
||||
# elif defined(__ICC8051__)
|
||||
# define ARCHITECTURE_ID "8051"
|
||||
|
||||
# elif defined(__ICCSTM8__)
|
||||
# define ARCHITECTURE_ID "STM8"
|
||||
|
||||
# else /* unknown architecture */
|
||||
# define ARCHITECTURE_ID ""
|
||||
# endif
|
||||
|
||||
#elif defined(__ghs__)
|
||||
# if defined(__PPC64__)
|
||||
# define ARCHITECTURE_ID "PPC64"
|
||||
|
||||
# elif defined(__ppc__)
|
||||
# define ARCHITECTURE_ID "PPC"
|
||||
|
||||
# elif defined(__ARM__)
|
||||
# define ARCHITECTURE_ID "ARM"
|
||||
|
||||
# elif defined(__x86_64__)
|
||||
# define ARCHITECTURE_ID "x64"
|
||||
|
||||
# elif defined(__i386__)
|
||||
# define ARCHITECTURE_ID "X86"
|
||||
|
||||
# else /* unknown architecture */
|
||||
# define ARCHITECTURE_ID ""
|
||||
# endif
|
||||
|
||||
#elif defined(__TI_COMPILER_VERSION__)
|
||||
# if defined(__TI_ARM__)
|
||||
# define ARCHITECTURE_ID "ARM"
|
||||
|
||||
# elif defined(__MSP430__)
|
||||
# define ARCHITECTURE_ID "MSP430"
|
||||
|
||||
# elif defined(__TMS320C28XX__)
|
||||
# define ARCHITECTURE_ID "TMS320C28x"
|
||||
|
||||
# elif defined(__TMS320C6X__) || defined(_TMS320C6X)
|
||||
# define ARCHITECTURE_ID "TMS320C6x"
|
||||
|
||||
# else /* unknown architecture */
|
||||
# define ARCHITECTURE_ID ""
|
||||
# endif
|
||||
|
||||
#else
|
||||
# define ARCHITECTURE_ID
|
||||
#endif
|
||||
|
||||
/* Convert integer to decimal digit literals. */
|
||||
#define DEC(n) \
|
||||
('0' + (((n) / 10000000)%10)), \
|
||||
('0' + (((n) / 1000000)%10)), \
|
||||
('0' + (((n) / 100000)%10)), \
|
||||
('0' + (((n) / 10000)%10)), \
|
||||
('0' + (((n) / 1000)%10)), \
|
||||
('0' + (((n) / 100)%10)), \
|
||||
('0' + (((n) / 10)%10)), \
|
||||
('0' + ((n) % 10))
|
||||
|
||||
/* Convert integer to hex digit literals. */
|
||||
#define HEX(n) \
|
||||
('0' + ((n)>>28 & 0xF)), \
|
||||
('0' + ((n)>>24 & 0xF)), \
|
||||
('0' + ((n)>>20 & 0xF)), \
|
||||
('0' + ((n)>>16 & 0xF)), \
|
||||
('0' + ((n)>>12 & 0xF)), \
|
||||
('0' + ((n)>>8 & 0xF)), \
|
||||
('0' + ((n)>>4 & 0xF)), \
|
||||
('0' + ((n) & 0xF))
|
||||
|
||||
/* Construct a string literal encoding the version number. */
|
||||
#ifdef COMPILER_VERSION
|
||||
char const* info_version = "INFO" ":" "compiler_version[" COMPILER_VERSION "]";
|
||||
|
||||
/* Construct a string literal encoding the version number components. */
|
||||
#elif defined(COMPILER_VERSION_MAJOR)
|
||||
char const info_version[] = {
|
||||
'I', 'N', 'F', 'O', ':',
|
||||
'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[',
|
||||
COMPILER_VERSION_MAJOR,
|
||||
# ifdef COMPILER_VERSION_MINOR
|
||||
'.', COMPILER_VERSION_MINOR,
|
||||
# ifdef COMPILER_VERSION_PATCH
|
||||
'.', COMPILER_VERSION_PATCH,
|
||||
# ifdef COMPILER_VERSION_TWEAK
|
||||
'.', COMPILER_VERSION_TWEAK,
|
||||
# endif
|
||||
# endif
|
||||
# endif
|
||||
']','\0'};
|
||||
#endif
|
||||
|
||||
/* Construct a string literal encoding the internal version number. */
|
||||
#ifdef COMPILER_VERSION_INTERNAL
|
||||
char const info_version_internal[] = {
|
||||
'I', 'N', 'F', 'O', ':',
|
||||
'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','_',
|
||||
'i','n','t','e','r','n','a','l','[',
|
||||
COMPILER_VERSION_INTERNAL,']','\0'};
|
||||
#elif defined(COMPILER_VERSION_INTERNAL_STR)
|
||||
char const* info_version_internal = "INFO" ":" "compiler_version_internal[" COMPILER_VERSION_INTERNAL_STR "]";
|
||||
#endif
|
||||
|
||||
/* Construct a string literal encoding the version number components. */
|
||||
#ifdef SIMULATE_VERSION_MAJOR
|
||||
char const info_simulate_version[] = {
|
||||
'I', 'N', 'F', 'O', ':',
|
||||
's','i','m','u','l','a','t','e','_','v','e','r','s','i','o','n','[',
|
||||
SIMULATE_VERSION_MAJOR,
|
||||
# ifdef SIMULATE_VERSION_MINOR
|
||||
'.', SIMULATE_VERSION_MINOR,
|
||||
# ifdef SIMULATE_VERSION_PATCH
|
||||
'.', SIMULATE_VERSION_PATCH,
|
||||
# ifdef SIMULATE_VERSION_TWEAK
|
||||
'.', SIMULATE_VERSION_TWEAK,
|
||||
# endif
|
||||
# endif
|
||||
# endif
|
||||
']','\0'};
|
||||
#endif
|
||||
|
||||
/* Construct the string literal in pieces to prevent the source from
|
||||
getting matched. Store it in a pointer rather than an array
|
||||
because some compilers will just produce instructions to fill the
|
||||
array rather than assigning a pointer to a static array. */
|
||||
char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]";
|
||||
char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]";
|
||||
|
||||
|
||||
|
||||
#if defined(__INTEL_COMPILER) && defined(_MSVC_LANG) && _MSVC_LANG < 201403L
|
||||
# if defined(__INTEL_CXX11_MODE__)
|
||||
# if defined(__cpp_aggregate_nsdmi)
|
||||
# define CXX_STD 201402L
|
||||
# else
|
||||
# define CXX_STD 201103L
|
||||
# endif
|
||||
# else
|
||||
# define CXX_STD 199711L
|
||||
# endif
|
||||
#elif defined(_MSC_VER) && defined(_MSVC_LANG)
|
||||
# define CXX_STD _MSVC_LANG
|
||||
#else
|
||||
# define CXX_STD __cplusplus
|
||||
#endif
|
||||
|
||||
const char* info_language_standard_default = "INFO" ":" "standard_default["
|
||||
#if CXX_STD > 202002L
|
||||
"23"
|
||||
#elif CXX_STD > 201703L
|
||||
"20"
|
||||
#elif CXX_STD >= 201703L
|
||||
"17"
|
||||
#elif CXX_STD >= 201402L
|
||||
"14"
|
||||
#elif CXX_STD >= 201103L
|
||||
"11"
|
||||
#else
|
||||
"98"
|
||||
#endif
|
||||
"]";
|
||||
|
||||
const char* info_language_extensions_default = "INFO" ":" "extensions_default["
|
||||
/* !defined(_MSC_VER) to exclude Clang's MSVC compatibility mode. */
|
||||
#if (defined(__clang__) || defined(__GNUC__) || \
|
||||
defined(__TI_COMPILER_VERSION__)) && \
|
||||
!defined(__STRICT_ANSI__) && !defined(_MSC_VER)
|
||||
"ON"
|
||||
#else
|
||||
"OFF"
|
||||
#endif
|
||||
"]";
|
||||
|
||||
/*--------------------------------------------------------------------------*/
|
||||
|
||||
int main(int argc, char* argv[])
|
||||
{
|
||||
int require = 0;
|
||||
require += info_compiler[argc];
|
||||
require += info_platform[argc];
|
||||
#ifdef COMPILER_VERSION_MAJOR
|
||||
require += info_version[argc];
|
||||
#endif
|
||||
#ifdef COMPILER_VERSION_INTERNAL
|
||||
require += info_version_internal[argc];
|
||||
#endif
|
||||
#ifdef SIMULATE_ID
|
||||
require += info_simulate[argc];
|
||||
#endif
|
||||
#ifdef SIMULATE_VERSION_MAJOR
|
||||
require += info_simulate_version[argc];
|
||||
#endif
|
||||
#if defined(__CRAYXT_COMPUTE_LINUX_TARGET)
|
||||
require += info_cray[argc];
|
||||
#endif
|
||||
require += info_language_standard_default[argc];
|
||||
require += info_language_extensions_default[argc];
|
||||
(void)argv;
|
||||
return require;
|
||||
}
|
||||
@@ -0,0 +1,16 @@
|
||||
# CMAKE generated file: DO NOT EDIT!
|
||||
# Generated by "Unix Makefiles" Generator, CMake Version 3.22
|
||||
|
||||
# Relative path conversion top directories.
|
||||
set(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect")
|
||||
set(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect")
|
||||
|
||||
# Force unix paths in dependencies.
|
||||
set(CMAKE_FORCE_UNIX_PATHS 1)
|
||||
|
||||
|
||||
# The C and CXX include file regular expressions for this directory.
|
||||
set(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$")
|
||||
set(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$")
|
||||
set(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN})
|
||||
set(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN})
|
||||
@@ -0,0 +1,485 @@
|
||||
The system is: Linux - 5.15.148-tegra - aarch64
|
||||
Compiling the C compiler identification source file "CMakeCCompilerId.c" succeeded.
|
||||
Compiler: /usr/bin/cc
|
||||
Build flags:
|
||||
Id flags:
|
||||
|
||||
The output was:
|
||||
0
|
||||
|
||||
|
||||
Compilation of the C compiler identification source "CMakeCCompilerId.c" produced "a.out"
|
||||
|
||||
The C compiler identification is GNU, found in "/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/3.22.1/CompilerIdC/a.out"
|
||||
|
||||
Compiling the CXX compiler identification source file "CMakeCXXCompilerId.cpp" succeeded.
|
||||
Compiler: /usr/bin/c++
|
||||
Build flags:
|
||||
Id flags:
|
||||
|
||||
The output was:
|
||||
0
|
||||
|
||||
|
||||
Compilation of the CXX compiler identification source "CMakeCXXCompilerId.cpp" produced "a.out"
|
||||
|
||||
The CXX compiler identification is GNU, found in "/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/3.22.1/CompilerIdCXX/a.out"
|
||||
|
||||
Detecting C compiler ABI info compiled with the following output:
|
||||
Change Dir: /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp
|
||||
|
||||
Run Build Command(s):/usr/bin/gmake -f Makefile cmTC_706ba/fast && /usr/bin/gmake -f CMakeFiles/cmTC_706ba.dir/build.make CMakeFiles/cmTC_706ba.dir/build
|
||||
gmake[1]: Entering directory '/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp'
|
||||
Building C object CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.o
|
||||
/usr/bin/cc -v -o CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-3.22/Modules/CMakeCCompilerABI.c
|
||||
Using built-in specs.
|
||||
COLLECT_GCC=/usr/bin/cc
|
||||
Target: aarch64-linux-gnu
|
||||
Configured with: ../src/configure -v --with-pkgversion='Ubuntu 11.4.0-1ubuntu1~22.04.3' --with-bugurl=file:///usr/share/doc/gcc-11/README.Bugs --enable-languages=c,ada,c++,go,d,fortran,objc,obj-c++,m2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-11 --program-prefix=aarch64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-bootstrap --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-libquadmath --disable-libquadmath-support --enable-plugin --enable-default-pie --with-system-zlib --enable-libphobos-checking=release --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --enable-fix-cortex-a53-843419 --disable-werror --enable-checking=release --build=aarch64-linux-gnu --host=aarch64-linux-gnu --target=aarch64-linux-gnu --with-build-config=bootstrap-lto-lean --enable-link-serialization=4
|
||||
Thread model: posix
|
||||
Supported LTO compression algorithms: zlib zstd
|
||||
gcc version 11.4.0 (Ubuntu 11.4.0-1ubuntu1~22.04.3)
|
||||
COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.o' '-c' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'CMakeFiles/cmTC_706ba.dir/'
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/cc1 -quiet -v -imultiarch aarch64-linux-gnu /usr/share/cmake-3.22/Modules/CMakeCCompilerABI.c -quiet -dumpdir CMakeFiles/cmTC_706ba.dir/ -dumpbase CMakeCCompilerABI.c.c -dumpbase-ext .c -mlittle-endian -mabi=lp64 -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -o /tmp/ccx1Gkh8.s
|
||||
GNU C17 (Ubuntu 11.4.0-1ubuntu1~22.04.3) version 11.4.0 (aarch64-linux-gnu)
|
||||
compiled by GNU C version 11.4.0, GMP version 6.2.1, MPFR version 4.1.0, MPC version 1.2.1, isl version isl-0.24-GMP
|
||||
|
||||
GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072
|
||||
ignoring nonexistent directory "/usr/local/include/aarch64-linux-gnu"
|
||||
ignoring nonexistent directory "/usr/lib/gcc/aarch64-linux-gnu/11/include-fixed"
|
||||
ignoring nonexistent directory "/usr/lib/gcc/aarch64-linux-gnu/11/../../../../aarch64-linux-gnu/include"
|
||||
#include "..." search starts here:
|
||||
#include <...> search starts here:
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/include
|
||||
/usr/local/include
|
||||
/usr/include/aarch64-linux-gnu
|
||||
/usr/include
|
||||
End of search list.
|
||||
GNU C17 (Ubuntu 11.4.0-1ubuntu1~22.04.3) version 11.4.0 (aarch64-linux-gnu)
|
||||
compiled by GNU C version 11.4.0, GMP version 6.2.1, MPFR version 4.1.0, MPC version 1.2.1, isl version isl-0.24-GMP
|
||||
|
||||
GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072
|
||||
Compiler executable checksum: 44447769998af3517ef276c2696d65ed
|
||||
COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.o' '-c' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'CMakeFiles/cmTC_706ba.dir/'
|
||||
as -v -EL -mabi=lp64 -o CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.o /tmp/ccx1Gkh8.s
|
||||
GNU assembler version 2.38 (aarch64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.38
|
||||
COMPILER_PATH=/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/:/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/
|
||||
LIBRARY_PATH=/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib/:/lib/aarch64-linux-gnu/:/lib/../lib/:/usr/lib/aarch64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../:/lib/:/usr/lib/
|
||||
COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.o' '-c' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.'
|
||||
Linking C executable cmTC_706ba
|
||||
/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_706ba.dir/link.txt --verbose=1
|
||||
/usr/bin/cc -v CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.o -o cmTC_706ba
|
||||
Using built-in specs.
|
||||
COLLECT_GCC=/usr/bin/cc
|
||||
COLLECT_LTO_WRAPPER=/usr/lib/gcc/aarch64-linux-gnu/11/lto-wrapper
|
||||
Target: aarch64-linux-gnu
|
||||
Configured with: ../src/configure -v --with-pkgversion='Ubuntu 11.4.0-1ubuntu1~22.04.3' --with-bugurl=file:///usr/share/doc/gcc-11/README.Bugs --enable-languages=c,ada,c++,go,d,fortran,objc,obj-c++,m2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-11 --program-prefix=aarch64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-bootstrap --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-libquadmath --disable-libquadmath-support --enable-plugin --enable-default-pie --with-system-zlib --enable-libphobos-checking=release --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --enable-fix-cortex-a53-843419 --disable-werror --enable-checking=release --build=aarch64-linux-gnu --host=aarch64-linux-gnu --target=aarch64-linux-gnu --with-build-config=bootstrap-lto-lean --enable-link-serialization=4
|
||||
Thread model: posix
|
||||
Supported LTO compression algorithms: zlib zstd
|
||||
gcc version 11.4.0 (Ubuntu 11.4.0-1ubuntu1~22.04.3)
|
||||
COMPILER_PATH=/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/:/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/
|
||||
LIBRARY_PATH=/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib/:/lib/aarch64-linux-gnu/:/lib/../lib/:/usr/lib/aarch64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../:/lib/:/usr/lib/
|
||||
COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_706ba' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'cmTC_706ba.'
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/collect2 -plugin /usr/lib/gcc/aarch64-linux-gnu/11/liblto_plugin.so -plugin-opt=/usr/lib/gcc/aarch64-linux-gnu/11/lto-wrapper -plugin-opt=-fresolution=/tmp/cc25pahp.res -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s --build-id --eh-frame-hdr --hash-style=gnu --as-needed -dynamic-linker /lib/ld-linux-aarch64.so.1 -X -EL -maarch64linux --fix-cortex-a53-843419 -pie -z now -z relro -o cmTC_706ba /usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/Scrt1.o /usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crti.o /usr/lib/gcc/aarch64-linux-gnu/11/crtbeginS.o -L/usr/lib/gcc/aarch64-linux-gnu/11 -L/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu -L/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib -L/lib/aarch64-linux-gnu -L/lib/../lib -L/usr/lib/aarch64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/aarch64-linux-gnu/11/../../.. CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.o -lgcc --push-state --as-needed -lgcc_s --pop-state -lc -lgcc --push-state --as-needed -lgcc_s --pop-state /usr/lib/gcc/aarch64-linux-gnu/11/crtendS.o /usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crtn.o
|
||||
COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_706ba' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'cmTC_706ba.'
|
||||
gmake[1]: Leaving directory '/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp'
|
||||
|
||||
|
||||
|
||||
Parsed C implicit include dir info from above output: rv=done
|
||||
found start of include info
|
||||
found start of implicit include info
|
||||
add: [/usr/lib/gcc/aarch64-linux-gnu/11/include]
|
||||
add: [/usr/local/include]
|
||||
add: [/usr/include/aarch64-linux-gnu]
|
||||
add: [/usr/include]
|
||||
end of search list found
|
||||
collapse include dir [/usr/lib/gcc/aarch64-linux-gnu/11/include] ==> [/usr/lib/gcc/aarch64-linux-gnu/11/include]
|
||||
collapse include dir [/usr/local/include] ==> [/usr/local/include]
|
||||
collapse include dir [/usr/include/aarch64-linux-gnu] ==> [/usr/include/aarch64-linux-gnu]
|
||||
collapse include dir [/usr/include] ==> [/usr/include]
|
||||
implicit include dirs: [/usr/lib/gcc/aarch64-linux-gnu/11/include;/usr/local/include;/usr/include/aarch64-linux-gnu;/usr/include]
|
||||
|
||||
|
||||
Parsed C implicit link information from above output:
|
||||
link line regex: [^( *|.*[/\])(ld|CMAKE_LINK_STARTFILE-NOTFOUND|([^/\]+-)?ld|collect2)[^/\]*( |$)]
|
||||
ignore line: [Change Dir: /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp]
|
||||
ignore line: []
|
||||
ignore line: [Run Build Command(s):/usr/bin/gmake -f Makefile cmTC_706ba/fast && /usr/bin/gmake -f CMakeFiles/cmTC_706ba.dir/build.make CMakeFiles/cmTC_706ba.dir/build]
|
||||
ignore line: [gmake[1]: Entering directory '/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp']
|
||||
ignore line: [Building C object CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.o]
|
||||
ignore line: [/usr/bin/cc -v -o CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-3.22/Modules/CMakeCCompilerABI.c]
|
||||
ignore line: [Using built-in specs.]
|
||||
ignore line: [COLLECT_GCC=/usr/bin/cc]
|
||||
ignore line: [Target: aarch64-linux-gnu]
|
||||
ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 11.4.0-1ubuntu1~22.04.3' --with-bugurl=file:///usr/share/doc/gcc-11/README.Bugs --enable-languages=c ada c++ go d fortran objc obj-c++ m2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-11 --program-prefix=aarch64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-bootstrap --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-libquadmath --disable-libquadmath-support --enable-plugin --enable-default-pie --with-system-zlib --enable-libphobos-checking=release --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --enable-fix-cortex-a53-843419 --disable-werror --enable-checking=release --build=aarch64-linux-gnu --host=aarch64-linux-gnu --target=aarch64-linux-gnu --with-build-config=bootstrap-lto-lean --enable-link-serialization=4]
|
||||
ignore line: [Thread model: posix]
|
||||
ignore line: [Supported LTO compression algorithms: zlib zstd]
|
||||
ignore line: [gcc version 11.4.0 (Ubuntu 11.4.0-1ubuntu1~22.04.3) ]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.o' '-c' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'CMakeFiles/cmTC_706ba.dir/']
|
||||
ignore line: [ /usr/lib/gcc/aarch64-linux-gnu/11/cc1 -quiet -v -imultiarch aarch64-linux-gnu /usr/share/cmake-3.22/Modules/CMakeCCompilerABI.c -quiet -dumpdir CMakeFiles/cmTC_706ba.dir/ -dumpbase CMakeCCompilerABI.c.c -dumpbase-ext .c -mlittle-endian -mabi=lp64 -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -o /tmp/ccx1Gkh8.s]
|
||||
ignore line: [GNU C17 (Ubuntu 11.4.0-1ubuntu1~22.04.3) version 11.4.0 (aarch64-linux-gnu)]
|
||||
ignore line: [ compiled by GNU C version 11.4.0 GMP version 6.2.1 MPFR version 4.1.0 MPC version 1.2.1 isl version isl-0.24-GMP]
|
||||
ignore line: []
|
||||
ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072]
|
||||
ignore line: [ignoring nonexistent directory "/usr/local/include/aarch64-linux-gnu"]
|
||||
ignore line: [ignoring nonexistent directory "/usr/lib/gcc/aarch64-linux-gnu/11/include-fixed"]
|
||||
ignore line: [ignoring nonexistent directory "/usr/lib/gcc/aarch64-linux-gnu/11/../../../../aarch64-linux-gnu/include"]
|
||||
ignore line: [#include "..." search starts here:]
|
||||
ignore line: [#include <...> search starts here:]
|
||||
ignore line: [ /usr/lib/gcc/aarch64-linux-gnu/11/include]
|
||||
ignore line: [ /usr/local/include]
|
||||
ignore line: [ /usr/include/aarch64-linux-gnu]
|
||||
ignore line: [ /usr/include]
|
||||
ignore line: [End of search list.]
|
||||
ignore line: [GNU C17 (Ubuntu 11.4.0-1ubuntu1~22.04.3) version 11.4.0 (aarch64-linux-gnu)]
|
||||
ignore line: [ compiled by GNU C version 11.4.0 GMP version 6.2.1 MPFR version 4.1.0 MPC version 1.2.1 isl version isl-0.24-GMP]
|
||||
ignore line: []
|
||||
ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072]
|
||||
ignore line: [Compiler executable checksum: 44447769998af3517ef276c2696d65ed]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.o' '-c' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'CMakeFiles/cmTC_706ba.dir/']
|
||||
ignore line: [ as -v -EL -mabi=lp64 -o CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.o /tmp/ccx1Gkh8.s]
|
||||
ignore line: [GNU assembler version 2.38 (aarch64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.38]
|
||||
ignore line: [COMPILER_PATH=/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/:/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/]
|
||||
ignore line: [LIBRARY_PATH=/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib/:/lib/aarch64-linux-gnu/:/lib/../lib/:/usr/lib/aarch64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../:/lib/:/usr/lib/]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.o' '-c' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.']
|
||||
ignore line: [Linking C executable cmTC_706ba]
|
||||
ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_706ba.dir/link.txt --verbose=1]
|
||||
ignore line: [/usr/bin/cc -v CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.o -o cmTC_706ba ]
|
||||
ignore line: [Using built-in specs.]
|
||||
ignore line: [COLLECT_GCC=/usr/bin/cc]
|
||||
ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/aarch64-linux-gnu/11/lto-wrapper]
|
||||
ignore line: [Target: aarch64-linux-gnu]
|
||||
ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 11.4.0-1ubuntu1~22.04.3' --with-bugurl=file:///usr/share/doc/gcc-11/README.Bugs --enable-languages=c ada c++ go d fortran objc obj-c++ m2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-11 --program-prefix=aarch64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-bootstrap --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-libquadmath --disable-libquadmath-support --enable-plugin --enable-default-pie --with-system-zlib --enable-libphobos-checking=release --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --enable-fix-cortex-a53-843419 --disable-werror --enable-checking=release --build=aarch64-linux-gnu --host=aarch64-linux-gnu --target=aarch64-linux-gnu --with-build-config=bootstrap-lto-lean --enable-link-serialization=4]
|
||||
ignore line: [Thread model: posix]
|
||||
ignore line: [Supported LTO compression algorithms: zlib zstd]
|
||||
ignore line: [gcc version 11.4.0 (Ubuntu 11.4.0-1ubuntu1~22.04.3) ]
|
||||
ignore line: [COMPILER_PATH=/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/:/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/]
|
||||
ignore line: [LIBRARY_PATH=/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib/:/lib/aarch64-linux-gnu/:/lib/../lib/:/usr/lib/aarch64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../:/lib/:/usr/lib/]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_706ba' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'cmTC_706ba.']
|
||||
link line: [ /usr/lib/gcc/aarch64-linux-gnu/11/collect2 -plugin /usr/lib/gcc/aarch64-linux-gnu/11/liblto_plugin.so -plugin-opt=/usr/lib/gcc/aarch64-linux-gnu/11/lto-wrapper -plugin-opt=-fresolution=/tmp/cc25pahp.res -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s --build-id --eh-frame-hdr --hash-style=gnu --as-needed -dynamic-linker /lib/ld-linux-aarch64.so.1 -X -EL -maarch64linux --fix-cortex-a53-843419 -pie -z now -z relro -o cmTC_706ba /usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/Scrt1.o /usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crti.o /usr/lib/gcc/aarch64-linux-gnu/11/crtbeginS.o -L/usr/lib/gcc/aarch64-linux-gnu/11 -L/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu -L/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib -L/lib/aarch64-linux-gnu -L/lib/../lib -L/usr/lib/aarch64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/aarch64-linux-gnu/11/../../.. CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.o -lgcc --push-state --as-needed -lgcc_s --pop-state -lc -lgcc --push-state --as-needed -lgcc_s --pop-state /usr/lib/gcc/aarch64-linux-gnu/11/crtendS.o /usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crtn.o]
|
||||
arg [/usr/lib/gcc/aarch64-linux-gnu/11/collect2] ==> ignore
|
||||
arg [-plugin] ==> ignore
|
||||
arg [/usr/lib/gcc/aarch64-linux-gnu/11/liblto_plugin.so] ==> ignore
|
||||
arg [-plugin-opt=/usr/lib/gcc/aarch64-linux-gnu/11/lto-wrapper] ==> ignore
|
||||
arg [-plugin-opt=-fresolution=/tmp/cc25pahp.res] ==> ignore
|
||||
arg [-plugin-opt=-pass-through=-lgcc] ==> ignore
|
||||
arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore
|
||||
arg [-plugin-opt=-pass-through=-lc] ==> ignore
|
||||
arg [-plugin-opt=-pass-through=-lgcc] ==> ignore
|
||||
arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore
|
||||
arg [--build-id] ==> ignore
|
||||
arg [--eh-frame-hdr] ==> ignore
|
||||
arg [--hash-style=gnu] ==> ignore
|
||||
arg [--as-needed] ==> ignore
|
||||
arg [-dynamic-linker] ==> ignore
|
||||
arg [/lib/ld-linux-aarch64.so.1] ==> ignore
|
||||
arg [-X] ==> ignore
|
||||
arg [-EL] ==> ignore
|
||||
arg [-maarch64linux] ==> ignore
|
||||
arg [--fix-cortex-a53-843419] ==> ignore
|
||||
arg [-pie] ==> ignore
|
||||
arg [-znow] ==> ignore
|
||||
arg [-zrelro] ==> ignore
|
||||
arg [-o] ==> ignore
|
||||
arg [cmTC_706ba] ==> ignore
|
||||
arg [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/Scrt1.o] ==> obj [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/Scrt1.o]
|
||||
arg [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crti.o] ==> obj [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crti.o]
|
||||
arg [/usr/lib/gcc/aarch64-linux-gnu/11/crtbeginS.o] ==> obj [/usr/lib/gcc/aarch64-linux-gnu/11/crtbeginS.o]
|
||||
arg [-L/usr/lib/gcc/aarch64-linux-gnu/11] ==> dir [/usr/lib/gcc/aarch64-linux-gnu/11]
|
||||
arg [-L/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu] ==> dir [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu]
|
||||
arg [-L/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib] ==> dir [/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib]
|
||||
arg [-L/lib/aarch64-linux-gnu] ==> dir [/lib/aarch64-linux-gnu]
|
||||
arg [-L/lib/../lib] ==> dir [/lib/../lib]
|
||||
arg [-L/usr/lib/aarch64-linux-gnu] ==> dir [/usr/lib/aarch64-linux-gnu]
|
||||
arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib]
|
||||
arg [-L/usr/lib/gcc/aarch64-linux-gnu/11/../../..] ==> dir [/usr/lib/gcc/aarch64-linux-gnu/11/../../..]
|
||||
arg [CMakeFiles/cmTC_706ba.dir/CMakeCCompilerABI.c.o] ==> ignore
|
||||
arg [-lgcc] ==> lib [gcc]
|
||||
arg [--push-state] ==> ignore
|
||||
arg [--as-needed] ==> ignore
|
||||
arg [-lgcc_s] ==> lib [gcc_s]
|
||||
arg [--pop-state] ==> ignore
|
||||
arg [-lc] ==> lib [c]
|
||||
arg [-lgcc] ==> lib [gcc]
|
||||
arg [--push-state] ==> ignore
|
||||
arg [--as-needed] ==> ignore
|
||||
arg [-lgcc_s] ==> lib [gcc_s]
|
||||
arg [--pop-state] ==> ignore
|
||||
arg [/usr/lib/gcc/aarch64-linux-gnu/11/crtendS.o] ==> obj [/usr/lib/gcc/aarch64-linux-gnu/11/crtendS.o]
|
||||
arg [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crtn.o] ==> obj [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crtn.o]
|
||||
collapse obj [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/Scrt1.o] ==> [/usr/lib/aarch64-linux-gnu/Scrt1.o]
|
||||
collapse obj [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crti.o] ==> [/usr/lib/aarch64-linux-gnu/crti.o]
|
||||
collapse obj [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crtn.o] ==> [/usr/lib/aarch64-linux-gnu/crtn.o]
|
||||
collapse library dir [/usr/lib/gcc/aarch64-linux-gnu/11] ==> [/usr/lib/gcc/aarch64-linux-gnu/11]
|
||||
collapse library dir [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu] ==> [/usr/lib/aarch64-linux-gnu]
|
||||
collapse library dir [/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib] ==> [/usr/lib]
|
||||
collapse library dir [/lib/aarch64-linux-gnu] ==> [/lib/aarch64-linux-gnu]
|
||||
collapse library dir [/lib/../lib] ==> [/lib]
|
||||
collapse library dir [/usr/lib/aarch64-linux-gnu] ==> [/usr/lib/aarch64-linux-gnu]
|
||||
collapse library dir [/usr/lib/../lib] ==> [/usr/lib]
|
||||
collapse library dir [/usr/lib/gcc/aarch64-linux-gnu/11/../../..] ==> [/usr/lib]
|
||||
implicit libs: [gcc;gcc_s;c;gcc;gcc_s]
|
||||
implicit objs: [/usr/lib/aarch64-linux-gnu/Scrt1.o;/usr/lib/aarch64-linux-gnu/crti.o;/usr/lib/gcc/aarch64-linux-gnu/11/crtbeginS.o;/usr/lib/gcc/aarch64-linux-gnu/11/crtendS.o;/usr/lib/aarch64-linux-gnu/crtn.o]
|
||||
implicit dirs: [/usr/lib/gcc/aarch64-linux-gnu/11;/usr/lib/aarch64-linux-gnu;/usr/lib;/lib/aarch64-linux-gnu;/lib]
|
||||
implicit fwks: []
|
||||
|
||||
|
||||
Detecting CXX compiler ABI info compiled with the following output:
|
||||
Change Dir: /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp
|
||||
|
||||
Run Build Command(s):/usr/bin/gmake -f Makefile cmTC_42c38/fast && /usr/bin/gmake -f CMakeFiles/cmTC_42c38.dir/build.make CMakeFiles/cmTC_42c38.dir/build
|
||||
gmake[1]: Entering directory '/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp'
|
||||
Building CXX object CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.o
|
||||
/usr/bin/c++ -v -o CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-3.22/Modules/CMakeCXXCompilerABI.cpp
|
||||
Using built-in specs.
|
||||
COLLECT_GCC=/usr/bin/c++
|
||||
Target: aarch64-linux-gnu
|
||||
Configured with: ../src/configure -v --with-pkgversion='Ubuntu 11.4.0-1ubuntu1~22.04.3' --with-bugurl=file:///usr/share/doc/gcc-11/README.Bugs --enable-languages=c,ada,c++,go,d,fortran,objc,obj-c++,m2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-11 --program-prefix=aarch64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-bootstrap --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-libquadmath --disable-libquadmath-support --enable-plugin --enable-default-pie --with-system-zlib --enable-libphobos-checking=release --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --enable-fix-cortex-a53-843419 --disable-werror --enable-checking=release --build=aarch64-linux-gnu --host=aarch64-linux-gnu --target=aarch64-linux-gnu --with-build-config=bootstrap-lto-lean --enable-link-serialization=4
|
||||
Thread model: posix
|
||||
Supported LTO compression algorithms: zlib zstd
|
||||
gcc version 11.4.0 (Ubuntu 11.4.0-1ubuntu1~22.04.3)
|
||||
COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'CMakeFiles/cmTC_42c38.dir/'
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/cc1plus -quiet -v -imultiarch aarch64-linux-gnu -D_GNU_SOURCE /usr/share/cmake-3.22/Modules/CMakeCXXCompilerABI.cpp -quiet -dumpdir CMakeFiles/cmTC_42c38.dir/ -dumpbase CMakeCXXCompilerABI.cpp.cpp -dumpbase-ext .cpp -mlittle-endian -mabi=lp64 -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -o /tmp/cceAI70l.s
|
||||
GNU C++17 (Ubuntu 11.4.0-1ubuntu1~22.04.3) version 11.4.0 (aarch64-linux-gnu)
|
||||
compiled by GNU C version 11.4.0, GMP version 6.2.1, MPFR version 4.1.0, MPC version 1.2.1, isl version isl-0.24-GMP
|
||||
|
||||
GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072
|
||||
ignoring duplicate directory "/usr/include/aarch64-linux-gnu/c++/11"
|
||||
ignoring nonexistent directory "/usr/local/include/aarch64-linux-gnu"
|
||||
ignoring nonexistent directory "/usr/lib/gcc/aarch64-linux-gnu/11/include-fixed"
|
||||
ignoring nonexistent directory "/usr/lib/gcc/aarch64-linux-gnu/11/../../../../aarch64-linux-gnu/include"
|
||||
#include "..." search starts here:
|
||||
#include <...> search starts here:
|
||||
/usr/include/c++/11
|
||||
/usr/include/aarch64-linux-gnu/c++/11
|
||||
/usr/include/c++/11/backward
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/include
|
||||
/usr/local/include
|
||||
/usr/include/aarch64-linux-gnu
|
||||
/usr/include
|
||||
End of search list.
|
||||
GNU C++17 (Ubuntu 11.4.0-1ubuntu1~22.04.3) version 11.4.0 (aarch64-linux-gnu)
|
||||
compiled by GNU C version 11.4.0, GMP version 6.2.1, MPFR version 4.1.0, MPC version 1.2.1, isl version isl-0.24-GMP
|
||||
|
||||
GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072
|
||||
Compiler executable checksum: 1ec2e7097ef542eddc6fe6fb48e7bad4
|
||||
COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'CMakeFiles/cmTC_42c38.dir/'
|
||||
as -v -EL -mabi=lp64 -o CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.o /tmp/cceAI70l.s
|
||||
GNU assembler version 2.38 (aarch64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.38
|
||||
COMPILER_PATH=/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/:/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/
|
||||
LIBRARY_PATH=/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib/:/lib/aarch64-linux-gnu/:/lib/../lib/:/usr/lib/aarch64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../:/lib/:/usr/lib/
|
||||
COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.'
|
||||
Linking CXX executable cmTC_42c38
|
||||
/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_42c38.dir/link.txt --verbose=1
|
||||
/usr/bin/c++ -v CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.o -o cmTC_42c38
|
||||
Using built-in specs.
|
||||
COLLECT_GCC=/usr/bin/c++
|
||||
COLLECT_LTO_WRAPPER=/usr/lib/gcc/aarch64-linux-gnu/11/lto-wrapper
|
||||
Target: aarch64-linux-gnu
|
||||
Configured with: ../src/configure -v --with-pkgversion='Ubuntu 11.4.0-1ubuntu1~22.04.3' --with-bugurl=file:///usr/share/doc/gcc-11/README.Bugs --enable-languages=c,ada,c++,go,d,fortran,objc,obj-c++,m2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-11 --program-prefix=aarch64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-bootstrap --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-libquadmath --disable-libquadmath-support --enable-plugin --enable-default-pie --with-system-zlib --enable-libphobos-checking=release --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --enable-fix-cortex-a53-843419 --disable-werror --enable-checking=release --build=aarch64-linux-gnu --host=aarch64-linux-gnu --target=aarch64-linux-gnu --with-build-config=bootstrap-lto-lean --enable-link-serialization=4
|
||||
Thread model: posix
|
||||
Supported LTO compression algorithms: zlib zstd
|
||||
gcc version 11.4.0 (Ubuntu 11.4.0-1ubuntu1~22.04.3)
|
||||
COMPILER_PATH=/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/:/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/
|
||||
LIBRARY_PATH=/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib/:/lib/aarch64-linux-gnu/:/lib/../lib/:/usr/lib/aarch64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../:/lib/:/usr/lib/
|
||||
COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_42c38' '-shared-libgcc' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'cmTC_42c38.'
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/collect2 -plugin /usr/lib/gcc/aarch64-linux-gnu/11/liblto_plugin.so -plugin-opt=/usr/lib/gcc/aarch64-linux-gnu/11/lto-wrapper -plugin-opt=-fresolution=/tmp/ccb6eoYN.res -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc --build-id --eh-frame-hdr --hash-style=gnu --as-needed -dynamic-linker /lib/ld-linux-aarch64.so.1 -X -EL -maarch64linux --fix-cortex-a53-843419 -pie -z now -z relro -o cmTC_42c38 /usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/Scrt1.o /usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crti.o /usr/lib/gcc/aarch64-linux-gnu/11/crtbeginS.o -L/usr/lib/gcc/aarch64-linux-gnu/11 -L/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu -L/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib -L/lib/aarch64-linux-gnu -L/lib/../lib -L/usr/lib/aarch64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/aarch64-linux-gnu/11/../../.. CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/aarch64-linux-gnu/11/crtendS.o /usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crtn.o
|
||||
COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_42c38' '-shared-libgcc' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'cmTC_42c38.'
|
||||
gmake[1]: Leaving directory '/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp'
|
||||
|
||||
|
||||
|
||||
Parsed CXX implicit include dir info from above output: rv=done
|
||||
found start of include info
|
||||
found start of implicit include info
|
||||
add: [/usr/include/c++/11]
|
||||
add: [/usr/include/aarch64-linux-gnu/c++/11]
|
||||
add: [/usr/include/c++/11/backward]
|
||||
add: [/usr/lib/gcc/aarch64-linux-gnu/11/include]
|
||||
add: [/usr/local/include]
|
||||
add: [/usr/include/aarch64-linux-gnu]
|
||||
add: [/usr/include]
|
||||
end of search list found
|
||||
collapse include dir [/usr/include/c++/11] ==> [/usr/include/c++/11]
|
||||
collapse include dir [/usr/include/aarch64-linux-gnu/c++/11] ==> [/usr/include/aarch64-linux-gnu/c++/11]
|
||||
collapse include dir [/usr/include/c++/11/backward] ==> [/usr/include/c++/11/backward]
|
||||
collapse include dir [/usr/lib/gcc/aarch64-linux-gnu/11/include] ==> [/usr/lib/gcc/aarch64-linux-gnu/11/include]
|
||||
collapse include dir [/usr/local/include] ==> [/usr/local/include]
|
||||
collapse include dir [/usr/include/aarch64-linux-gnu] ==> [/usr/include/aarch64-linux-gnu]
|
||||
collapse include dir [/usr/include] ==> [/usr/include]
|
||||
implicit include dirs: [/usr/include/c++/11;/usr/include/aarch64-linux-gnu/c++/11;/usr/include/c++/11/backward;/usr/lib/gcc/aarch64-linux-gnu/11/include;/usr/local/include;/usr/include/aarch64-linux-gnu;/usr/include]
|
||||
|
||||
|
||||
Parsed CXX implicit link information from above output:
|
||||
link line regex: [^( *|.*[/\])(ld|CMAKE_LINK_STARTFILE-NOTFOUND|([^/\]+-)?ld|collect2)[^/\]*( |$)]
|
||||
ignore line: [Change Dir: /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp]
|
||||
ignore line: []
|
||||
ignore line: [Run Build Command(s):/usr/bin/gmake -f Makefile cmTC_42c38/fast && /usr/bin/gmake -f CMakeFiles/cmTC_42c38.dir/build.make CMakeFiles/cmTC_42c38.dir/build]
|
||||
ignore line: [gmake[1]: Entering directory '/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp']
|
||||
ignore line: [Building CXX object CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.o]
|
||||
ignore line: [/usr/bin/c++ -v -o CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-3.22/Modules/CMakeCXXCompilerABI.cpp]
|
||||
ignore line: [Using built-in specs.]
|
||||
ignore line: [COLLECT_GCC=/usr/bin/c++]
|
||||
ignore line: [Target: aarch64-linux-gnu]
|
||||
ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 11.4.0-1ubuntu1~22.04.3' --with-bugurl=file:///usr/share/doc/gcc-11/README.Bugs --enable-languages=c ada c++ go d fortran objc obj-c++ m2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-11 --program-prefix=aarch64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-bootstrap --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-libquadmath --disable-libquadmath-support --enable-plugin --enable-default-pie --with-system-zlib --enable-libphobos-checking=release --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --enable-fix-cortex-a53-843419 --disable-werror --enable-checking=release --build=aarch64-linux-gnu --host=aarch64-linux-gnu --target=aarch64-linux-gnu --with-build-config=bootstrap-lto-lean --enable-link-serialization=4]
|
||||
ignore line: [Thread model: posix]
|
||||
ignore line: [Supported LTO compression algorithms: zlib zstd]
|
||||
ignore line: [gcc version 11.4.0 (Ubuntu 11.4.0-1ubuntu1~22.04.3) ]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'CMakeFiles/cmTC_42c38.dir/']
|
||||
ignore line: [ /usr/lib/gcc/aarch64-linux-gnu/11/cc1plus -quiet -v -imultiarch aarch64-linux-gnu -D_GNU_SOURCE /usr/share/cmake-3.22/Modules/CMakeCXXCompilerABI.cpp -quiet -dumpdir CMakeFiles/cmTC_42c38.dir/ -dumpbase CMakeCXXCompilerABI.cpp.cpp -dumpbase-ext .cpp -mlittle-endian -mabi=lp64 -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -o /tmp/cceAI70l.s]
|
||||
ignore line: [GNU C++17 (Ubuntu 11.4.0-1ubuntu1~22.04.3) version 11.4.0 (aarch64-linux-gnu)]
|
||||
ignore line: [ compiled by GNU C version 11.4.0 GMP version 6.2.1 MPFR version 4.1.0 MPC version 1.2.1 isl version isl-0.24-GMP]
|
||||
ignore line: []
|
||||
ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072]
|
||||
ignore line: [ignoring duplicate directory "/usr/include/aarch64-linux-gnu/c++/11"]
|
||||
ignore line: [ignoring nonexistent directory "/usr/local/include/aarch64-linux-gnu"]
|
||||
ignore line: [ignoring nonexistent directory "/usr/lib/gcc/aarch64-linux-gnu/11/include-fixed"]
|
||||
ignore line: [ignoring nonexistent directory "/usr/lib/gcc/aarch64-linux-gnu/11/../../../../aarch64-linux-gnu/include"]
|
||||
ignore line: [#include "..." search starts here:]
|
||||
ignore line: [#include <...> search starts here:]
|
||||
ignore line: [ /usr/include/c++/11]
|
||||
ignore line: [ /usr/include/aarch64-linux-gnu/c++/11]
|
||||
ignore line: [ /usr/include/c++/11/backward]
|
||||
ignore line: [ /usr/lib/gcc/aarch64-linux-gnu/11/include]
|
||||
ignore line: [ /usr/local/include]
|
||||
ignore line: [ /usr/include/aarch64-linux-gnu]
|
||||
ignore line: [ /usr/include]
|
||||
ignore line: [End of search list.]
|
||||
ignore line: [GNU C++17 (Ubuntu 11.4.0-1ubuntu1~22.04.3) version 11.4.0 (aarch64-linux-gnu)]
|
||||
ignore line: [ compiled by GNU C version 11.4.0 GMP version 6.2.1 MPFR version 4.1.0 MPC version 1.2.1 isl version isl-0.24-GMP]
|
||||
ignore line: []
|
||||
ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072]
|
||||
ignore line: [Compiler executable checksum: 1ec2e7097ef542eddc6fe6fb48e7bad4]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'CMakeFiles/cmTC_42c38.dir/']
|
||||
ignore line: [ as -v -EL -mabi=lp64 -o CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.o /tmp/cceAI70l.s]
|
||||
ignore line: [GNU assembler version 2.38 (aarch64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.38]
|
||||
ignore line: [COMPILER_PATH=/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/:/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/]
|
||||
ignore line: [LIBRARY_PATH=/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib/:/lib/aarch64-linux-gnu/:/lib/../lib/:/usr/lib/aarch64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../:/lib/:/usr/lib/]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.']
|
||||
ignore line: [Linking CXX executable cmTC_42c38]
|
||||
ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_42c38.dir/link.txt --verbose=1]
|
||||
ignore line: [/usr/bin/c++ -v CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.o -o cmTC_42c38 ]
|
||||
ignore line: [Using built-in specs.]
|
||||
ignore line: [COLLECT_GCC=/usr/bin/c++]
|
||||
ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/aarch64-linux-gnu/11/lto-wrapper]
|
||||
ignore line: [Target: aarch64-linux-gnu]
|
||||
ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 11.4.0-1ubuntu1~22.04.3' --with-bugurl=file:///usr/share/doc/gcc-11/README.Bugs --enable-languages=c ada c++ go d fortran objc obj-c++ m2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-11 --program-prefix=aarch64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-bootstrap --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-libquadmath --disable-libquadmath-support --enable-plugin --enable-default-pie --with-system-zlib --enable-libphobos-checking=release --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --enable-fix-cortex-a53-843419 --disable-werror --enable-checking=release --build=aarch64-linux-gnu --host=aarch64-linux-gnu --target=aarch64-linux-gnu --with-build-config=bootstrap-lto-lean --enable-link-serialization=4]
|
||||
ignore line: [Thread model: posix]
|
||||
ignore line: [Supported LTO compression algorithms: zlib zstd]
|
||||
ignore line: [gcc version 11.4.0 (Ubuntu 11.4.0-1ubuntu1~22.04.3) ]
|
||||
ignore line: [COMPILER_PATH=/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/:/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/]
|
||||
ignore line: [LIBRARY_PATH=/usr/lib/gcc/aarch64-linux-gnu/11/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib/:/lib/aarch64-linux-gnu/:/lib/../lib/:/usr/lib/aarch64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/aarch64-linux-gnu/11/../../../:/lib/:/usr/lib/]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_42c38' '-shared-libgcc' '-mlittle-endian' '-mabi=lp64' '-dumpdir' 'cmTC_42c38.']
|
||||
link line: [ /usr/lib/gcc/aarch64-linux-gnu/11/collect2 -plugin /usr/lib/gcc/aarch64-linux-gnu/11/liblto_plugin.so -plugin-opt=/usr/lib/gcc/aarch64-linux-gnu/11/lto-wrapper -plugin-opt=-fresolution=/tmp/ccb6eoYN.res -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc --build-id --eh-frame-hdr --hash-style=gnu --as-needed -dynamic-linker /lib/ld-linux-aarch64.so.1 -X -EL -maarch64linux --fix-cortex-a53-843419 -pie -z now -z relro -o cmTC_42c38 /usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/Scrt1.o /usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crti.o /usr/lib/gcc/aarch64-linux-gnu/11/crtbeginS.o -L/usr/lib/gcc/aarch64-linux-gnu/11 -L/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu -L/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib -L/lib/aarch64-linux-gnu -L/lib/../lib -L/usr/lib/aarch64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/aarch64-linux-gnu/11/../../.. CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/aarch64-linux-gnu/11/crtendS.o /usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crtn.o]
|
||||
arg [/usr/lib/gcc/aarch64-linux-gnu/11/collect2] ==> ignore
|
||||
arg [-plugin] ==> ignore
|
||||
arg [/usr/lib/gcc/aarch64-linux-gnu/11/liblto_plugin.so] ==> ignore
|
||||
arg [-plugin-opt=/usr/lib/gcc/aarch64-linux-gnu/11/lto-wrapper] ==> ignore
|
||||
arg [-plugin-opt=-fresolution=/tmp/ccb6eoYN.res] ==> ignore
|
||||
arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore
|
||||
arg [-plugin-opt=-pass-through=-lgcc] ==> ignore
|
||||
arg [-plugin-opt=-pass-through=-lc] ==> ignore
|
||||
arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore
|
||||
arg [-plugin-opt=-pass-through=-lgcc] ==> ignore
|
||||
arg [--build-id] ==> ignore
|
||||
arg [--eh-frame-hdr] ==> ignore
|
||||
arg [--hash-style=gnu] ==> ignore
|
||||
arg [--as-needed] ==> ignore
|
||||
arg [-dynamic-linker] ==> ignore
|
||||
arg [/lib/ld-linux-aarch64.so.1] ==> ignore
|
||||
arg [-X] ==> ignore
|
||||
arg [-EL] ==> ignore
|
||||
arg [-maarch64linux] ==> ignore
|
||||
arg [--fix-cortex-a53-843419] ==> ignore
|
||||
arg [-pie] ==> ignore
|
||||
arg [-znow] ==> ignore
|
||||
arg [-zrelro] ==> ignore
|
||||
arg [-o] ==> ignore
|
||||
arg [cmTC_42c38] ==> ignore
|
||||
arg [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/Scrt1.o] ==> obj [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/Scrt1.o]
|
||||
arg [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crti.o] ==> obj [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crti.o]
|
||||
arg [/usr/lib/gcc/aarch64-linux-gnu/11/crtbeginS.o] ==> obj [/usr/lib/gcc/aarch64-linux-gnu/11/crtbeginS.o]
|
||||
arg [-L/usr/lib/gcc/aarch64-linux-gnu/11] ==> dir [/usr/lib/gcc/aarch64-linux-gnu/11]
|
||||
arg [-L/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu] ==> dir [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu]
|
||||
arg [-L/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib] ==> dir [/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib]
|
||||
arg [-L/lib/aarch64-linux-gnu] ==> dir [/lib/aarch64-linux-gnu]
|
||||
arg [-L/lib/../lib] ==> dir [/lib/../lib]
|
||||
arg [-L/usr/lib/aarch64-linux-gnu] ==> dir [/usr/lib/aarch64-linux-gnu]
|
||||
arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib]
|
||||
arg [-L/usr/lib/gcc/aarch64-linux-gnu/11/../../..] ==> dir [/usr/lib/gcc/aarch64-linux-gnu/11/../../..]
|
||||
arg [CMakeFiles/cmTC_42c38.dir/CMakeCXXCompilerABI.cpp.o] ==> ignore
|
||||
arg [-lstdc++] ==> lib [stdc++]
|
||||
arg [-lm] ==> lib [m]
|
||||
arg [-lgcc_s] ==> lib [gcc_s]
|
||||
arg [-lgcc] ==> lib [gcc]
|
||||
arg [-lc] ==> lib [c]
|
||||
arg [-lgcc_s] ==> lib [gcc_s]
|
||||
arg [-lgcc] ==> lib [gcc]
|
||||
arg [/usr/lib/gcc/aarch64-linux-gnu/11/crtendS.o] ==> obj [/usr/lib/gcc/aarch64-linux-gnu/11/crtendS.o]
|
||||
arg [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crtn.o] ==> obj [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crtn.o]
|
||||
collapse obj [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/Scrt1.o] ==> [/usr/lib/aarch64-linux-gnu/Scrt1.o]
|
||||
collapse obj [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crti.o] ==> [/usr/lib/aarch64-linux-gnu/crti.o]
|
||||
collapse obj [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu/crtn.o] ==> [/usr/lib/aarch64-linux-gnu/crtn.o]
|
||||
collapse library dir [/usr/lib/gcc/aarch64-linux-gnu/11] ==> [/usr/lib/gcc/aarch64-linux-gnu/11]
|
||||
collapse library dir [/usr/lib/gcc/aarch64-linux-gnu/11/../../../aarch64-linux-gnu] ==> [/usr/lib/aarch64-linux-gnu]
|
||||
collapse library dir [/usr/lib/gcc/aarch64-linux-gnu/11/../../../../lib] ==> [/usr/lib]
|
||||
collapse library dir [/lib/aarch64-linux-gnu] ==> [/lib/aarch64-linux-gnu]
|
||||
collapse library dir [/lib/../lib] ==> [/lib]
|
||||
collapse library dir [/usr/lib/aarch64-linux-gnu] ==> [/usr/lib/aarch64-linux-gnu]
|
||||
collapse library dir [/usr/lib/../lib] ==> [/usr/lib]
|
||||
collapse library dir [/usr/lib/gcc/aarch64-linux-gnu/11/../../..] ==> [/usr/lib]
|
||||
implicit libs: [stdc++;m;gcc_s;gcc;c;gcc_s;gcc]
|
||||
implicit objs: [/usr/lib/aarch64-linux-gnu/Scrt1.o;/usr/lib/aarch64-linux-gnu/crti.o;/usr/lib/gcc/aarch64-linux-gnu/11/crtbeginS.o;/usr/lib/gcc/aarch64-linux-gnu/11/crtendS.o;/usr/lib/aarch64-linux-gnu/crtn.o]
|
||||
implicit dirs: [/usr/lib/gcc/aarch64-linux-gnu/11;/usr/lib/aarch64-linux-gnu;/usr/lib;/lib/aarch64-linux-gnu;/lib]
|
||||
implicit fwks: []
|
||||
|
||||
|
||||
Determining if the include file pthread.h exists passed with the following output:
|
||||
Change Dir: /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp
|
||||
|
||||
Run Build Command(s):/usr/bin/gmake -f Makefile cmTC_f8885/fast && /usr/bin/gmake -f CMakeFiles/cmTC_f8885.dir/build.make CMakeFiles/cmTC_f8885.dir/build
|
||||
gmake[1]: Entering directory '/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp'
|
||||
Building C object CMakeFiles/cmTC_f8885.dir/CheckIncludeFile.c.o
|
||||
/usr/bin/cc -o CMakeFiles/cmTC_f8885.dir/CheckIncludeFile.c.o -c /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp/CheckIncludeFile.c
|
||||
Linking C executable cmTC_f8885
|
||||
/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_f8885.dir/link.txt --verbose=1
|
||||
/usr/bin/cc CMakeFiles/cmTC_f8885.dir/CheckIncludeFile.c.o -o cmTC_f8885
|
||||
gmake[1]: Leaving directory '/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp'
|
||||
|
||||
|
||||
|
||||
Performing C SOURCE FILE Test CMAKE_HAVE_LIBC_PTHREAD succeeded with the following output:
|
||||
Change Dir: /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp
|
||||
|
||||
Run Build Command(s):/usr/bin/gmake -f Makefile cmTC_63354/fast && /usr/bin/gmake -f CMakeFiles/cmTC_63354.dir/build.make CMakeFiles/cmTC_63354.dir/build
|
||||
gmake[1]: Entering directory '/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp'
|
||||
Building C object CMakeFiles/cmTC_63354.dir/src.c.o
|
||||
/usr/bin/cc -DCMAKE_HAVE_LIBC_PTHREAD -o CMakeFiles/cmTC_63354.dir/src.c.o -c /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp/src.c
|
||||
Linking C executable cmTC_63354
|
||||
/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_63354.dir/link.txt --verbose=1
|
||||
/usr/bin/cc CMakeFiles/cmTC_63354.dir/src.c.o -o cmTC_63354
|
||||
gmake[1]: Leaving directory '/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/CMakeTmp'
|
||||
|
||||
|
||||
Source file was:
|
||||
#include <pthread.h>
|
||||
|
||||
static void* test_func(void* data)
|
||||
{
|
||||
return data;
|
||||
}
|
||||
|
||||
int main(void)
|
||||
{
|
||||
pthread_t thread;
|
||||
pthread_create(&thread, NULL, test_func, NULL);
|
||||
pthread_detach(thread);
|
||||
pthread_cancel(thread);
|
||||
pthread_join(thread, NULL);
|
||||
pthread_atfork(NULL, NULL, NULL);
|
||||
pthread_exit(NULL);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -0,0 +1,2 @@
|
||||
# Hashes of file build rules.
|
||||
097f62fc9f3acf6f7485c8604b0a928b CMakeFiles/armor_yolo_detect_uninstall
|
||||
@@ -0,0 +1,222 @@
|
||||
# CMAKE generated file: DO NOT EDIT!
|
||||
# Generated by "Unix Makefiles" Generator, CMake Version 3.22
|
||||
|
||||
# Default target executed when no arguments are given to make.
|
||||
default_target: all
|
||||
.PHONY : default_target
|
||||
|
||||
#=============================================================================
|
||||
# Special targets provided by cmake.
|
||||
|
||||
# Disable implicit rules so canonical targets will work.
|
||||
.SUFFIXES:
|
||||
|
||||
# Disable VCS-based implicit rules.
|
||||
% : %,v
|
||||
|
||||
# Disable VCS-based implicit rules.
|
||||
% : RCS/%
|
||||
|
||||
# Disable VCS-based implicit rules.
|
||||
% : RCS/%,v
|
||||
|
||||
# Disable VCS-based implicit rules.
|
||||
% : SCCS/s.%
|
||||
|
||||
# Disable VCS-based implicit rules.
|
||||
% : s.%
|
||||
|
||||
.SUFFIXES: .hpux_make_needs_suffix_list
|
||||
|
||||
# Command-line flag to silence nested $(MAKE).
|
||||
$(VERBOSE)MAKESILENT = -s
|
||||
|
||||
#Suppress display of executed commands.
|
||||
$(VERBOSE).SILENT:
|
||||
|
||||
# A target that is always out of date.
|
||||
cmake_force:
|
||||
.PHONY : cmake_force
|
||||
|
||||
#=============================================================================
|
||||
# Set environment variables for the build.
|
||||
|
||||
# The shell in which to execute make rules.
|
||||
SHELL = /bin/sh
|
||||
|
||||
# The CMake executable.
|
||||
CMAKE_COMMAND = /usr/bin/cmake
|
||||
|
||||
# The command to remove a file.
|
||||
RM = /usr/bin/cmake -E rm -f
|
||||
|
||||
# Escaping for special characters.
|
||||
EQUALS = =
|
||||
|
||||
# The top-level source directory on which CMake was run.
|
||||
CMAKE_SOURCE_DIR = /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect
|
||||
|
||||
# The top-level build directory on which CMake was run.
|
||||
CMAKE_BINARY_DIR = /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect
|
||||
|
||||
#=============================================================================
|
||||
# Directory level rules for the build root directory
|
||||
|
||||
# The main recursive "all" target.
|
||||
all: CMakeFiles/armor_yolo_detect.dir/all
|
||||
all: CMakeFiles/trt_inference_test.dir/all
|
||||
all: CMakeFiles/armor_yolo_detector_node.dir/all
|
||||
.PHONY : all
|
||||
|
||||
# The main recursive "preinstall" target.
|
||||
preinstall:
|
||||
.PHONY : preinstall
|
||||
|
||||
# The main recursive "clean" target.
|
||||
clean: CMakeFiles/uninstall.dir/clean
|
||||
clean: CMakeFiles/armor_yolo_detect_uninstall.dir/clean
|
||||
clean: CMakeFiles/armor_yolo_detect.dir/clean
|
||||
clean: CMakeFiles/trt_inference_test.dir/clean
|
||||
clean: CMakeFiles/armor_yolo_detector_node.dir/clean
|
||||
.PHONY : clean
|
||||
|
||||
#=============================================================================
|
||||
# Target rules for target CMakeFiles/uninstall.dir
|
||||
|
||||
# All Build rule for target.
|
||||
CMakeFiles/uninstall.dir/all: CMakeFiles/armor_yolo_detect_uninstall.dir/all
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/uninstall.dir/build.make CMakeFiles/uninstall.dir/depend
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/uninstall.dir/build.make CMakeFiles/uninstall.dir/build
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles --progress-num= "Built target uninstall"
|
||||
.PHONY : CMakeFiles/uninstall.dir/all
|
||||
|
||||
# Build rule for subdir invocation for target.
|
||||
CMakeFiles/uninstall.dir/rule: cmake_check_build_system
|
||||
$(CMAKE_COMMAND) -E cmake_progress_start /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles 0
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/Makefile2 CMakeFiles/uninstall.dir/all
|
||||
$(CMAKE_COMMAND) -E cmake_progress_start /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles 0
|
||||
.PHONY : CMakeFiles/uninstall.dir/rule
|
||||
|
||||
# Convenience name for target.
|
||||
uninstall: CMakeFiles/uninstall.dir/rule
|
||||
.PHONY : uninstall
|
||||
|
||||
# clean rule for target.
|
||||
CMakeFiles/uninstall.dir/clean:
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/uninstall.dir/build.make CMakeFiles/uninstall.dir/clean
|
||||
.PHONY : CMakeFiles/uninstall.dir/clean
|
||||
|
||||
#=============================================================================
|
||||
# Target rules for target CMakeFiles/armor_yolo_detect_uninstall.dir
|
||||
|
||||
# All Build rule for target.
|
||||
CMakeFiles/armor_yolo_detect_uninstall.dir/all:
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/armor_yolo_detect_uninstall.dir/build.make CMakeFiles/armor_yolo_detect_uninstall.dir/depend
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/armor_yolo_detect_uninstall.dir/build.make CMakeFiles/armor_yolo_detect_uninstall.dir/build
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles --progress-num= "Built target armor_yolo_detect_uninstall"
|
||||
.PHONY : CMakeFiles/armor_yolo_detect_uninstall.dir/all
|
||||
|
||||
# Build rule for subdir invocation for target.
|
||||
CMakeFiles/armor_yolo_detect_uninstall.dir/rule: cmake_check_build_system
|
||||
$(CMAKE_COMMAND) -E cmake_progress_start /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles 0
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/Makefile2 CMakeFiles/armor_yolo_detect_uninstall.dir/all
|
||||
$(CMAKE_COMMAND) -E cmake_progress_start /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles 0
|
||||
.PHONY : CMakeFiles/armor_yolo_detect_uninstall.dir/rule
|
||||
|
||||
# Convenience name for target.
|
||||
armor_yolo_detect_uninstall: CMakeFiles/armor_yolo_detect_uninstall.dir/rule
|
||||
.PHONY : armor_yolo_detect_uninstall
|
||||
|
||||
# clean rule for target.
|
||||
CMakeFiles/armor_yolo_detect_uninstall.dir/clean:
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/armor_yolo_detect_uninstall.dir/build.make CMakeFiles/armor_yolo_detect_uninstall.dir/clean
|
||||
.PHONY : CMakeFiles/armor_yolo_detect_uninstall.dir/clean
|
||||
|
||||
#=============================================================================
|
||||
# Target rules for target CMakeFiles/armor_yolo_detect.dir
|
||||
|
||||
# All Build rule for target.
|
||||
CMakeFiles/armor_yolo_detect.dir/all:
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/armor_yolo_detect.dir/build.make CMakeFiles/armor_yolo_detect.dir/depend
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/armor_yolo_detect.dir/build.make CMakeFiles/armor_yolo_detect.dir/build
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles --progress-num=1,2,3,4,5 "Built target armor_yolo_detect"
|
||||
.PHONY : CMakeFiles/armor_yolo_detect.dir/all
|
||||
|
||||
# Build rule for subdir invocation for target.
|
||||
CMakeFiles/armor_yolo_detect.dir/rule: cmake_check_build_system
|
||||
$(CMAKE_COMMAND) -E cmake_progress_start /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles 5
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/Makefile2 CMakeFiles/armor_yolo_detect.dir/all
|
||||
$(CMAKE_COMMAND) -E cmake_progress_start /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles 0
|
||||
.PHONY : CMakeFiles/armor_yolo_detect.dir/rule
|
||||
|
||||
# Convenience name for target.
|
||||
armor_yolo_detect: CMakeFiles/armor_yolo_detect.dir/rule
|
||||
.PHONY : armor_yolo_detect
|
||||
|
||||
# clean rule for target.
|
||||
CMakeFiles/armor_yolo_detect.dir/clean:
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/armor_yolo_detect.dir/build.make CMakeFiles/armor_yolo_detect.dir/clean
|
||||
.PHONY : CMakeFiles/armor_yolo_detect.dir/clean
|
||||
|
||||
#=============================================================================
|
||||
# Target rules for target CMakeFiles/trt_inference_test.dir
|
||||
|
||||
# All Build rule for target.
|
||||
CMakeFiles/trt_inference_test.dir/all: CMakeFiles/armor_yolo_detect.dir/all
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/trt_inference_test.dir/build.make CMakeFiles/trt_inference_test.dir/depend
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/trt_inference_test.dir/build.make CMakeFiles/trt_inference_test.dir/build
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles --progress-num=8,9 "Built target trt_inference_test"
|
||||
.PHONY : CMakeFiles/trt_inference_test.dir/all
|
||||
|
||||
# Build rule for subdir invocation for target.
|
||||
CMakeFiles/trt_inference_test.dir/rule: cmake_check_build_system
|
||||
$(CMAKE_COMMAND) -E cmake_progress_start /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles 7
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/Makefile2 CMakeFiles/trt_inference_test.dir/all
|
||||
$(CMAKE_COMMAND) -E cmake_progress_start /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles 0
|
||||
.PHONY : CMakeFiles/trt_inference_test.dir/rule
|
||||
|
||||
# Convenience name for target.
|
||||
trt_inference_test: CMakeFiles/trt_inference_test.dir/rule
|
||||
.PHONY : trt_inference_test
|
||||
|
||||
# clean rule for target.
|
||||
CMakeFiles/trt_inference_test.dir/clean:
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/trt_inference_test.dir/build.make CMakeFiles/trt_inference_test.dir/clean
|
||||
.PHONY : CMakeFiles/trt_inference_test.dir/clean
|
||||
|
||||
#=============================================================================
|
||||
# Target rules for target CMakeFiles/armor_yolo_detector_node.dir
|
||||
|
||||
# All Build rule for target.
|
||||
CMakeFiles/armor_yolo_detector_node.dir/all:
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/armor_yolo_detector_node.dir/build.make CMakeFiles/armor_yolo_detector_node.dir/depend
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/armor_yolo_detector_node.dir/build.make CMakeFiles/armor_yolo_detector_node.dir/build
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles --progress-num=6,7 "Built target armor_yolo_detector_node"
|
||||
.PHONY : CMakeFiles/armor_yolo_detector_node.dir/all
|
||||
|
||||
# Build rule for subdir invocation for target.
|
||||
CMakeFiles/armor_yolo_detector_node.dir/rule: cmake_check_build_system
|
||||
$(CMAKE_COMMAND) -E cmake_progress_start /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles 2
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/Makefile2 CMakeFiles/armor_yolo_detector_node.dir/all
|
||||
$(CMAKE_COMMAND) -E cmake_progress_start /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles 0
|
||||
.PHONY : CMakeFiles/armor_yolo_detector_node.dir/rule
|
||||
|
||||
# Convenience name for target.
|
||||
armor_yolo_detector_node: CMakeFiles/armor_yolo_detector_node.dir/rule
|
||||
.PHONY : armor_yolo_detector_node
|
||||
|
||||
# clean rule for target.
|
||||
CMakeFiles/armor_yolo_detector_node.dir/clean:
|
||||
$(MAKE) $(MAKESILENT) -f CMakeFiles/armor_yolo_detector_node.dir/build.make CMakeFiles/armor_yolo_detector_node.dir/clean
|
||||
.PHONY : CMakeFiles/armor_yolo_detector_node.dir/clean
|
||||
|
||||
#=============================================================================
|
||||
# Special targets to cleanup operation of make.
|
||||
|
||||
# Special rule to run CMake to check the build system integrity.
|
||||
# No rule that depends on this can have commands that come from listfiles
|
||||
# because they might be regenerated.
|
||||
cmake_check_build_system:
|
||||
$(CMAKE_COMMAND) -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0
|
||||
.PHONY : cmake_check_build_system
|
||||
|
||||
@@ -0,0 +1 @@
|
||||
empty
|
||||
@@ -0,0 +1 @@
|
||||
empty
|
||||
@@ -0,0 +1 @@
|
||||
empty
|
||||
@@ -0,0 +1 @@
|
||||
empty
|
||||
@@ -0,0 +1 @@
|
||||
empty
|
||||
@@ -0,0 +1 @@
|
||||
9
|
||||
@@ -0,0 +1,12 @@
|
||||
/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/uninstall.dir
|
||||
/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/armor_yolo_detect_uninstall.dir
|
||||
/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/armor_yolo_detect.dir
|
||||
/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/trt_inference_test.dir
|
||||
/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/armor_yolo_detector_node.dir
|
||||
/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/test.dir
|
||||
/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/edit_cache.dir
|
||||
/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/rebuild_cache.dir
|
||||
/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/list_install_components.dir
|
||||
/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/install.dir
|
||||
/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/install/local.dir
|
||||
/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/install/strip.dir
|
||||
@@ -0,0 +1,22 @@
|
||||
|
||||
# Consider dependencies only in project.
|
||||
set(CMAKE_DEPENDS_IN_PROJECT_ONLY OFF)
|
||||
|
||||
# The set of languages for which implicit dependencies are needed:
|
||||
set(CMAKE_DEPENDS_LANGUAGES
|
||||
)
|
||||
|
||||
# The set of dependency files which are needed:
|
||||
set(CMAKE_DEPENDS_DEPENDENCY_FILES
|
||||
"/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/src/armor_yolo_detector.cpp" "CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.o" "gcc" "CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.o.d"
|
||||
"/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/src/armor_yolo_detector_node.cpp" "CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.o" "gcc" "CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.o.d"
|
||||
"/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/src/trt_logger.cpp" "CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.o" "gcc" "CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.o.d"
|
||||
"/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/src/yolo_tensorrt.cpp" "CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.o" "gcc" "CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.o.d"
|
||||
)
|
||||
|
||||
# Targets to which this target links.
|
||||
set(CMAKE_TARGET_LINKED_INFO_FILES
|
||||
)
|
||||
|
||||
# Fortran module output directory.
|
||||
set(CMAKE_Fortran_TARGET_MODULE_DIR "")
|
||||
@@ -0,0 +1,353 @@
|
||||
# CMAKE generated file: DO NOT EDIT!
|
||||
# Generated by "Unix Makefiles" Generator, CMake Version 3.22
|
||||
|
||||
# Delete rule output on recipe failure.
|
||||
.DELETE_ON_ERROR:
|
||||
|
||||
#=============================================================================
|
||||
# Special targets provided by cmake.
|
||||
|
||||
# Disable implicit rules so canonical targets will work.
|
||||
.SUFFIXES:
|
||||
|
||||
# Disable VCS-based implicit rules.
|
||||
% : %,v
|
||||
|
||||
# Disable VCS-based implicit rules.
|
||||
% : RCS/%
|
||||
|
||||
# Disable VCS-based implicit rules.
|
||||
% : RCS/%,v
|
||||
|
||||
# Disable VCS-based implicit rules.
|
||||
% : SCCS/s.%
|
||||
|
||||
# Disable VCS-based implicit rules.
|
||||
% : s.%
|
||||
|
||||
.SUFFIXES: .hpux_make_needs_suffix_list
|
||||
|
||||
# Command-line flag to silence nested $(MAKE).
|
||||
$(VERBOSE)MAKESILENT = -s
|
||||
|
||||
#Suppress display of executed commands.
|
||||
$(VERBOSE).SILENT:
|
||||
|
||||
# A target that is always out of date.
|
||||
cmake_force:
|
||||
.PHONY : cmake_force
|
||||
|
||||
#=============================================================================
|
||||
# Set environment variables for the build.
|
||||
|
||||
# The shell in which to execute make rules.
|
||||
SHELL = /bin/sh
|
||||
|
||||
# The CMake executable.
|
||||
CMAKE_COMMAND = /usr/bin/cmake
|
||||
|
||||
# The command to remove a file.
|
||||
RM = /usr/bin/cmake -E rm -f
|
||||
|
||||
# Escaping for special characters.
|
||||
EQUALS = =
|
||||
|
||||
# The top-level source directory on which CMake was run.
|
||||
CMAKE_SOURCE_DIR = /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect
|
||||
|
||||
# The top-level build directory on which CMake was run.
|
||||
CMAKE_BINARY_DIR = /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect
|
||||
|
||||
# Include any dependencies generated for this target.
|
||||
include CMakeFiles/armor_yolo_detect.dir/depend.make
|
||||
# Include any dependencies generated by the compiler for this target.
|
||||
include CMakeFiles/armor_yolo_detect.dir/compiler_depend.make
|
||||
|
||||
# Include the progress variables for this target.
|
||||
include CMakeFiles/armor_yolo_detect.dir/progress.make
|
||||
|
||||
# Include the compile flags for this target's objects.
|
||||
include CMakeFiles/armor_yolo_detect.dir/flags.make
|
||||
|
||||
CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.o: CMakeFiles/armor_yolo_detect.dir/flags.make
|
||||
CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.o: ../../src/armor_yolo_detector.cpp
|
||||
CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.o: CMakeFiles/armor_yolo_detect.dir/compiler_depend.ts
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles --progress-num=$(CMAKE_PROGRESS_1) "Building CXX object CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.o"
|
||||
/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -MD -MT CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.o -MF CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.o.d -o CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.o -c /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/src/armor_yolo_detector.cpp
|
||||
|
||||
CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.i: cmake_force
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.i"
|
||||
/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/src/armor_yolo_detector.cpp > CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.i
|
||||
|
||||
CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.s: cmake_force
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.s"
|
||||
/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/src/armor_yolo_detector.cpp -o CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.s
|
||||
|
||||
CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.o: CMakeFiles/armor_yolo_detect.dir/flags.make
|
||||
CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.o: ../../src/armor_yolo_detector_node.cpp
|
||||
CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.o: CMakeFiles/armor_yolo_detect.dir/compiler_depend.ts
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles --progress-num=$(CMAKE_PROGRESS_2) "Building CXX object CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.o"
|
||||
/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -MD -MT CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.o -MF CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.o.d -o CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.o -c /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/src/armor_yolo_detector_node.cpp
|
||||
|
||||
CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.i: cmake_force
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.i"
|
||||
/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/src/armor_yolo_detector_node.cpp > CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.i
|
||||
|
||||
CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.s: cmake_force
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.s"
|
||||
/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/src/armor_yolo_detector_node.cpp -o CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.s
|
||||
|
||||
CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.o: CMakeFiles/armor_yolo_detect.dir/flags.make
|
||||
CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.o: ../../src/trt_logger.cpp
|
||||
CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.o: CMakeFiles/armor_yolo_detect.dir/compiler_depend.ts
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles --progress-num=$(CMAKE_PROGRESS_3) "Building CXX object CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.o"
|
||||
/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -MD -MT CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.o -MF CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.o.d -o CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.o -c /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/src/trt_logger.cpp
|
||||
|
||||
CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.i: cmake_force
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.i"
|
||||
/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/src/trt_logger.cpp > CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.i
|
||||
|
||||
CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.s: cmake_force
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.s"
|
||||
/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/src/trt_logger.cpp -o CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.s
|
||||
|
||||
CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.o: CMakeFiles/armor_yolo_detect.dir/flags.make
|
||||
CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.o: ../../src/yolo_tensorrt.cpp
|
||||
CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.o: CMakeFiles/armor_yolo_detect.dir/compiler_depend.ts
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles --progress-num=$(CMAKE_PROGRESS_4) "Building CXX object CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.o"
|
||||
/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -MD -MT CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.o -MF CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.o.d -o CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.o -c /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/src/yolo_tensorrt.cpp
|
||||
|
||||
CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.i: cmake_force
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.i"
|
||||
/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/src/yolo_tensorrt.cpp > CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.i
|
||||
|
||||
CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.s: cmake_force
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.s"
|
||||
/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/src/yolo_tensorrt.cpp -o CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.s
|
||||
|
||||
# Object files for target armor_yolo_detect
|
||||
armor_yolo_detect_OBJECTS = \
|
||||
"CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.o" \
|
||||
"CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.o" \
|
||||
"CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.o" \
|
||||
"CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.o"
|
||||
|
||||
# External object files for target armor_yolo_detect
|
||||
armor_yolo_detect_EXTERNAL_OBJECTS =
|
||||
|
||||
libarmor_yolo_detect.so: CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.o
|
||||
libarmor_yolo_detect.so: CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.o
|
||||
libarmor_yolo_detect.so: CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.o
|
||||
libarmor_yolo_detect.so: CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.o
|
||||
libarmor_yolo_detect.so: CMakeFiles/armor_yolo_detect.dir/build.make
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libcomponent_manager.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstd_srvs__rosidl_typesupport_fastrtps_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstd_srvs__rosidl_typesupport_introspection_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstd_srvs__rosidl_typesupport_fastrtps_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstd_srvs__rosidl_typesupport_introspection_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstd_srvs__rosidl_typesupport_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstd_srvs__rosidl_generator_py.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libvisualization_msgs__rosidl_typesupport_fastrtps_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libvisualization_msgs__rosidl_typesupport_fastrtps_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libvisualization_msgs__rosidl_typesupport_introspection_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libvisualization_msgs__rosidl_typesupport_introspection_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libvisualization_msgs__rosidl_typesupport_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libvisualization_msgs__rosidl_generator_py.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libcv_bridge.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/aarch64-linux-gnu/libimage_transport.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstatic_transform_broadcaster_node.so
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_stitching.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_alphamat.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_aruco.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_barcode.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_bgsegm.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_bioinspired.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_ccalib.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_dnn_objdetect.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_dnn_superres.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_dpm.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_face.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_freetype.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_fuzzy.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_hdf.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_hfs.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_img_hash.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_intensity_transform.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_line_descriptor.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_mcc.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_quality.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_rapid.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_reg.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_rgbd.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_saliency.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_shape.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_stereo.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_structured_light.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_superres.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_surface_matching.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_tracking.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_videostab.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_viz.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_wechat_qrcode.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_xobjdetect.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_xphoto.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/local/cuda-12.6/lib64/libcudart_static.a
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/librt.a
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libclass_loader.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libcomposition_interfaces__rosidl_typesupport_fastrtps_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libcomposition_interfaces__rosidl_typesupport_introspection_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libcomposition_interfaces__rosidl_typesupport_fastrtps_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libcomposition_interfaces__rosidl_typesupport_introspection_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libcomposition_interfaces__rosidl_typesupport_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libcomposition_interfaces__rosidl_generator_py.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libcomposition_interfaces__rosidl_typesupport_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libcomposition_interfaces__rosidl_generator_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstd_srvs__rosidl_typesupport_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstd_srvs__rosidl_generator_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libvisualization_msgs__rosidl_typesupport_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libvisualization_msgs__rosidl_generator_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_fastrtps_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_fastrtps_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_introspection_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_introspection_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libsensor_msgs__rosidl_generator_py.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libsensor_msgs__rosidl_generator_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libtf2_ros.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libtf2.so
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libconsole_bridge.so.1.0
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libmessage_filters.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librclcpp_action.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librclcpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/liblibstatistics_collector.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_fastrtps_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_fastrtps_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_introspection_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_introspection_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librosgraph_msgs__rosidl_generator_py.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librosgraph_msgs__rosidl_generator_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_fastrtps_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_fastrtps_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_introspection_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_introspection_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstatistics_msgs__rosidl_generator_py.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstatistics_msgs__rosidl_generator_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librcl_action.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librcl.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_fastrtps_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_introspection_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_fastrtps_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_introspection_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librcl_interfaces__rosidl_generator_py.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librcl_interfaces__rosidl_generator_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librcl_yaml_param_parser.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libyaml.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libtracetools.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librmw_implementation.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libament_index_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librcl_logging_spdlog.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librcl_logging_interface.so
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libfmt.so.8.1.1
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libtf2_msgs__rosidl_typesupport_fastrtps_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_fastrtps_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_fastrtps_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_fastrtps_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_fastrtps_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_fastrtps_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librosidl_typesupport_fastrtps_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libtf2_msgs__rosidl_typesupport_introspection_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_introspection_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_introspection_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_introspection_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_introspection_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_introspection_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libtf2_msgs__rosidl_typesupport_fastrtps_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_fastrtps_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_fastrtps_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_fastrtps_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_fastrtps_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_fastrtps_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librosidl_typesupport_fastrtps_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libfastcdr.so.1.0.24
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librmw.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libtf2_msgs__rosidl_typesupport_introspection_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_introspection_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_introspection_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_introspection_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_introspection_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_introspection_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librosidl_typesupport_introspection_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librosidl_typesupport_introspection_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libtf2_msgs__rosidl_typesupport_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librosidl_typesupport_cpp.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libtf2_msgs__rosidl_generator_py.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libgeometry_msgs__rosidl_generator_py.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstd_msgs__rosidl_generator_py.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libtf2_msgs__rosidl_typesupport_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libtf2_msgs__rosidl_generator_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libgeometry_msgs__rosidl_generator_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libstd_msgs__rosidl_generator_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libaction_msgs__rosidl_generator_py.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_generator_py.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libaction_msgs__rosidl_generator_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_generator_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_generator_py.so
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libpython3.10.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librosidl_typesupport_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librcpputils.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_generator_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librosidl_runtime_c.so
|
||||
libarmor_yolo_detect.so: /opt/ros/humble/lib/librcutils.so
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/liborocos-kdl.so
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_highgui.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_datasets.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_plot.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_text.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_ml.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_phase_unwrapping.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_optflow.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_ximgproc.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_video.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_videoio.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_imgcodecs.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_objdetect.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_calib3d.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_dnn.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_features2d.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_flann.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_photo.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_imgproc.so.4.5.4d
|
||||
libarmor_yolo_detect.so: /usr/lib/aarch64-linux-gnu/libopencv_core.so.4.5.4d
|
||||
libarmor_yolo_detect.so: CMakeFiles/armor_yolo_detect.dir/link.txt
|
||||
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --bold --progress-dir=/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles --progress-num=$(CMAKE_PROGRESS_5) "Linking CXX shared library libarmor_yolo_detect.so"
|
||||
$(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/armor_yolo_detect.dir/link.txt --verbose=$(VERBOSE)
|
||||
|
||||
# Rule to build all files generated by this target.
|
||||
CMakeFiles/armor_yolo_detect.dir/build: libarmor_yolo_detect.so
|
||||
.PHONY : CMakeFiles/armor_yolo_detect.dir/build
|
||||
|
||||
CMakeFiles/armor_yolo_detect.dir/clean:
|
||||
$(CMAKE_COMMAND) -P CMakeFiles/armor_yolo_detect.dir/cmake_clean.cmake
|
||||
.PHONY : CMakeFiles/armor_yolo_detect.dir/clean
|
||||
|
||||
CMakeFiles/armor_yolo_detect.dir/depend:
|
||||
cd /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect /home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/build/armor_yolo_detect/CMakeFiles/armor_yolo_detect.dir/DependInfo.cmake --color=$(COLOR)
|
||||
.PHONY : CMakeFiles/armor_yolo_detect.dir/depend
|
||||
|
||||
@@ -0,0 +1,17 @@
|
||||
file(REMOVE_RECURSE
|
||||
"CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.o"
|
||||
"CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector.cpp.o.d"
|
||||
"CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.o"
|
||||
"CMakeFiles/armor_yolo_detect.dir/src/armor_yolo_detector_node.cpp.o.d"
|
||||
"CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.o"
|
||||
"CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.o.d"
|
||||
"CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.o"
|
||||
"CMakeFiles/armor_yolo_detect.dir/src/yolo_tensorrt.cpp.o.d"
|
||||
"libarmor_yolo_detect.pdb"
|
||||
"libarmor_yolo_detect.so"
|
||||
)
|
||||
|
||||
# Per-language clean rules from dependency scanning.
|
||||
foreach(lang CXX)
|
||||
include(CMakeFiles/armor_yolo_detect.dir/cmake_clean_${lang}.cmake OPTIONAL)
|
||||
endforeach()
|
||||
@@ -0,0 +1,227 @@
|
||||
# CMAKE generated file: DO NOT EDIT!
|
||||
# Generated by "Unix Makefiles" Generator, CMake Version 3.22
|
||||
|
||||
CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.o
|
||||
/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/src/trt_logger.cpp
|
||||
/usr/include/stdc-predef.h
|
||||
/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/include/armor_yolo_detect/trt_logger.hpp
|
||||
/usr/include/aarch64-linux-gnu/NvInfer.h
|
||||
/usr/include/aarch64-linux-gnu/NvInferLegacyDims.h
|
||||
/usr/include/aarch64-linux-gnu/NvInferRuntimeBase.h
|
||||
/usr/include/aarch64-linux-gnu/NvInferVersion.h
|
||||
/usr/include/c++/11/cstddef
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/c++config.h
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/os_defines.h
|
||||
/usr/include/features.h
|
||||
/usr/include/features-time64.h
|
||||
/usr/include/aarch64-linux-gnu/bits/wordsize.h
|
||||
/usr/include/aarch64-linux-gnu/bits/timesize.h
|
||||
/usr/include/aarch64-linux-gnu/sys/cdefs.h
|
||||
/usr/include/aarch64-linux-gnu/bits/long-double.h
|
||||
/usr/include/aarch64-linux-gnu/gnu/stubs.h
|
||||
/usr/include/aarch64-linux-gnu/gnu/stubs-lp64.h
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/cpu_defines.h
|
||||
/usr/include/c++/11/pstl/pstl_config.h
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/include/stddef.h
|
||||
/usr/include/c++/11/cstdint
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/include/stdint.h
|
||||
/usr/include/stdint.h
|
||||
/usr/include/aarch64-linux-gnu/bits/libc-header-start.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types.h
|
||||
/usr/include/aarch64-linux-gnu/bits/typesizes.h
|
||||
/usr/include/aarch64-linux-gnu/bits/time64.h
|
||||
/usr/include/aarch64-linux-gnu/bits/wchar.h
|
||||
/usr/include/aarch64-linux-gnu/bits/stdint-intn.h
|
||||
/usr/include/aarch64-linux-gnu/bits/stdint-uintn.h
|
||||
/usr/local/cuda-12.6/include/cuda_runtime_api.h
|
||||
/usr/local/cuda-12.6/include/crt/host_defines.h
|
||||
/usr/local/cuda-12.6/include/builtin_types.h
|
||||
/usr/local/cuda-12.6/include/device_types.h
|
||||
/usr/local/cuda-12.6/include/driver_types.h
|
||||
/usr/local/cuda-12.6/include/vector_types.h
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/include/limits.h
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/include/syslimits.h
|
||||
/usr/include/limits.h
|
||||
/usr/include/aarch64-linux-gnu/bits/posix1_lim.h
|
||||
/usr/include/aarch64-linux-gnu/bits/local_lim.h
|
||||
/usr/include/linux/limits.h
|
||||
/usr/include/aarch64-linux-gnu/bits/pthread_stack_min-dynamic.h
|
||||
/usr/include/aarch64-linux-gnu/bits/posix2_lim.h
|
||||
/usr/include/aarch64-linux-gnu/bits/xopen_lim.h
|
||||
/usr/include/aarch64-linux-gnu/bits/uio_lim.h
|
||||
/usr/local/cuda-12.6/include/surface_types.h
|
||||
/usr/local/cuda-12.6/include/texture_types.h
|
||||
/usr/local/cuda-12.6/include/cuda_device_runtime_api.h
|
||||
/usr/include/aarch64-linux-gnu/NvInferRuntime.h
|
||||
/usr/include/aarch64-linux-gnu/NvInferImpl.h
|
||||
/usr/include/aarch64-linux-gnu/NvInferRuntimeCommon.h
|
||||
/usr/include/aarch64-linux-gnu/NvInferRuntimePlugin.h
|
||||
/usr/include/c++/11/iostream
|
||||
/usr/include/c++/11/ostream
|
||||
/usr/include/c++/11/ios
|
||||
/usr/include/c++/11/iosfwd
|
||||
/usr/include/c++/11/bits/stringfwd.h
|
||||
/usr/include/c++/11/bits/memoryfwd.h
|
||||
/usr/include/c++/11/bits/postypes.h
|
||||
/usr/include/c++/11/cwchar
|
||||
/usr/include/wchar.h
|
||||
/usr/include/aarch64-linux-gnu/bits/floatn.h
|
||||
/usr/include/aarch64-linux-gnu/bits/floatn-common.h
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/include/stdarg.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/wint_t.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/mbstate_t.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__mbstate_t.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__FILE.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/FILE.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/locale_t.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__locale_t.h
|
||||
/usr/include/c++/11/exception
|
||||
/usr/include/c++/11/bits/exception.h
|
||||
/usr/include/c++/11/bits/exception_ptr.h
|
||||
/usr/include/c++/11/bits/exception_defines.h
|
||||
/usr/include/c++/11/bits/cxxabi_init_exception.h
|
||||
/usr/include/c++/11/typeinfo
|
||||
/usr/include/c++/11/bits/hash_bytes.h
|
||||
/usr/include/c++/11/new
|
||||
/usr/include/c++/11/bits/move.h
|
||||
/usr/include/c++/11/type_traits
|
||||
/usr/include/c++/11/bits/nested_exception.h
|
||||
/usr/include/c++/11/bits/char_traits.h
|
||||
/usr/include/c++/11/bits/stl_algobase.h
|
||||
/usr/include/c++/11/bits/functexcept.h
|
||||
/usr/include/c++/11/bits/cpp_type_traits.h
|
||||
/usr/include/c++/11/ext/type_traits.h
|
||||
/usr/include/c++/11/ext/numeric_traits.h
|
||||
/usr/include/c++/11/bits/stl_pair.h
|
||||
/usr/include/c++/11/bits/stl_iterator_base_types.h
|
||||
/usr/include/c++/11/bits/stl_iterator_base_funcs.h
|
||||
/usr/include/c++/11/bits/concept_check.h
|
||||
/usr/include/c++/11/debug/assertions.h
|
||||
/usr/include/c++/11/bits/stl_iterator.h
|
||||
/usr/include/c++/11/bits/ptr_traits.h
|
||||
/usr/include/c++/11/debug/debug.h
|
||||
/usr/include/c++/11/bits/predefined_ops.h
|
||||
/usr/include/c++/11/bits/localefwd.h
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/c++locale.h
|
||||
/usr/include/c++/11/clocale
|
||||
/usr/include/locale.h
|
||||
/usr/include/aarch64-linux-gnu/bits/locale.h
|
||||
/usr/include/c++/11/cctype
|
||||
/usr/include/ctype.h
|
||||
/usr/include/aarch64-linux-gnu/bits/endian.h
|
||||
/usr/include/aarch64-linux-gnu/bits/endianness.h
|
||||
/usr/include/c++/11/bits/ios_base.h
|
||||
/usr/include/c++/11/ext/atomicity.h
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/gthr.h
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/gthr-default.h
|
||||
/usr/include/pthread.h
|
||||
/usr/include/sched.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/time_t.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_timespec.h
|
||||
/usr/include/aarch64-linux-gnu/bits/sched.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_sched_param.h
|
||||
/usr/include/aarch64-linux-gnu/bits/cpu-set.h
|
||||
/usr/include/time.h
|
||||
/usr/include/aarch64-linux-gnu/bits/time.h
|
||||
/usr/include/aarch64-linux-gnu/bits/timex.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_timeval.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/clock_t.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_tm.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/clockid_t.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/timer_t.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_itimerspec.h
|
||||
/usr/include/aarch64-linux-gnu/bits/pthreadtypes.h
|
||||
/usr/include/aarch64-linux-gnu/bits/thread-shared-types.h
|
||||
/usr/include/aarch64-linux-gnu/bits/pthreadtypes-arch.h
|
||||
/usr/include/aarch64-linux-gnu/bits/atomic_wide_counter.h
|
||||
/usr/include/aarch64-linux-gnu/bits/struct_mutex.h
|
||||
/usr/include/aarch64-linux-gnu/bits/struct_rwlock.h
|
||||
/usr/include/aarch64-linux-gnu/bits/setjmp.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__sigset_t.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct___jmp_buf_tag.h
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/atomic_word.h
|
||||
/usr/include/aarch64-linux-gnu/sys/single_threaded.h
|
||||
/usr/include/c++/11/bits/locale_classes.h
|
||||
/usr/include/c++/11/string
|
||||
/usr/include/c++/11/bits/allocator.h
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/c++allocator.h
|
||||
/usr/include/c++/11/ext/new_allocator.h
|
||||
/usr/include/c++/11/bits/ostream_insert.h
|
||||
/usr/include/c++/11/bits/cxxabi_forced.h
|
||||
/usr/include/c++/11/bits/stl_function.h
|
||||
/usr/include/c++/11/backward/binders.h
|
||||
/usr/include/c++/11/bits/range_access.h
|
||||
/usr/include/c++/11/initializer_list
|
||||
/usr/include/c++/11/bits/basic_string.h
|
||||
/usr/include/c++/11/ext/alloc_traits.h
|
||||
/usr/include/c++/11/bits/alloc_traits.h
|
||||
/usr/include/c++/11/bits/stl_construct.h
|
||||
/usr/include/c++/11/string_view
|
||||
/usr/include/c++/11/bits/functional_hash.h
|
||||
/usr/include/c++/11/bits/string_view.tcc
|
||||
/usr/include/c++/11/ext/string_conversions.h
|
||||
/usr/include/c++/11/cstdlib
|
||||
/usr/include/stdlib.h
|
||||
/usr/include/aarch64-linux-gnu/bits/waitflags.h
|
||||
/usr/include/aarch64-linux-gnu/bits/waitstatus.h
|
||||
/usr/include/aarch64-linux-gnu/sys/types.h
|
||||
/usr/include/endian.h
|
||||
/usr/include/aarch64-linux-gnu/bits/byteswap.h
|
||||
/usr/include/aarch64-linux-gnu/bits/uintn-identity.h
|
||||
/usr/include/aarch64-linux-gnu/sys/select.h
|
||||
/usr/include/aarch64-linux-gnu/bits/select.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/sigset_t.h
|
||||
/usr/include/alloca.h
|
||||
/usr/include/aarch64-linux-gnu/bits/stdlib-float.h
|
||||
/usr/include/c++/11/bits/std_abs.h
|
||||
/usr/include/c++/11/cstdio
|
||||
/usr/include/stdio.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__fpos_t.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__fpos64_t.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_FILE.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/cookie_io_functions_t.h
|
||||
/usr/include/aarch64-linux-gnu/bits/stdio_lim.h
|
||||
/usr/include/c++/11/cerrno
|
||||
/usr/include/errno.h
|
||||
/usr/include/aarch64-linux-gnu/bits/errno.h
|
||||
/usr/include/linux/errno.h
|
||||
/usr/include/aarch64-linux-gnu/asm/errno.h
|
||||
/usr/include/asm-generic/errno.h
|
||||
/usr/include/asm-generic/errno-base.h
|
||||
/usr/include/aarch64-linux-gnu/bits/types/error_t.h
|
||||
/usr/include/c++/11/bits/charconv.h
|
||||
/usr/include/c++/11/bits/basic_string.tcc
|
||||
/usr/include/c++/11/bits/locale_classes.tcc
|
||||
/usr/include/c++/11/system_error
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/error_constants.h
|
||||
/usr/include/c++/11/stdexcept
|
||||
/usr/include/c++/11/streambuf
|
||||
/usr/include/c++/11/bits/streambuf.tcc
|
||||
/usr/include/c++/11/bits/basic_ios.h
|
||||
/usr/include/c++/11/bits/locale_facets.h
|
||||
/usr/include/c++/11/cwctype
|
||||
/usr/include/wctype.h
|
||||
/usr/include/aarch64-linux-gnu/bits/wctype-wchar.h
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/ctype_base.h
|
||||
/usr/include/c++/11/bits/streambuf_iterator.h
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/ctype_inline.h
|
||||
/usr/include/c++/11/bits/locale_facets.tcc
|
||||
/usr/include/c++/11/bits/basic_ios.tcc
|
||||
/usr/include/c++/11/bits/ostream.tcc
|
||||
/usr/include/c++/11/istream
|
||||
/usr/include/c++/11/bits/istream.tcc
|
||||
/usr/include/c++/11/mutex
|
||||
/usr/include/c++/11/tuple
|
||||
/usr/include/c++/11/utility
|
||||
/usr/include/c++/11/bits/stl_relops.h
|
||||
/usr/include/c++/11/array
|
||||
/usr/include/c++/11/bits/uses_allocator.h
|
||||
/usr/include/c++/11/bits/invoke.h
|
||||
/usr/include/c++/11/chrono
|
||||
/usr/include/c++/11/ratio
|
||||
/usr/include/c++/11/limits
|
||||
/usr/include/c++/11/ctime
|
||||
/usr/include/c++/11/bits/parse_numbers.h
|
||||
/usr/include/c++/11/bits/std_mutex.h
|
||||
/usr/include/c++/11/bits/unique_lock.h
|
||||
|
||||
@@ -0,0 +1,670 @@
|
||||
# CMAKE generated file: DO NOT EDIT!
|
||||
# Generated by "Unix Makefiles" Generator, CMake Version 3.22
|
||||
|
||||
CMakeFiles/armor_yolo_detect.dir/src/trt_logger.cpp.o: ../../src/trt_logger.cpp \
|
||||
/usr/include/stdc-predef.h \
|
||||
../../include/armor_yolo_detect/trt_logger.hpp \
|
||||
/usr/include/aarch64-linux-gnu/NvInfer.h \
|
||||
/usr/include/aarch64-linux-gnu/NvInferLegacyDims.h \
|
||||
/usr/include/aarch64-linux-gnu/NvInferRuntimeBase.h \
|
||||
/usr/include/aarch64-linux-gnu/NvInferVersion.h \
|
||||
/usr/include/c++/11/cstddef \
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/c++config.h \
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/os_defines.h \
|
||||
/usr/include/features.h \
|
||||
/usr/include/features-time64.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/wordsize.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/timesize.h \
|
||||
/usr/include/aarch64-linux-gnu/sys/cdefs.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/long-double.h \
|
||||
/usr/include/aarch64-linux-gnu/gnu/stubs.h \
|
||||
/usr/include/aarch64-linux-gnu/gnu/stubs-lp64.h \
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/cpu_defines.h \
|
||||
/usr/include/c++/11/pstl/pstl_config.h \
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/include/stddef.h \
|
||||
/usr/include/c++/11/cstdint \
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/include/stdint.h \
|
||||
/usr/include/stdint.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/libc-header-start.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/typesizes.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/time64.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/wchar.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/stdint-intn.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/stdint-uintn.h \
|
||||
/usr/local/cuda-12.6/include/cuda_runtime_api.h \
|
||||
/usr/local/cuda-12.6/include/crt/host_defines.h \
|
||||
/usr/local/cuda-12.6/include/builtin_types.h \
|
||||
/usr/local/cuda-12.6/include/device_types.h \
|
||||
/usr/local/cuda-12.6/include/driver_types.h \
|
||||
/usr/local/cuda-12.6/include/vector_types.h \
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/include/limits.h \
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/include/syslimits.h \
|
||||
/usr/include/limits.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/posix1_lim.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/local_lim.h \
|
||||
/usr/include/linux/limits.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/pthread_stack_min-dynamic.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/posix2_lim.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/xopen_lim.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/uio_lim.h \
|
||||
/usr/local/cuda-12.6/include/surface_types.h \
|
||||
/usr/local/cuda-12.6/include/texture_types.h \
|
||||
/usr/local/cuda-12.6/include/cuda_device_runtime_api.h \
|
||||
/usr/include/aarch64-linux-gnu/NvInferRuntime.h \
|
||||
/usr/include/aarch64-linux-gnu/NvInferImpl.h \
|
||||
/usr/include/aarch64-linux-gnu/NvInferRuntimeCommon.h \
|
||||
/usr/include/aarch64-linux-gnu/NvInferRuntimePlugin.h \
|
||||
/usr/include/c++/11/iostream \
|
||||
/usr/include/c++/11/ostream \
|
||||
/usr/include/c++/11/ios \
|
||||
/usr/include/c++/11/iosfwd \
|
||||
/usr/include/c++/11/bits/stringfwd.h \
|
||||
/usr/include/c++/11/bits/memoryfwd.h \
|
||||
/usr/include/c++/11/bits/postypes.h \
|
||||
/usr/include/c++/11/cwchar \
|
||||
/usr/include/wchar.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/floatn.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/floatn-common.h \
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/include/stdarg.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/wint_t.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/mbstate_t.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__mbstate_t.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__FILE.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/FILE.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/locale_t.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__locale_t.h \
|
||||
/usr/include/c++/11/exception \
|
||||
/usr/include/c++/11/bits/exception.h \
|
||||
/usr/include/c++/11/bits/exception_ptr.h \
|
||||
/usr/include/c++/11/bits/exception_defines.h \
|
||||
/usr/include/c++/11/bits/cxxabi_init_exception.h \
|
||||
/usr/include/c++/11/typeinfo \
|
||||
/usr/include/c++/11/bits/hash_bytes.h \
|
||||
/usr/include/c++/11/new \
|
||||
/usr/include/c++/11/bits/move.h \
|
||||
/usr/include/c++/11/type_traits \
|
||||
/usr/include/c++/11/bits/nested_exception.h \
|
||||
/usr/include/c++/11/bits/char_traits.h \
|
||||
/usr/include/c++/11/bits/stl_algobase.h \
|
||||
/usr/include/c++/11/bits/functexcept.h \
|
||||
/usr/include/c++/11/bits/cpp_type_traits.h \
|
||||
/usr/include/c++/11/ext/type_traits.h \
|
||||
/usr/include/c++/11/ext/numeric_traits.h \
|
||||
/usr/include/c++/11/bits/stl_pair.h \
|
||||
/usr/include/c++/11/bits/stl_iterator_base_types.h \
|
||||
/usr/include/c++/11/bits/stl_iterator_base_funcs.h \
|
||||
/usr/include/c++/11/bits/concept_check.h \
|
||||
/usr/include/c++/11/debug/assertions.h \
|
||||
/usr/include/c++/11/bits/stl_iterator.h \
|
||||
/usr/include/c++/11/bits/ptr_traits.h \
|
||||
/usr/include/c++/11/debug/debug.h \
|
||||
/usr/include/c++/11/bits/predefined_ops.h \
|
||||
/usr/include/c++/11/bits/localefwd.h \
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/c++locale.h \
|
||||
/usr/include/c++/11/clocale \
|
||||
/usr/include/locale.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/locale.h \
|
||||
/usr/include/c++/11/cctype \
|
||||
/usr/include/ctype.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/endian.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/endianness.h \
|
||||
/usr/include/c++/11/bits/ios_base.h \
|
||||
/usr/include/c++/11/ext/atomicity.h \
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/gthr.h \
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/gthr-default.h \
|
||||
/usr/include/pthread.h \
|
||||
/usr/include/sched.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/time_t.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_timespec.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/sched.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_sched_param.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/cpu-set.h \
|
||||
/usr/include/time.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/time.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/timex.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_timeval.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/clock_t.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_tm.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/clockid_t.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/timer_t.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_itimerspec.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/pthreadtypes.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/thread-shared-types.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/pthreadtypes-arch.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/atomic_wide_counter.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/struct_mutex.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/struct_rwlock.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/setjmp.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__sigset_t.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct___jmp_buf_tag.h \
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/atomic_word.h \
|
||||
/usr/include/aarch64-linux-gnu/sys/single_threaded.h \
|
||||
/usr/include/c++/11/bits/locale_classes.h \
|
||||
/usr/include/c++/11/string \
|
||||
/usr/include/c++/11/bits/allocator.h \
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/c++allocator.h \
|
||||
/usr/include/c++/11/ext/new_allocator.h \
|
||||
/usr/include/c++/11/bits/ostream_insert.h \
|
||||
/usr/include/c++/11/bits/cxxabi_forced.h \
|
||||
/usr/include/c++/11/bits/stl_function.h \
|
||||
/usr/include/c++/11/backward/binders.h \
|
||||
/usr/include/c++/11/bits/range_access.h \
|
||||
/usr/include/c++/11/initializer_list \
|
||||
/usr/include/c++/11/bits/basic_string.h \
|
||||
/usr/include/c++/11/ext/alloc_traits.h \
|
||||
/usr/include/c++/11/bits/alloc_traits.h \
|
||||
/usr/include/c++/11/bits/stl_construct.h \
|
||||
/usr/include/c++/11/string_view \
|
||||
/usr/include/c++/11/bits/functional_hash.h \
|
||||
/usr/include/c++/11/bits/string_view.tcc \
|
||||
/usr/include/c++/11/ext/string_conversions.h \
|
||||
/usr/include/c++/11/cstdlib \
|
||||
/usr/include/stdlib.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/waitflags.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/waitstatus.h \
|
||||
/usr/include/aarch64-linux-gnu/sys/types.h \
|
||||
/usr/include/endian.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/byteswap.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/uintn-identity.h \
|
||||
/usr/include/aarch64-linux-gnu/sys/select.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/select.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/sigset_t.h \
|
||||
/usr/include/alloca.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/stdlib-float.h \
|
||||
/usr/include/c++/11/bits/std_abs.h \
|
||||
/usr/include/c++/11/cstdio \
|
||||
/usr/include/stdio.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__fpos_t.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__fpos64_t.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_FILE.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/cookie_io_functions_t.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/stdio_lim.h \
|
||||
/usr/include/c++/11/cerrno \
|
||||
/usr/include/errno.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/errno.h \
|
||||
/usr/include/linux/errno.h \
|
||||
/usr/include/aarch64-linux-gnu/asm/errno.h \
|
||||
/usr/include/asm-generic/errno.h \
|
||||
/usr/include/asm-generic/errno-base.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/types/error_t.h \
|
||||
/usr/include/c++/11/bits/charconv.h \
|
||||
/usr/include/c++/11/bits/basic_string.tcc \
|
||||
/usr/include/c++/11/bits/locale_classes.tcc \
|
||||
/usr/include/c++/11/system_error \
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/error_constants.h \
|
||||
/usr/include/c++/11/stdexcept \
|
||||
/usr/include/c++/11/streambuf \
|
||||
/usr/include/c++/11/bits/streambuf.tcc \
|
||||
/usr/include/c++/11/bits/basic_ios.h \
|
||||
/usr/include/c++/11/bits/locale_facets.h \
|
||||
/usr/include/c++/11/cwctype \
|
||||
/usr/include/wctype.h \
|
||||
/usr/include/aarch64-linux-gnu/bits/wctype-wchar.h \
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/ctype_base.h \
|
||||
/usr/include/c++/11/bits/streambuf_iterator.h \
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/ctype_inline.h \
|
||||
/usr/include/c++/11/bits/locale_facets.tcc \
|
||||
/usr/include/c++/11/bits/basic_ios.tcc \
|
||||
/usr/include/c++/11/bits/ostream.tcc \
|
||||
/usr/include/c++/11/istream \
|
||||
/usr/include/c++/11/bits/istream.tcc \
|
||||
/usr/include/c++/11/mutex \
|
||||
/usr/include/c++/11/tuple \
|
||||
/usr/include/c++/11/utility \
|
||||
/usr/include/c++/11/bits/stl_relops.h \
|
||||
/usr/include/c++/11/array \
|
||||
/usr/include/c++/11/bits/uses_allocator.h \
|
||||
/usr/include/c++/11/bits/invoke.h \
|
||||
/usr/include/c++/11/chrono \
|
||||
/usr/include/c++/11/ratio \
|
||||
/usr/include/c++/11/limits \
|
||||
/usr/include/c++/11/ctime \
|
||||
/usr/include/c++/11/bits/parse_numbers.h \
|
||||
/usr/include/c++/11/bits/std_mutex.h \
|
||||
/usr/include/c++/11/bits/unique_lock.h
|
||||
|
||||
|
||||
/usr/include/c++/11/bits/unique_lock.h:
|
||||
|
||||
/usr/include/c++/11/bits/std_mutex.h:
|
||||
|
||||
/usr/include/c++/11/bits/parse_numbers.h:
|
||||
|
||||
/usr/include/c++/11/bits/uses_allocator.h:
|
||||
|
||||
/usr/include/c++/11/array:
|
||||
|
||||
/usr/include/c++/11/bits/stl_relops.h:
|
||||
|
||||
/usr/include/c++/11/mutex:
|
||||
|
||||
/usr/include/c++/11/istream:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/ctype_inline.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/ctype_base.h:
|
||||
|
||||
/usr/include/wctype.h:
|
||||
|
||||
/usr/include/c++/11/cwctype:
|
||||
|
||||
/usr/include/c++/11/bits/locale_facets.h:
|
||||
|
||||
/usr/include/c++/11/bits/basic_ios.h:
|
||||
|
||||
/usr/include/c++/11/stdexcept:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/error_constants.h:
|
||||
|
||||
/usr/include/c++/11/bits/locale_classes.tcc:
|
||||
|
||||
/usr/include/c++/11/bits/basic_string.tcc:
|
||||
|
||||
/usr/include/asm-generic/errno.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/error_t.h:
|
||||
|
||||
/usr/include/linux/errno.h:
|
||||
|
||||
/usr/include/c++/11/utility:
|
||||
|
||||
/usr/include/errno.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/stdio_lim.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/wctype-wchar.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_FILE.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__fpos64_t.h:
|
||||
|
||||
/usr/include/c++/11/bits/streambuf.tcc:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__fpos_t.h:
|
||||
|
||||
/usr/include/stdio.h:
|
||||
|
||||
/usr/include/c++/11/bits/std_abs.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/sigset_t.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/sys/select.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/uintn-identity.h:
|
||||
|
||||
/usr/include/endian.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/sys/types.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/waitstatus.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/waitflags.h:
|
||||
|
||||
/usr/include/stdlib.h:
|
||||
|
||||
/usr/include/c++/11/bits/functional_hash.h:
|
||||
|
||||
/usr/include/c++/11/string_view:
|
||||
|
||||
/usr/include/c++/11/bits/stl_construct.h:
|
||||
|
||||
/usr/include/c++/11/bits/alloc_traits.h:
|
||||
|
||||
/usr/include/c++/11/bits/basic_string.h:
|
||||
|
||||
/usr/include/c++/11/bits/stl_function.h:
|
||||
|
||||
/usr/include/c++/11/ext/alloc_traits.h:
|
||||
|
||||
/usr/include/c++/11/bits/cxxabi_forced.h:
|
||||
|
||||
/usr/include/c++/11/bits/ostream_insert.h:
|
||||
|
||||
/usr/include/c++/11/ext/new_allocator.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/c++allocator.h:
|
||||
|
||||
/usr/include/c++/11/bits/locale_classes.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/sys/single_threaded.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/atomic_word.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct___jmp_buf_tag.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__sigset_t.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/pthreadtypes-arch.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/thread-shared-types.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_itimerspec.h:
|
||||
|
||||
/usr/include/c++/11/iosfwd:
|
||||
|
||||
/usr/include/c++/11/ios:
|
||||
|
||||
/usr/include/c++/11/chrono:
|
||||
|
||||
/usr/include/c++/11/cstdio:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/stdint-uintn.h:
|
||||
|
||||
/usr/include/c++/11/ostream:
|
||||
|
||||
/usr/include/c++/11/system_error:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/gnu/stubs-lp64.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/NvInferRuntime.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/uio_lim.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/xopen_lim.h:
|
||||
|
||||
/usr/include/c++/11/bits/invoke.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/posix2_lim.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/struct_rwlock.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/pthread_stack_min-dynamic.h:
|
||||
|
||||
/usr/include/c++/11/bits/exception.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/sched.h:
|
||||
|
||||
/usr/include/c++/11/bits/ostream.tcc:
|
||||
|
||||
/usr/include/c++/11/clocale:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/timer_t.h:
|
||||
|
||||
/usr/include/c++/11/bits/istream.tcc:
|
||||
|
||||
/usr/include/limits.h:
|
||||
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/include/syslimits.h:
|
||||
|
||||
/usr/local/cuda-12.6/include/vector_types.h:
|
||||
|
||||
/usr/include/c++/11/bits/predefined_ops.h:
|
||||
|
||||
/usr/local/cuda-12.6/include/driver_types.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/pthreadtypes.h:
|
||||
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/include/limits.h:
|
||||
|
||||
/usr/include/c++/11/cstdint:
|
||||
|
||||
/usr/include/c++/11/string:
|
||||
|
||||
/usr/local/cuda-12.6/include/device_types.h:
|
||||
|
||||
/usr/include/features-time64.h:
|
||||
|
||||
/usr/local/cuda-12.6/include/crt/host_defines.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/wchar.h:
|
||||
|
||||
/usr/include/features.h:
|
||||
|
||||
/usr/include/c++/11/ext/numeric_traits.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/os_defines.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/clock_t.h:
|
||||
|
||||
/usr/include/c++/11/limits:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/cpu_defines.h:
|
||||
|
||||
/usr/include/locale.h:
|
||||
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/include/stddef.h:
|
||||
|
||||
/usr/include/c++/11/bits/locale_facets.tcc:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/stdint-intn.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/gnu/stubs.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/cookie_io_functions_t.h:
|
||||
|
||||
/usr/include/linux/limits.h:
|
||||
|
||||
/usr/include/stdint.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/long-double.h:
|
||||
|
||||
/usr/include/c++/11/ext/string_conversions.h:
|
||||
|
||||
/usr/include/c++/11/bits/exception_ptr.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/byteswap.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/NvInferRuntimeBase.h:
|
||||
|
||||
/usr/include/c++/11/bits/concept_check.h:
|
||||
|
||||
/usr/include/c++/11/ratio:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/libc-header-start.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/NvInfer.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/NvInferLegacyDims.h:
|
||||
|
||||
../../src/trt_logger.cpp:
|
||||
|
||||
/usr/local/cuda-12.6/include/builtin_types.h:
|
||||
|
||||
/usr/include/asm-generic/errno-base.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/wordsize.h:
|
||||
|
||||
/usr/include/c++/11/bits/char_traits.h:
|
||||
|
||||
../../include/armor_yolo_detect/trt_logger.hpp:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_timespec.h:
|
||||
|
||||
/usr/include/c++/11/ctime:
|
||||
|
||||
/usr/local/cuda-12.6/include/cuda_device_runtime_api.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/select.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/timesize.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/setjmp.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/struct_mutex.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types.h:
|
||||
|
||||
/usr/include/c++/11/bits/range_access.h:
|
||||
|
||||
/usr/include/c++/11/cstddef:
|
||||
|
||||
/usr/include/c++/11/bits/stl_algobase.h:
|
||||
|
||||
/usr/include/c++/11/cwchar:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/NvInferRuntimeCommon.h:
|
||||
|
||||
/usr/include/c++/11/bits/nested_exception.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_tm.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/errno.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/c++config.h:
|
||||
|
||||
/usr/include/c++/11/tuple:
|
||||
|
||||
/usr/include/c++/11/type_traits:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/FILE.h:
|
||||
|
||||
/usr/include/stdc-predef.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/typesizes.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/atomic_wide_counter.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/gthr-default.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__mbstate_t.h:
|
||||
|
||||
/usr/include/c++/11/ext/type_traits.h:
|
||||
|
||||
/usr/local/cuda-12.6/include/texture_types.h:
|
||||
|
||||
/usr/include/alloca.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/time64.h:
|
||||
|
||||
/usr/include/c++/11/streambuf:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/stdlib-float.h:
|
||||
|
||||
/usr/include/c++/11/bits/functexcept.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/time.h:
|
||||
|
||||
/usr/include/c++/11/bits/stringfwd.h:
|
||||
|
||||
/usr/include/c++/11/bits/memoryfwd.h:
|
||||
|
||||
/usr/include/c++/11/bits/postypes.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/timex.h:
|
||||
|
||||
/usr/include/c++/11/backward/binders.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/posix1_lim.h:
|
||||
|
||||
/usr/include/c++/11/iostream:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/floatn.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/floatn-common.h:
|
||||
|
||||
/usr/include/c++/11/bits/string_view.tcc:
|
||||
|
||||
/usr/local/cuda-12.6/include/cuda_runtime_api.h:
|
||||
|
||||
/usr/include/c++/11/bits/hash_bytes.h:
|
||||
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/include/stdarg.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__locale_t.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/locale.h:
|
||||
|
||||
/usr/include/c++/11/bits/charconv.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/mbstate_t.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/__FILE.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/locale_t.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/sys/cdefs.h:
|
||||
|
||||
/usr/include/c++/11/exception:
|
||||
|
||||
/usr/include/c++/11/bits/exception_defines.h:
|
||||
|
||||
/usr/include/wchar.h:
|
||||
|
||||
/usr/include/c++/11/bits/cxxabi_init_exception.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/wint_t.h:
|
||||
|
||||
/usr/include/c++/11/typeinfo:
|
||||
|
||||
/usr/include/c++/11/bits/ptr_traits.h:
|
||||
|
||||
/usr/include/c++/11/bits/stl_iterator.h:
|
||||
|
||||
/usr/include/c++/11/new:
|
||||
|
||||
/usr/include/c++/11/bits/move.h:
|
||||
|
||||
/usr/include/pthread.h:
|
||||
|
||||
/usr/include/c++/11/bits/cpp_type_traits.h:
|
||||
|
||||
/usr/include/c++/11/bits/stl_pair.h:
|
||||
|
||||
/usr/include/c++/11/ext/atomicity.h:
|
||||
|
||||
/usr/include/c++/11/cstdlib:
|
||||
|
||||
/usr/include/c++/11/bits/stl_iterator_base_types.h:
|
||||
|
||||
/usr/include/c++/11/bits/stl_iterator_base_funcs.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/NvInferRuntimePlugin.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/endianness.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/local_lim.h:
|
||||
|
||||
/usr/include/ctype.h:
|
||||
|
||||
/usr/include/c++/11/debug/assertions.h:
|
||||
|
||||
/usr/include/c++/11/bits/localefwd.h:
|
||||
|
||||
/usr/include/c++/11/cerrno:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/c++locale.h:
|
||||
|
||||
/usr/include/c++/11/bits/streambuf_iterator.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/time_t.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/asm/errno.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/NvInferImpl.h:
|
||||
|
||||
/usr/include/c++/11/cctype:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/NvInferVersion.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/endian.h:
|
||||
|
||||
/usr/include/c++/11/bits/ios_base.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/c++/11/bits/gthr.h:
|
||||
|
||||
/usr/local/cuda-12.6/include/surface_types.h:
|
||||
|
||||
/usr/include/sched.h:
|
||||
|
||||
/usr/include/c++/11/debug/debug.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_sched_param.h:
|
||||
|
||||
/usr/include/c++/11/bits/basic_ios.tcc:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/cpu-set.h:
|
||||
|
||||
/usr/lib/gcc/aarch64-linux-gnu/11/include/stdint.h:
|
||||
|
||||
/usr/include/time.h:
|
||||
|
||||
/usr/include/c++/11/initializer_list:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/struct_timeval.h:
|
||||
|
||||
/usr/include/c++/11/bits/allocator.h:
|
||||
|
||||
/usr/include/c++/11/pstl/pstl_config.h:
|
||||
|
||||
/usr/include/aarch64-linux-gnu/bits/types/clockid_t.h:
|
||||
@@ -0,0 +1,2 @@
|
||||
# CMAKE generated file: DO NOT EDIT!
|
||||
# Timestamp file for compiler generated dependencies management for armor_yolo_detect.
|
||||
@@ -0,0 +1,2 @@
|
||||
# Empty dependencies file for armor_yolo_detect.
|
||||
# This may be replaced when dependencies are built.
|
||||
@@ -0,0 +1,10 @@
|
||||
# CMAKE generated file: DO NOT EDIT!
|
||||
# Generated by "Unix Makefiles" Generator, CMake Version 3.22
|
||||
|
||||
# compile CXX with /usr/bin/c++
|
||||
CXX_DEFINES = -DDEFAULT_RMW_IMPLEMENTATION=rmw_fastrtps_cpp -DFMT_LOCALE -DFMT_SHARED -DRCUTILS_ENABLE_FAULT_INJECTION -Darmor_yolo_detect_EXPORTS
|
||||
|
||||
CXX_INCLUDES = -I/home/jetson/yq_2026/src/rm_auto_aim/armor_yolo_detect/include -I/usr/local/cuda-12.6/include -isystem /opt/ros/humble/include/rclcpp -isystem /opt/ros/humble/include/rclcpp_components -isystem /opt/ros/humble/include/sensor_msgs -isystem /opt/ros/humble/include/geometry_msgs -isystem /opt/ros/humble/include/std_srvs -isystem /opt/ros/humble/include/visualization_msgs -isystem /opt/ros/humble/include/cv_bridge -isystem /opt/ros/humble/include/image_transport -isystem /opt/ros/humble/include/tf2 -isystem /opt/ros/humble/include/tf2_ros -isystem /opt/ros/humble/include/tf2_geometry_msgs -isystem /usr/include/opencv4 -isystem /usr/include/eigen3 -isystem /opt/ros/humble/include/ament_index_cpp -isystem /opt/ros/humble/include/libstatistics_collector -isystem /opt/ros/humble/include/builtin_interfaces -isystem /opt/ros/humble/include/rosidl_runtime_c -isystem /opt/ros/humble/include/rcutils -isystem /opt/ros/humble/include/rosidl_typesupport_interface -isystem /opt/ros/humble/include/fastcdr -isystem /opt/ros/humble/include/rosidl_runtime_cpp -isystem /opt/ros/humble/include/rosidl_typesupport_fastrtps_cpp -isystem /opt/ros/humble/include/rmw -isystem /opt/ros/humble/include/rosidl_typesupport_fastrtps_c -isystem /opt/ros/humble/include/rosidl_typesupport_introspection_c -isystem /opt/ros/humble/include/rosidl_typesupport_introspection_cpp -isystem /opt/ros/humble/include/rcl -isystem /opt/ros/humble/include/rcl_interfaces -isystem /opt/ros/humble/include/rcl_logging_interface -isystem /opt/ros/humble/include/rcl_yaml_param_parser -isystem /opt/ros/humble/include/libyaml_vendor -isystem /opt/ros/humble/include/tracetools -isystem /opt/ros/humble/include/rcpputils -isystem /opt/ros/humble/include/statistics_msgs -isystem /opt/ros/humble/include/rosgraph_msgs -isystem /opt/ros/humble/include/rosidl_typesupport_cpp -isystem /opt/ros/humble/include/rosidl_typesupport_c -isystem /opt/ros/humble/include/class_loader -isystem /opt/ros/humble/include/composition_interfaces -isystem /opt/ros/humble/include/std_msgs -isystem /opt/ros/humble/include/message_filters -isystem /opt/ros/humble/include/rclcpp_action -isystem /opt/ros/humble/include/action_msgs -isystem /opt/ros/humble/include/unique_identifier_msgs -isystem /opt/ros/humble/include/rcl_action -isystem /opt/ros/humble/include/tf2_msgs
|
||||
|
||||
CXX_FLAGS = -fPIC -std=gnu++17
|
||||
|
||||
@@ -0,0 +1,6 @@
|
||||
CMAKE_PROGRESS_1 = 1
|
||||
CMAKE_PROGRESS_2 = 2
|
||||
CMAKE_PROGRESS_3 = 3
|
||||
CMAKE_PROGRESS_4 = 4
|
||||
CMAKE_PROGRESS_5 = 5
|
||||
|
||||