first commit
5
.gitignore
vendored
Normal file
@ -0,0 +1,5 @@
|
||||
build
|
||||
install
|
||||
log
|
||||
.vscode
|
||||
deb_build
|
||||
148
README.md
Normal file
@ -0,0 +1,148 @@
|
||||
# 清扫车 ROS2 控制与定位消息接口
|
||||
|
||||
## 1. 文档概述
|
||||
|
||||
清扫车 ROS2 控制与定位消息接口
|
||||
|
||||
## 2. 依赖环境
|
||||
|
||||
### 2.1 系统环境
|
||||
|
||||
* **ROS2 版本**:Foxy
|
||||
* **Ubuntu 版本**:20.04
|
||||
|
||||
### 2.2 .deb 的安装、启动与卸载
|
||||
|
||||
在目标机器上执行安装:
|
||||
|
||||
```bash
|
||||
sudo dpkg -i controller_XXXX_arm64.deb
|
||||
```
|
||||
|
||||
安装完成后主要文件路径:
|
||||
|
||||
工作空间:/opt/controller/
|
||||
|
||||
启动脚本:/opt/controller/start_all.sh
|
||||
|
||||
CAN 配置脚本:/opt/controller/can.sh
|
||||
|
||||
日志文件:/var/log/controller/controller.log
|
||||
|
||||
systemd 服务:
|
||||
|
||||
CAN 配置服务:/etc/systemd/system/controller-can.service
|
||||
|
||||
ROS2 节点服务:/etc/systemd/system/controller.service
|
||||
|
||||
安装后,CAN 配置服务会先运行,确保 can0 接口可用,然后 ROS2 节点服务会启动。
|
||||
|
||||
|
||||
手动启动 ROS2 节点:
|
||||
```bash
|
||||
sudo systemctl start controller.service
|
||||
```
|
||||
|
||||
重启服务:
|
||||
```bash
|
||||
sudo systemctl restart controller.service
|
||||
```
|
||||
|
||||
启动 CAN 配置服务(通常自动执行,不需要手动):
|
||||
```bash
|
||||
sudo systemctl start controller-can.service
|
||||
```
|
||||
|
||||
查看运行状态
|
||||
```bash
|
||||
sudo systemctl status controller.service
|
||||
sudo systemctl status controller-can.service
|
||||
```
|
||||
|
||||
实时查看最新日志:
|
||||
```bash
|
||||
tail -f /var/log/controller/controller.log
|
||||
```
|
||||
|
||||
也可以使用 journalctl 查看 systemd 输出:
|
||||
```bash
|
||||
sudo journalctl -u controller.service -f
|
||||
```
|
||||
|
||||
旧日志会自动轮转,由 logrotate 管理,每天生成一个历史日志,历史日志会压缩 .gz,默认保留最近 14 天日志
|
||||
|
||||
轮转后的文件示例:
|
||||
```bash
|
||||
/var/log/controller/controller.log # 当天日志
|
||||
/var/log/controller/controller.log-20250923.gz # 历史压缩日志
|
||||
```
|
||||
|
||||
停止服务
|
||||
```bash
|
||||
sudo systemctl stop controller.service
|
||||
sudo systemctl stop controller-can.service
|
||||
```
|
||||
|
||||
禁用开机自启
|
||||
```bash
|
||||
sudo systemctl disable controller.service
|
||||
sudo systemctl disable controller-can.service
|
||||
```
|
||||
|
||||
卸载 deb 包
|
||||
```bash
|
||||
sudo dpkg -r controller
|
||||
```
|
||||
|
||||
卸载包后 日志文件会保留,便于调试。
|
||||
|
||||
## 3. 消息(msg)文件详情
|
||||
|
||||
### 3.1 McCtrl.msg(车辆控制指令消息)
|
||||
|
||||
|
||||
#### 字段定义
|
||||
|
||||
|
||||
|
||||
| 字段类型 | 字段名称 | 取值范围 / 说明 | 功能描述 |
|
||||
| -------- | ------------------------------- | ----------------------------------------------- | ------------------------------------------------------------ |
|
||||
| uint8 | brake | 0(不刹)、1(刹) | 电磁刹控制:0 表示解除电磁刹,1 表示激活电磁刹 |
|
||||
| uint8 | gear | 0(空挡)、1(后退)、2(前进)、3(保留) | 车辆挡位控制,3 为预留挡位暂未使用 |
|
||||
| uint8 | rpm | 0-4000 | 电机转速指令,数值直接对应实际电机转速(rpm) |
|
||||
| float32 | angle | \[-40.0, 40.0] | 轮端转向角度控制,单位为度(°),[-左、+右] |
|
||||
| uint16 | angle\_speed | 120-1500 | 转向角速度控制,单位为 rpm |
|
||||
| bool | sweep | true(清扫)、false(不清扫) | 清扫 |
|
||||
|
||||
|
||||
#### 对应 Topic
|
||||
|
||||
|
||||
|
||||
* **Topic**:`/auto_mc_ctrl`
|
||||
|
||||
|
||||
|
||||
### 3.2 Rtk.msg(RTK 定位信息消息)
|
||||
|
||||
|
||||
#### 字段定义
|
||||
|
||||
|
||||
|
||||
| 字段类型 | 字段名称 | 取值范围 / 说明 | 功能描述 |
|
||||
| -------- | ---------- | ----------------------------------------- | ------------------------------------------------------------ |
|
||||
| float64 | lat | 无固定范围(符合 WGS84 坐标系经纬度格式) | 车辆所在位置的纬度 |
|
||||
| float64 | lon | 无固定范围(符合 WGS84 坐标系经纬度格式) | 车辆所在位置的经度 |
|
||||
| float32 | head | 0-360 | 车辆航向角(单位:度),0° 表示正北方向,顺时针递增 |
|
||||
| float32 | speed | | |
|
||||
| int32 | p\_quality | 0-9 | 定位解状态<br /> 0初始化, 1单点定位, 2码差分, 3无效PPS, 4固定解, 5浮点解, 6正在估算, 7,人工输入固定值, 8模拟模式, 9WAAS差分;<br /> 固定解是最优解 |
|
||||
| int32 | h\_quality | 0-9 | 定向解状态<br /> 0初始化, 1单点定位, 2码差分, 3无效PPS, 4固定解, 5浮点解, 6正在估算, 7,人工输入固定值, 8模拟模式, 9WAAS差分;<br /> 固定解是最优解 |
|
||||
|
||||
#### 对应 Topic
|
||||
|
||||
|
||||
|
||||
* **Topic**:`/rtk_message`
|
||||
|
||||
|
||||
33
can.sh
Executable file
@ -0,0 +1,33 @@
|
||||
#!/bin/bash
|
||||
# Script: can.sh
|
||||
# Description: Configures CAN interface can0 on startup
|
||||
|
||||
# Check if running as root
|
||||
if [[ $EUID -ne 0 ]]; then
|
||||
echo "This script must be run as root"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
# Disable CAN interface can0 if it's up
|
||||
if ip link show can0 &> /dev/null; then
|
||||
ip link set can0 down
|
||||
fi
|
||||
|
||||
# Load necessary kernel modules
|
||||
modprobe can
|
||||
modprobe can_raw
|
||||
modprobe mttcan
|
||||
|
||||
# Configure CAN interface can0 with bitrate 250000
|
||||
ip link set can0 type can bitrate 500000
|
||||
ip link set up can0
|
||||
|
||||
# Check the return status of the last command
|
||||
if [[ $? -ne 0 ]]; then
|
||||
echo "Error configuring CAN interface can0"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
echo "CAN interface can0 configured successfully"
|
||||
exit 0
|
||||
|
||||
29
config.json
Normal file
@ -0,0 +1,29 @@
|
||||
{
|
||||
"mqtt": {
|
||||
"vid": "V060003",
|
||||
"upload_url": "https://qsc.ntiov.com:8443/api/sys/route/upload",
|
||||
"download_url_pre": "http://36.153.162.171:9510/api/ccp-web/file/",
|
||||
"inter_net_address": "tcp://192.168.4.196",
|
||||
"inter_net_port": 11883,
|
||||
"external_net_address": "tcp://36.153.162.171",
|
||||
"external_net_port": 19683,
|
||||
"mqtt_user": "zxwl",
|
||||
"mqtt_password": "zxwl1234@",
|
||||
"pub_gps_topic": "/zxwl/vehicle/V060003/gps",
|
||||
"remote_topic": "/zxwl/vehicle/V060003/ctrl",
|
||||
"mqtt_topic_push_status": "/zxwl/vehicle/V060003/task/status",
|
||||
"mqtt_topic_sub_task": "/zxwl/vehicle/V060003/task"
|
||||
},
|
||||
"detect_line_tolerance": 3.06,
|
||||
"detect_head_tolerance": 2,
|
||||
"lidar_detect_locate": {
|
||||
"front": 5,
|
||||
"f_front": 18,
|
||||
"rear": -8,
|
||||
"r_rear": -16,
|
||||
"left": -6,
|
||||
"l_left": -13,
|
||||
"right": 6,
|
||||
"r_right": 13
|
||||
}
|
||||
}
|
||||
BIN
controller_202509290926_arm64.deb
Normal file
96
gps_load_now.txt
Normal file
@ -0,0 +1,96 @@
|
||||
32.0311468570
|
||||
120.91525671300
|
||||
358.096008
|
||||
0.000000
|
||||
32.0311563730
|
||||
120.91525624100
|
||||
354.798004
|
||||
0.000000
|
||||
32.0311655490
|
||||
120.91525493600
|
||||
347.576996
|
||||
0.000000
|
||||
32.0311743100
|
||||
120.91525172600
|
||||
332.431000
|
||||
0.000000
|
||||
32.0311818630
|
||||
120.91524556200
|
||||
313.209991
|
||||
0.000000
|
||||
32.0311872560
|
||||
120.91523692500
|
||||
291.302002
|
||||
0.000000
|
||||
32.0311895010
|
||||
120.91522644400
|
||||
273.058014
|
||||
0.000000
|
||||
32.0311897810
|
||||
120.91521522700
|
||||
268.415009
|
||||
0.000000
|
||||
32.0311893590
|
||||
120.91520456100
|
||||
264.153992
|
||||
0.000000
|
||||
32.0311880140
|
||||
120.91519349600
|
||||
256.733002
|
||||
0.000000
|
||||
32.0311854800
|
||||
120.91518299200
|
||||
247.852005
|
||||
0.000000
|
||||
32.0311813510
|
||||
120.91517328200
|
||||
235.455994
|
||||
0.000000
|
||||
32.0311754410
|
||||
120.91516488300
|
||||
219.582001
|
||||
0.000000
|
||||
32.0311677300
|
||||
120.91515878500
|
||||
201.425995
|
||||
0.000000
|
||||
32.0311588910
|
||||
120.91515602500
|
||||
183.102005
|
||||
0.000000
|
||||
32.0311498140
|
||||
120.91515571600
|
||||
178.761002
|
||||
0.000000
|
||||
32.0311408050
|
||||
120.91515620700
|
||||
172.496002
|
||||
0.000000
|
||||
32.0311313060
|
||||
120.91515857400
|
||||
158.169998
|
||||
0.000000
|
||||
32.0311232530
|
||||
120.91516330100
|
||||
142.091995
|
||||
0.000000
|
||||
32.0311168570
|
||||
120.91517109100
|
||||
123.244003
|
||||
0.000000
|
||||
32.0311126890
|
||||
120.91518064100
|
||||
104.664001
|
||||
0.000000
|
||||
32.0311106850
|
||||
120.91519129000
|
||||
97.190002
|
||||
0.000000
|
||||
32.0311099930
|
||||
120.91520212400
|
||||
89.829002
|
||||
0.000000
|
||||
32.0311102590
|
||||
120.91521279400
|
||||
85.438004
|
||||
0.000000
|
||||
194
make_deb.sh
Executable file
@ -0,0 +1,194 @@
|
||||
#!/usr/bin/env bash
|
||||
set -euo pipefail
|
||||
|
||||
PKG_NAME="controller"
|
||||
PKG_VERSION="$(date +%Y%m%d%H%M)"
|
||||
ARCH="arm64"
|
||||
MAINTAINER="LYQ<liyq@ntiov.com>"
|
||||
DESCRIPTION="Binary package of remote controller nodes for robot (ROS2 foxy)."
|
||||
INSTALL_DIR="/opt/${PKG_NAME}"
|
||||
WORKDIR="$(pwd)/deb_build"
|
||||
INSTALL_SRC="$(pwd)/install"
|
||||
|
||||
# 清理工作目录
|
||||
rm -rf "${WORKDIR}"
|
||||
mkdir -p "${WORKDIR}/${INSTALL_DIR}"
|
||||
mkdir -p "${WORKDIR}/DEBIAN"
|
||||
|
||||
# 复制 ROS2 install 文件
|
||||
cp -a "${INSTALL_SRC}/." "${WORKDIR}/${INSTALL_DIR}/"
|
||||
|
||||
# control 文件
|
||||
cat > "${WORKDIR}/DEBIAN/control" <<EOF
|
||||
Package: ${PKG_NAME}
|
||||
Version: ${PKG_VERSION}
|
||||
Section: misc
|
||||
Priority: optional
|
||||
Architecture: ${ARCH}
|
||||
Essential: no
|
||||
Maintainer: ${MAINTAINER}
|
||||
Depends: ros-foxy-ros-base, logrotate
|
||||
Description: ${DESCRIPTION}
|
||||
EOF
|
||||
|
||||
# ============================
|
||||
# 创建 can.sh (root 执行)
|
||||
# ============================
|
||||
cat > "${WORKDIR}/${INSTALL_DIR}/can.sh" <<'EOF'
|
||||
#!/bin/bash
|
||||
# Script: can.sh
|
||||
# Description: Configures CAN interface can0 on startup
|
||||
|
||||
if [[ $EUID -ne 0 ]]; then
|
||||
echo "This script must be run as root"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
if ip link show can0 &> /dev/null; then
|
||||
ip link set can0 down
|
||||
fi
|
||||
|
||||
modprobe can
|
||||
modprobe can_raw
|
||||
modprobe mttcan
|
||||
|
||||
ip link set can0 type can bitrate 500000
|
||||
ip link set up can0
|
||||
|
||||
if [[ $? -ne 0 ]]; then
|
||||
echo "Error configuring CAN interface can0"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
echo "CAN interface can0 configured successfully"
|
||||
exit 0
|
||||
EOF
|
||||
|
||||
chmod +x "${WORKDIR}/${INSTALL_DIR}/can.sh"
|
||||
|
||||
# ============================
|
||||
# 创建 start_all.sh (aiec 用户执行)
|
||||
# ============================
|
||||
cat > "${WORKDIR}/${INSTALL_DIR}/start_all.sh" <<EOF
|
||||
#!/bin/bash
|
||||
set -e
|
||||
|
||||
# 加载 ROS2 系统环境
|
||||
source /opt/ros/foxy/setup.bash
|
||||
|
||||
# 加载打包的工作空间环境
|
||||
source ${INSTALL_DIR}/local_setup.bash
|
||||
|
||||
# 启动多个节点
|
||||
ros2 run radio_ctrl radio_ctrl_node &
|
||||
ros2 run mc mc_node &
|
||||
ros2 run ctrl_arbiter ctrl_arbiter_node &
|
||||
ros2 run mqtt_report mqtt_report_node &
|
||||
# ros2 run rtk rtk_node &
|
||||
# ros2 run pub_gps pub_gps_node &
|
||||
|
||||
wait
|
||||
EOF
|
||||
chmod +x "${WORKDIR}/${INSTALL_DIR}/start_all.sh"
|
||||
|
||||
# ============================
|
||||
# systemd 服务目录
|
||||
# ============================
|
||||
mkdir -p "${WORKDIR}/etc/systemd/system"
|
||||
|
||||
# CAN 配置服务 (root 执行)
|
||||
cat > "${WORKDIR}/etc/systemd/system/${PKG_NAME}-can.service" <<EOF
|
||||
[Unit]
|
||||
Description=Configure CAN interface can0
|
||||
After=network.target
|
||||
|
||||
[Service]
|
||||
Type=oneshot
|
||||
ExecStart=${INSTALL_DIR}/can.sh
|
||||
RemainAfterExit=yes
|
||||
User=root
|
||||
|
||||
[Install]
|
||||
WantedBy=multi-user.target
|
||||
EOF
|
||||
|
||||
# ROS2 节点服务 (aiec 用户执行,日志写文件)
|
||||
cat > "${WORKDIR}/etc/systemd/system/${PKG_NAME}.service" <<EOF
|
||||
[Unit]
|
||||
Description=Remote Controller Nodes
|
||||
After=network.target ${PKG_NAME}-can.service
|
||||
Requires=${PKG_NAME}-can.service
|
||||
|
||||
[Service]
|
||||
Type=simple
|
||||
User=aiec
|
||||
Environment="ROS_DISTRO=foxy"
|
||||
ExecStart=${INSTALL_DIR}/start_all.sh
|
||||
Restart=on-failure
|
||||
RestartSec=2
|
||||
StandardOutput=append:/var/log/${PKG_NAME}/${PKG_NAME}.log
|
||||
StandardError=append:/var/log/${PKG_NAME}/${PKG_NAME}.log
|
||||
|
||||
[Install]
|
||||
WantedBy=multi-user.target
|
||||
EOF
|
||||
|
||||
# ============================
|
||||
# logrotate 配置
|
||||
# ============================
|
||||
mkdir -p "${WORKDIR}/etc/logrotate.d"
|
||||
cat > "${WORKDIR}/etc/logrotate.d/${PKG_NAME}" <<EOF
|
||||
/var/log/${PKG_NAME}/${PKG_NAME}.log {
|
||||
daily
|
||||
rotate 14
|
||||
compress
|
||||
missingok
|
||||
notifempty
|
||||
copytruncate
|
||||
dateext
|
||||
dateformat -%Y%m%d
|
||||
}
|
||||
EOF
|
||||
|
||||
# ============================
|
||||
# postinst 启用服务
|
||||
# ============================
|
||||
cat > "${WORKDIR}/DEBIAN/postinst" <<EOF
|
||||
#!/bin/bash
|
||||
set -e
|
||||
|
||||
# 创建日志目录
|
||||
mkdir -p /var/log/${PKG_NAME}
|
||||
chown aiec:aiec /var/log/${PKG_NAME}
|
||||
|
||||
systemctl daemon-reload
|
||||
systemctl enable ${PKG_NAME}-can.service
|
||||
systemctl enable ${PKG_NAME}.service
|
||||
|
||||
exit 0
|
||||
EOF
|
||||
chmod 755 "${WORKDIR}/DEBIAN/postinst"
|
||||
|
||||
# ============================
|
||||
# postrm 停用服务
|
||||
# ============================
|
||||
cat > "${WORKDIR}/DEBIAN/postrm" <<EOF
|
||||
#!/bin/bash
|
||||
set -e
|
||||
|
||||
systemctl stop ${PKG_NAME}.service || true
|
||||
systemctl disable ${PKG_NAME}.service || true
|
||||
systemctl stop ${PKG_NAME}-can.service || true
|
||||
systemctl disable ${PKG_NAME}-can.service || true
|
||||
systemctl daemon-reload
|
||||
|
||||
exit 0
|
||||
EOF
|
||||
chmod 755 "${WORKDIR}/DEBIAN/postrm"
|
||||
|
||||
# ============================
|
||||
# 构建 deb 包
|
||||
# ============================
|
||||
dpkg-deb --build "${WORKDIR}" "${PKG_NAME}_${PKG_VERSION}_${ARCH}.deb"
|
||||
|
||||
echo "生成 ${PKG_NAME}_${PKG_VERSION}_${ARCH}.deb"
|
||||
7
prepare.sh
Executable file
@ -0,0 +1,7 @@
|
||||
#!/bin/bash
|
||||
|
||||
sudo ./can.sh
|
||||
|
||||
sudo chmod 777 /dev/ttyTHS0
|
||||
|
||||
sudo ip route add 36.153.162.0/24 via 192.168.5.1 dev eth4
|
||||
190
ros2_nodes.sh
Executable file
@ -0,0 +1,190 @@
|
||||
#!/bin/bash
|
||||
###############################################################################
|
||||
# ros2_nodes.sh
|
||||
# 一键启动 / 停止 / 重启 / 状态查询 6 个 ROS 2 节点(或仅核心 4 节点)
|
||||
# 用法:
|
||||
# ./ros2_nodes.sh start # 默认启动全部 6 节点
|
||||
# ./ros2_nodes.sh start all # 同上
|
||||
# ./ros2_nodes.sh start core # 仅启动 4 个核心节点
|
||||
# ./ros2_nodes.sh stop # 停止
|
||||
# ./ros2_nodes.sh restart [core] # 重启(可选 core / all)
|
||||
# ./ros2_nodes.sh status # 查看状态
|
||||
# ./ros2_nodes.sh rotate # 手动轮换日志
|
||||
###############################################################################
|
||||
|
||||
##== 基本路径与环境 ===========================================================
|
||||
WORKSPACE_PATH="/home/nvidia/Downloads/sweeper_whu"
|
||||
source "$WORKSPACE_PATH/install/setup.bash"
|
||||
|
||||
##== 日志目录与轮换配置 =======================================================
|
||||
LOG_DIR="/var/log/ros2"
|
||||
MAX_LOG_SIZE="10M" # 单个日志大小
|
||||
MAX_LOG_FILES=5 # 保留文件数
|
||||
|
||||
##== 节点命令列表 ==============================================================
|
||||
|
||||
# 1) 全量 6 节点(键名 = 节点标识 , 值 = 启动命令)
|
||||
declare -A NODES_ALL=(
|
||||
["mc"]="ros2 run mc mc_node"
|
||||
["radio_ctrl"]="ros2 run radio_ctrl radio_ctrl_node"
|
||||
["ctrl_arbiter"]="ros2 run ctrl_arbiter ctrl_arbiter_node"
|
||||
["mqtt_report"]="ros2 run mqtt_report mqtt_report_node"
|
||||
["rtk"]="ros2 run rtk rtk_node"
|
||||
["pub_gps"]="ros2 run pub_gps pub_gps_node"
|
||||
)
|
||||
|
||||
# 2) 核心节点名称数组(便于 core 模式筛选)
|
||||
CORE_NAMES=(mc radio_ctrl ctrl_arbiter mqtt_report)
|
||||
|
||||
##== 函数 =====================================================================
|
||||
|
||||
# 预启动环境准备:CAN、USB 权限、日志目录与 logrotate
|
||||
setup_environment() {
|
||||
echo "[INFO] 设置 CAN0 波特率为 500K..."
|
||||
sudo ip link set can0 down 2>/dev/null
|
||||
sudo ip link set can0 type can bitrate 500000
|
||||
sudo ip link set can0 up
|
||||
echo "[INFO] CAN0 配置完成。"
|
||||
|
||||
echo "[INFO] 设置 /dev/ttyUSB0 权限为 777..."
|
||||
sudo chmod 777 /dev/ttyUSB0
|
||||
echo "[INFO] ttyUSB0 权限设置完成。"
|
||||
|
||||
echo "[INFO] 设置 /dev/ttyTHS1 权限为 777..."
|
||||
sudo chmod 777 /dev/ttyTHS1
|
||||
echo "[INFO] ttyTHS1 权限设置完成。"
|
||||
|
||||
# 日志目录
|
||||
echo "[INFO] 创建日志目录: $LOG_DIR"
|
||||
sudo mkdir -p "$LOG_DIR"
|
||||
sudo chown -R nvidia:nvidia "$LOG_DIR"
|
||||
|
||||
# logrotate 配置
|
||||
local LOGROTATE_CONF="/etc/logrotate.d/ros2_nodes"
|
||||
echo "[INFO] 配置 logrotate: $LOGROTATE_CONF"
|
||||
sudo bash -c "cat > $LOGROTATE_CONF" <<EOF
|
||||
$LOG_DIR/*.log {
|
||||
su nvidia nvidia
|
||||
daily
|
||||
maxsize $MAX_LOG_SIZE
|
||||
rotate $MAX_LOG_FILES
|
||||
missingok
|
||||
notifempty
|
||||
compress
|
||||
delaycompress
|
||||
sharedscripts
|
||||
copytruncate
|
||||
}
|
||||
EOF
|
||||
}
|
||||
|
||||
# 启动节点:start_nodes [core|all]
|
||||
start_nodes() {
|
||||
local mode=${1:-all} # 默认 all
|
||||
setup_environment
|
||||
|
||||
# 选择节点集合
|
||||
local names=()
|
||||
if [[ "$mode" == "core" ]]; then
|
||||
names=("${CORE_NAMES[@]}")
|
||||
else
|
||||
names=("${!NODES_ALL[@]}")
|
||||
fi
|
||||
|
||||
echo "[INFO] 启动模式: $mode"
|
||||
echo "[INFO] 节点列表: ${names[*]}"
|
||||
echo "[INFO] 每个节点启动间隔 0.1s"
|
||||
|
||||
for name in "${names[@]}"; do
|
||||
echo "[START] $name"
|
||||
local log_file="${LOG_DIR}/${name}.log"
|
||||
|
||||
#=====================================================================
|
||||
${NODES_ALL[$name]} >> "$log_file" 2>&1 &
|
||||
# gnome-terminal --title="$name" \
|
||||
# -- bash -c "source $WORKSPACE_PATH/install/setup.bash && ${NODES_ALL[$name]}; exec bash" &
|
||||
#=====================================================================
|
||||
|
||||
local pid=$!
|
||||
echo $pid > "/tmp/$name.pid"
|
||||
echo "[INFO] $name PID: $pid | 日志: $log_file"
|
||||
|
||||
sleep 0.1 # 每个节点之间暂停 0.1 秒
|
||||
done
|
||||
|
||||
echo "[INFO] 所有节点已启动 (${mode})."
|
||||
}
|
||||
|
||||
# 停止全部正在运行的节点
|
||||
stop_nodes() {
|
||||
echo "[INFO] 停止 ROS 2 节点..."
|
||||
for pidfile in /tmp/*.pid; do
|
||||
[ -e "$pidfile" ] || continue
|
||||
local name=$(basename "$pidfile" .pid)
|
||||
local pid=$(cat "$pidfile")
|
||||
if ps -p "$pid" > /dev/null 2>&1; then
|
||||
kill -SIGINT "$pid" && echo "[STOP] $name (PID $pid) - 发送 SIGINT"
|
||||
local timeout=5
|
||||
while kill -0 "$pid" 2>/dev/null && [ $timeout -gt 0 ]; do
|
||||
sleep 0.5; ((timeout--))
|
||||
done
|
||||
if kill -0 "$pid" 2>/dev/null; then
|
||||
kill -9 "$pid" && echo "[STOP] $name (PID $pid) - 强制终止"
|
||||
fi
|
||||
fi
|
||||
rm -f "$pidfile"
|
||||
done
|
||||
echo "[INFO] 所有节点已停止。"
|
||||
}
|
||||
|
||||
# 手动触发日志轮换
|
||||
rotate_logs() {
|
||||
echo "[INFO] 手动轮换日志..."
|
||||
sudo logrotate -f /etc/logrotate.d/ros2_nodes
|
||||
echo "[INFO] 日志轮换完成。"
|
||||
}
|
||||
|
||||
# 查看节点运行状态
|
||||
show_status() {
|
||||
echo "[INFO] 节点状态:"
|
||||
for name in "${!NODES_ALL[@]}"; do
|
||||
if [ -f "/tmp/$name.pid" ]; then
|
||||
local pid=$(cat "/tmp/$name.pid")
|
||||
if ps -p "$pid" > /dev/null 2>&1; then
|
||||
echo "[RUNNING] $name (PID $pid)"
|
||||
else
|
||||
echo "[DEAD] $name (PID $pid)"
|
||||
fi
|
||||
else
|
||||
echo "[STOPPED] $name"
|
||||
fi
|
||||
done
|
||||
}
|
||||
|
||||
##== 主入口 ===================================================================
|
||||
|
||||
case "$1" in
|
||||
start)
|
||||
# 用法: ./ros2_nodes.sh start [core|all]
|
||||
start_nodes "${2:-all}"
|
||||
;;
|
||||
stop)
|
||||
stop_nodes
|
||||
;;
|
||||
restart)
|
||||
stop_nodes
|
||||
sleep 1
|
||||
start_nodes "${2:-all}"
|
||||
;;
|
||||
rotate)
|
||||
rotate_logs
|
||||
;;
|
||||
status)
|
||||
show_status
|
||||
;;
|
||||
*)
|
||||
echo "Usage: $0 {start|stop|restart|rotate|status} [core|all]"
|
||||
echo " core : 仅启动 4 个核心节点 (mc radio_ctrl ctrl_arbiter mqtt_report)"
|
||||
echo " all : 启动全部 6 个节点 (默认)"
|
||||
;;
|
||||
esac
|
||||
44
routes/gps_load_1761208243532.txt
Normal file
@ -0,0 +1,44 @@
|
||||
32.0311442390
|
||||
120.91525759600
|
||||
358.131012
|
||||
0.000000
|
||||
32.0311534830
|
||||
120.91525806000
|
||||
10.571000
|
||||
0.000000
|
||||
32.0311624300
|
||||
120.91526160300
|
||||
30.403999
|
||||
0.000000
|
||||
32.0311698350
|
||||
120.91526811100
|
||||
42.812000
|
||||
0.000000
|
||||
32.0311764320
|
||||
120.91527574000
|
||||
45.012001
|
||||
0.000000
|
||||
32.0311827500
|
||||
120.91528336200
|
||||
45.269001
|
||||
0.000000
|
||||
32.0311892690
|
||||
120.91529116800
|
||||
46.345001
|
||||
0.000000
|
||||
32.0311954980
|
||||
120.91529957900
|
||||
54.297001
|
||||
0.000000
|
||||
32.0312002620
|
||||
120.91530907900
|
||||
66.992996
|
||||
0.000000
|
||||
32.0312030070
|
||||
120.91531955100
|
||||
80.920998
|
||||
0.000000
|
||||
32.0312029590
|
||||
120.91530925500
|
||||
78.594002
|
||||
0.000000
|
||||
68
routes/gps_load_1761367443087.txt
Normal file
@ -0,0 +1,68 @@
|
||||
32.0311017640
|
||||
120.91525757800
|
||||
352.238007
|
||||
0.000000
|
||||
32.0311108500
|
||||
120.91525573000
|
||||
349.462006
|
||||
0.000000
|
||||
32.0311198770
|
||||
120.91525398500
|
||||
348.104004
|
||||
0.000000
|
||||
32.0311290760
|
||||
120.91525266500
|
||||
356.882996
|
||||
0.000000
|
||||
32.0311383690
|
||||
120.91525232600
|
||||
1.130000
|
||||
0.000000
|
||||
32.0311478450
|
||||
120.91525275400
|
||||
2.373000
|
||||
0.000000
|
||||
32.0311569190
|
||||
120.91525367400
|
||||
9.031000
|
||||
0.000000
|
||||
32.0311658220
|
||||
120.91525588000
|
||||
16.469999
|
||||
0.000000
|
||||
32.0311748260
|
||||
120.91525988700
|
||||
25.517000
|
||||
0.000000
|
||||
32.0311828180
|
||||
120.91526533400
|
||||
36.137001
|
||||
0.000000
|
||||
32.0311902300
|
||||
120.91527240700
|
||||
45.061001
|
||||
0.000000
|
||||
32.0311962480
|
||||
120.91528038700
|
||||
55.247002
|
||||
0.000000
|
||||
32.0312010270
|
||||
120.91528964500
|
||||
64.734001
|
||||
0.000000
|
||||
32.0312043320
|
||||
120.91530032000
|
||||
77.070000
|
||||
0.000000
|
||||
32.0312057240
|
||||
120.91531159000
|
||||
82.500999
|
||||
0.000000
|
||||
32.0312068290
|
||||
120.91532278200
|
||||
83.804001
|
||||
0.000000
|
||||
32.0312077120
|
||||
120.91533411500
|
||||
87.883003
|
||||
0.000000
|
||||
96
routes/gps_load_1761367875670.txt
Normal file
@ -0,0 +1,96 @@
|
||||
32.0311468570
|
||||
120.91525671300
|
||||
358.096008
|
||||
0.000000
|
||||
32.0311563730
|
||||
120.91525624100
|
||||
354.798004
|
||||
0.000000
|
||||
32.0311655490
|
||||
120.91525493600
|
||||
347.576996
|
||||
0.000000
|
||||
32.0311743100
|
||||
120.91525172600
|
||||
332.431000
|
||||
0.000000
|
||||
32.0311818630
|
||||
120.91524556200
|
||||
313.209991
|
||||
0.000000
|
||||
32.0311872560
|
||||
120.91523692500
|
||||
291.302002
|
||||
0.000000
|
||||
32.0311895010
|
||||
120.91522644400
|
||||
273.058014
|
||||
0.000000
|
||||
32.0311897810
|
||||
120.91521522700
|
||||
268.415009
|
||||
0.000000
|
||||
32.0311893590
|
||||
120.91520456100
|
||||
264.153992
|
||||
0.000000
|
||||
32.0311880140
|
||||
120.91519349600
|
||||
256.733002
|
||||
0.000000
|
||||
32.0311854800
|
||||
120.91518299200
|
||||
247.852005
|
||||
0.000000
|
||||
32.0311813510
|
||||
120.91517328200
|
||||
235.455994
|
||||
0.000000
|
||||
32.0311754410
|
||||
120.91516488300
|
||||
219.582001
|
||||
0.000000
|
||||
32.0311677300
|
||||
120.91515878500
|
||||
201.425995
|
||||
0.000000
|
||||
32.0311588910
|
||||
120.91515602500
|
||||
183.102005
|
||||
0.000000
|
||||
32.0311498140
|
||||
120.91515571600
|
||||
178.761002
|
||||
0.000000
|
||||
32.0311408050
|
||||
120.91515620700
|
||||
172.496002
|
||||
0.000000
|
||||
32.0311313060
|
||||
120.91515857400
|
||||
158.169998
|
||||
0.000000
|
||||
32.0311232530
|
||||
120.91516330100
|
||||
142.091995
|
||||
0.000000
|
||||
32.0311168570
|
||||
120.91517109100
|
||||
123.244003
|
||||
0.000000
|
||||
32.0311126890
|
||||
120.91518064100
|
||||
104.664001
|
||||
0.000000
|
||||
32.0311106850
|
||||
120.91519129000
|
||||
97.190002
|
||||
0.000000
|
||||
32.0311099930
|
||||
120.91520212400
|
||||
89.829002
|
||||
0.000000
|
||||
32.0311102590
|
||||
120.91521279400
|
||||
85.438004
|
||||
0.000000
|
||||
54
run.sh
Executable file
@ -0,0 +1,54 @@
|
||||
#!/bin/bash
|
||||
|
||||
source install/setup.bash # ros workspace
|
||||
{
|
||||
gnome-terminal --title="radio" --tab "XXD_ros" -- bash -c "ros2 run radio_ctrl radio_ctrl_node"
|
||||
}&
|
||||
sleep 0.2s
|
||||
|
||||
{
|
||||
gnome-terminal --title="mc" --tab "XXD_ros" -- bash -c "ros2 run mc mc_node"
|
||||
}&
|
||||
sleep 0.2s
|
||||
|
||||
{
|
||||
gnome-terminal --title="ctrl_arbiter" --tab "XXD_ros" -- bash -c "ros2 run ctrl_arbiter ctrl_arbiter_node"
|
||||
}&
|
||||
sleep 0.2s
|
||||
|
||||
{
|
||||
gnome-terminal --title="report" --tab "XXD_ros" -- bash -c "ros2 run mqtt_report mqtt_report_node"
|
||||
}&
|
||||
sleep 0.2s
|
||||
|
||||
{
|
||||
gnome-terminal --title="lidar" --tab "XXD_ros" -- bash -c "ros2 launch rslidar_sdk start_double.launch.py"
|
||||
}&
|
||||
sleep 0.1s
|
||||
{
|
||||
gnome-terminal --title="rtk" --tab "XXD_ros" -- bash -c "ros2 run rtk rtk_node"
|
||||
}&
|
||||
sleep 0.1s
|
||||
{
|
||||
gnome-terminal --title="route" --tab "XXD_ros" -- bash -c "ros2 run route route_node"
|
||||
}&
|
||||
sleep 0.1s
|
||||
{
|
||||
gnome-terminal --title="sub" --tab "XXD_ros" -- bash -c "ros2 run sub sub_node"
|
||||
}&
|
||||
sleep 0.1s
|
||||
{
|
||||
gnome-terminal --title="task_manager" --tab "XXD_ros" -- bash -c "ros2 run task_manager task_manager_node"
|
||||
}&
|
||||
sleep 0.1s
|
||||
{
|
||||
gnome-terminal --title="pl" --tab "XXD_ros" -- bash -c "ros2 run pl pl_node"
|
||||
}&
|
||||
sleep 0.1s
|
||||
{
|
||||
gnome-terminal --title="fu" --tab "XXD_ros" -- bash -c "ros2 launch fu fu.launch.py"
|
||||
}
|
||||
sleep 0.1s
|
||||
{
|
||||
gnome-terminal --title="pub_gps" --tab "XXD_ros" -- bash -c "ros2 run pub_gps pub_gps_node"
|
||||
}
|
||||
41
src/airy/rslidar_msg-master/CMakeLists.txt
Normal file
@ -0,0 +1,41 @@
|
||||
cmake_minimum_required(VERSION 3.5)
|
||||
project(rslidar_msg)
|
||||
|
||||
# Default to C99
|
||||
if(NOT CMAKE_C_STANDARD)
|
||||
set(CMAKE_C_STANDARD 99)
|
||||
endif()
|
||||
|
||||
# Default to C++14
|
||||
if(NOT CMAKE_CXX_STANDARD)
|
||||
set(CMAKE_CXX_STANDARD 14)
|
||||
endif()
|
||||
|
||||
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
|
||||
add_compile_options(-Wall -Wextra -Wpedantic)
|
||||
endif()
|
||||
|
||||
# find dependencies
|
||||
find_package(ament_cmake REQUIRED)
|
||||
find_package(std_msgs REQUIRED)
|
||||
find_package(rclcpp REQUIRED)
|
||||
find_package(builtin_interfaces REQUIRED)
|
||||
find_package(rosidl_default_generators REQUIRED)
|
||||
|
||||
rosidl_generate_interfaces(${PROJECT_NAME}
|
||||
"msg/RslidarPacket.msg"
|
||||
DEPENDENCIES builtin_interfaces std_msgs
|
||||
)
|
||||
|
||||
if(BUILD_TESTING)
|
||||
find_package(ament_lint_auto REQUIRED)
|
||||
# the following line skips the linter which checks for copyrights
|
||||
# uncomment the line when a copyright and license is not present in all source files
|
||||
#set(ament_cmake_copyright_FOUND TRUE)
|
||||
# the following line skips cpplint (only works in a git repo)
|
||||
# uncomment the line when this package is not in a git repo
|
||||
#set(ament_cmake_cpplint_FOUND TRUE)
|
||||
ament_lint_auto_find_test_dependencies()
|
||||
endif()
|
||||
|
||||
ament_package()
|
||||
19
src/airy/rslidar_msg-master/LICENSE
Normal file
@ -0,0 +1,19 @@
|
||||
Copyright (c) 2020 RoboSense
|
||||
All rights reserved
|
||||
|
||||
By downloading, copying, installing or using the software you agree to this license. If you do not agree to this license, do not download, install, copy or use the software.
|
||||
|
||||
License Agreement
|
||||
For RoboSense LiDAR SDK Library
|
||||
(3-clause BSD License)
|
||||
|
||||
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
|
||||
|
||||
1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
|
||||
|
||||
2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
|
||||
|
||||
3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used to endorse or promote products derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
|
||||
5
src/airy/rslidar_msg-master/README.md
Normal file
@ -0,0 +1,5 @@
|
||||
## ROS2 LiDAR Packet Message
|
||||
|
||||
|
||||
|
||||
**This project is the custom LiDAR packet message in ROS2 environment. User need to put this project and rslidar_sdk in same workspace to compile.**
|
||||
4
src/airy/rslidar_msg-master/msg/RslidarPacket.msg
Normal file
@ -0,0 +1,4 @@
|
||||
std_msgs/Header header
|
||||
uint8 is_difop
|
||||
uint8 is_frame_begin
|
||||
uint8[] data
|
||||
29
src/airy/rslidar_msg-master/package.xml
Normal file
@ -0,0 +1,29 @@
|
||||
<?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>rslidar_msg</name>
|
||||
<version>0.0.0</version>
|
||||
<description>ros msgs for the rslidar_sdk project</description>
|
||||
<maintainer email="zdxiao@robosense.cn">robosense</maintainer>
|
||||
<license>BSD</license>
|
||||
|
||||
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||
|
||||
<depend>std_msgs</depend>
|
||||
<depend>rclcpp</depend>
|
||||
|
||||
<test_depend>ament_lint_auto</test_depend>
|
||||
<test_depend>ament_lint_common</test_depend>
|
||||
|
||||
<build_depend>builtin_interfaces</build_depend>
|
||||
|
||||
<exec_depend>builtin_interfaces</exec_depend>
|
||||
<build_depend>rosidl_default_generators</build_depend>
|
||||
|
||||
<exec_depend>rosidl_default_runtime</exec_depend>
|
||||
|
||||
<member_of_group>rosidl_interface_packages</member_of_group>
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
</export>
|
||||
</package>
|
||||
41
src/airy/rslidar_msg-master/ros1/CMakeLists.txt
Normal file
@ -0,0 +1,41 @@
|
||||
cmake_minimum_required(VERSION 3.5)
|
||||
project(rslidar_msg)
|
||||
|
||||
# Default to C99
|
||||
if(NOT CMAKE_C_STANDARD)
|
||||
set(CMAKE_C_STANDARD 99)
|
||||
endif()
|
||||
|
||||
# Default to C++14
|
||||
if(NOT CMAKE_CXX_STANDARD)
|
||||
set(CMAKE_CXX_STANDARD 14)
|
||||
endif()
|
||||
|
||||
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
|
||||
add_compile_options(-Wall -Wextra -Wpedantic)
|
||||
endif()
|
||||
|
||||
# find dependencies
|
||||
find_package(std_msgs REQUIRED)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
roscpp
|
||||
std_msgs
|
||||
sensor_msgs
|
||||
message_generation
|
||||
)
|
||||
|
||||
add_message_files(FILES
|
||||
RslidarPacket.msg
|
||||
)
|
||||
|
||||
generate_messages(DEPENDENCIES
|
||||
std_msgs
|
||||
sensor_msgs
|
||||
)
|
||||
|
||||
catkin_package(CATKIN_DEPENDS
|
||||
std_msgs
|
||||
sensor_msgs
|
||||
message_runtime
|
||||
)
|
||||
22
src/airy/rslidar_msg-master/ros1/package.xml
Normal file
@ -0,0 +1,22 @@
|
||||
<?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>rslidar_msg</name>
|
||||
<version>0.0.0</version>
|
||||
<description>ros msgs for the rslidar_sdk project</description>
|
||||
<maintainer email="zdxiao@robosense.cn">robosense</maintainer>
|
||||
<license>BSD</license>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
|
||||
<build_depend>roscpp</build_depend>
|
||||
<build_depend>std_msgs</build_depend>
|
||||
<build_depend>sensor_msgs</build_depend>
|
||||
<build_depend>message_generation</build_depend>
|
||||
|
||||
<exec_depend>roscpp</exec_depend>
|
||||
<exec_depend>std_msgs</exec_depend>
|
||||
<exec_depend>sensor_msgs</exec_depend>
|
||||
<exec_depend>message_runtime</exec_depend>
|
||||
|
||||
</package>
|
||||
41
src/airy/rslidar_msg-master/ros2/CMakeLists.txt
Normal file
@ -0,0 +1,41 @@
|
||||
cmake_minimum_required(VERSION 3.5)
|
||||
project(rslidar_msg)
|
||||
|
||||
# Default to C99
|
||||
if(NOT CMAKE_C_STANDARD)
|
||||
set(CMAKE_C_STANDARD 99)
|
||||
endif()
|
||||
|
||||
# Default to C++14
|
||||
if(NOT CMAKE_CXX_STANDARD)
|
||||
set(CMAKE_CXX_STANDARD 14)
|
||||
endif()
|
||||
|
||||
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
|
||||
add_compile_options(-Wall -Wextra -Wpedantic)
|
||||
endif()
|
||||
|
||||
# find dependencies
|
||||
find_package(ament_cmake REQUIRED)
|
||||
find_package(std_msgs REQUIRED)
|
||||
find_package(rclcpp REQUIRED)
|
||||
find_package(builtin_interfaces REQUIRED)
|
||||
find_package(rosidl_default_generators REQUIRED)
|
||||
|
||||
rosidl_generate_interfaces(${PROJECT_NAME}
|
||||
"msg/RslidarPacket.msg"
|
||||
DEPENDENCIES builtin_interfaces std_msgs
|
||||
)
|
||||
|
||||
if(BUILD_TESTING)
|
||||
find_package(ament_lint_auto REQUIRED)
|
||||
# the following line skips the linter which checks for copyrights
|
||||
# uncomment the line when a copyright and license is not present in all source files
|
||||
#set(ament_cmake_copyright_FOUND TRUE)
|
||||
# the following line skips cpplint (only works in a git repo)
|
||||
# uncomment the line when this package is not in a git repo
|
||||
#set(ament_cmake_cpplint_FOUND TRUE)
|
||||
ament_lint_auto_find_test_dependencies()
|
||||
endif()
|
||||
|
||||
ament_package()
|
||||
29
src/airy/rslidar_msg-master/ros2/package.xml
Normal file
@ -0,0 +1,29 @@
|
||||
<?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>rslidar_msg</name>
|
||||
<version>0.0.0</version>
|
||||
<description>ros msgs for the rslidar_sdk project</description>
|
||||
<maintainer email="zdxiao@robosense.cn">robosense</maintainer>
|
||||
<license>BSD</license>
|
||||
|
||||
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||
|
||||
<depend>std_msgs</depend>
|
||||
<depend>rclcpp</depend>
|
||||
|
||||
<test_depend>ament_lint_auto</test_depend>
|
||||
<test_depend>ament_lint_common</test_depend>
|
||||
|
||||
<build_depend>builtin_interfaces</build_depend>
|
||||
|
||||
<exec_depend>builtin_interfaces</exec_depend>
|
||||
<build_depend>rosidl_default_generators</build_depend>
|
||||
|
||||
<exec_depend>rosidl_default_runtime</exec_depend>
|
||||
|
||||
<member_of_group>rosidl_interface_packages</member_of_group>
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
</export>
|
||||
</package>
|
||||
66
src/airy/rslidar_sdk-main/.clang-format
Normal file
@ -0,0 +1,66 @@
|
||||
---
|
||||
BasedOnStyle: Google
|
||||
AccessModifierOffset: -2
|
||||
ConstructorInitializerIndentWidth: 2
|
||||
AlignEscapedNewlinesLeft: false
|
||||
AlignTrailingComments: true
|
||||
AllowAllParametersOfDeclarationOnNextLine: false
|
||||
AllowShortIfStatementsOnASingleLine: false
|
||||
AllowShortLoopsOnASingleLine: false
|
||||
AllowShortFunctionsOnASingleLine: None
|
||||
AllowShortLoopsOnASingleLine: false
|
||||
AlwaysBreakTemplateDeclarations: true
|
||||
AlwaysBreakBeforeMultilineStrings: false
|
||||
BreakBeforeBinaryOperators: false
|
||||
BreakBeforeTernaryOperators: false
|
||||
BreakConstructorInitializersBeforeComma: true
|
||||
BinPackParameters: true
|
||||
ColumnLimit: 120
|
||||
ConstructorInitializerAllOnOneLineOrOnePerLine: true
|
||||
DerivePointerBinding: false
|
||||
PointerBindsToType: true
|
||||
ExperimentalAutoDetectBinPacking: false
|
||||
IndentCaseLabels: true
|
||||
MaxEmptyLinesToKeep: 1
|
||||
NamespaceIndentation: None
|
||||
ObjCSpaceBeforeProtocolList: true
|
||||
PenaltyBreakBeforeFirstCallParameter: 19
|
||||
PenaltyBreakComment: 60
|
||||
PenaltyBreakString: 1
|
||||
PenaltyBreakFirstLessLess: 1000
|
||||
PenaltyExcessCharacter: 1000
|
||||
PenaltyReturnTypeOnItsOwnLine: 90
|
||||
SpacesBeforeTrailingComments: 2
|
||||
Cpp11BracedListStyle: false
|
||||
Standard: Auto
|
||||
IndentWidth: 2
|
||||
TabWidth: 2
|
||||
UseTab: Never
|
||||
IndentFunctionDeclarationAfterType: false
|
||||
SpacesInParentheses: false
|
||||
SpacesInAngles: false
|
||||
SpaceInEmptyParentheses: false
|
||||
SpacesInCStyleCastParentheses: false
|
||||
SpaceAfterControlStatementKeyword: true
|
||||
SpaceBeforeAssignmentOperators: true
|
||||
ContinuationIndentWidth: 4
|
||||
SortIncludes: false
|
||||
SpaceAfterCStyleCast: false
|
||||
|
||||
# Configure each individual brace in BraceWrapping
|
||||
BreakBeforeBraces: Custom
|
||||
|
||||
# Control of individual brace wrapping cases
|
||||
BraceWrapping: {
|
||||
AfterClass: 'true'
|
||||
AfterControlStatement: 'true'
|
||||
AfterEnum : 'true'
|
||||
AfterFunction : 'true'
|
||||
AfterNamespace : 'true'
|
||||
AfterStruct : 'true'
|
||||
AfterUnion : 'true'
|
||||
BeforeCatch : 'true'
|
||||
BeforeElse : 'true'
|
||||
IndentBraces : 'false'
|
||||
}
|
||||
...
|
||||
181
src/airy/rslidar_sdk-main/CHANGELOG.md
Normal file
@ -0,0 +1,181 @@
|
||||
# CHANGELOG
|
||||
|
||||
## v1.5.17 2025-02-14
|
||||
|
||||
### Added
|
||||
- Support RSAIRY.
|
||||
- Support parsing IMU data for RSAIRY and RSE1.
|
||||
- Support parsing IMU extrinsics parameters frome difop for RSAIRY.
|
||||
|
||||
### Changed
|
||||
- Add feature attribute to point type.
|
||||
- Updated config file.
|
||||
- Update help document.
|
||||
- Update block_time_offset as us for RSE1
|
||||
|
||||
### Fixed
|
||||
- Fix the issue of packets subscription failure under ros2.
|
||||
|
||||
|
||||
## v1.5.16 2024-08-27
|
||||
### Added
|
||||
- Load config path frome ros2 param.
|
||||
### Changed
|
||||
- Remove the original compilation method.
|
||||
### Fixed
|
||||
- Use single package.xml file for both ROS1 and ROS2 @Timple.
|
||||
- Update msop protocol of RSMX.
|
||||
|
||||
## v1.5.15 2024-08-07
|
||||
### Added
|
||||
- Support RSM3.
|
||||
|
||||
## v1.5.14 2024-07-15
|
||||
### Added
|
||||
- Support multiple lidars with different multicast addresses and the same port.
|
||||
### Fixed
|
||||
- Fixed the bug that only one lidar was parsed correctly when multiple bp4.0 were used.
|
||||
- Fix version number in the package.xml by @Timple.
|
||||
|
||||
## v1.5.13 2024-05-10
|
||||
### Added
|
||||
- Support RSMX.
|
||||
### Fixed
|
||||
- Update timestamp parsing unit and the number of packets per frame in decoder_RSE1.
|
||||
- Update firing_tss of Helios/Helios16P/RubyPlus.
|
||||
- Fix compilation bug of unit test.
|
||||
- Remove duplicate text "/rslidar_packets" by @luhuadong.
|
||||
|
||||
## v1.5.12 2023-12-28
|
||||
### Fixed
|
||||
- Fix bug in getting device info and status.
|
||||
- Fix bug in getting device temperature.
|
||||
|
||||
## v1.5.11 2023-12-18
|
||||
|
||||
### Changed
|
||||
- Enable modify socket buffer size.
|
||||
|
||||
## v1.5.10 - 2023-02-17
|
||||
|
||||
### Changed
|
||||
- Merge RSBPV4 into RSBP
|
||||
|
||||
|
||||
## v1.5.9 - 2023-02-17
|
||||
|
||||
### Changed
|
||||
- Increase sending DDS buffer queue to avoid packet loss
|
||||
|
||||
|
||||
## v1.5.8 - 2022-12-09
|
||||
|
||||
### Added
|
||||
- Support ROS2/Humble Hawksbill
|
||||
- rename RSEOS as RSE1
|
||||
|
||||
### Fixed
|
||||
- Fix wrong widthxheight while ros_send_by_rows=true
|
||||
|
||||
|
||||
## v1.5.7 - 2022-10-09
|
||||
|
||||
### Added
|
||||
- Seperate RSBPV4 from RSBP
|
||||
- Support to receive MSOP/DIFOP packet from rosbag v1.3.x
|
||||
- Support option ros_send_by_rows
|
||||
|
||||
## v1.5.6 - 2022-09-01
|
||||
|
||||
### Added
|
||||
+ Add a few build options according to rs_driver
|
||||
+ Update help documents
|
||||
|
||||
## v1.5.5 - 2022-08-01
|
||||
|
||||
### Changed
|
||||
- Output intensity in point cloud as float32
|
||||
|
||||
### Fixed
|
||||
- Fix compiling and runtime error on ROS2 Elequent
|
||||
- Fix frame_id in help docs
|
||||
|
||||
## v1.5.4 - 2022-07-01
|
||||
|
||||
### Added
|
||||
- Support the option to stamp the point cloud with the first point
|
||||
|
||||
### Changed
|
||||
- Remove the dependency on the protobuf library
|
||||
|
||||
## v1.5.3 - 2022-06-01
|
||||
|
||||
### Added
|
||||
- Support Jumbo Mode
|
||||
|
||||
### Fixed
|
||||
- Fix compiling error when protobuf is unavailable
|
||||
|
||||
## v1.5.0
|
||||
|
||||
### Changed
|
||||
- refactory the project
|
||||
|
||||
### Added
|
||||
- support user_layer_bytes and tail_layer_bytes
|
||||
- support M2
|
||||
- replace point with point cloud, as rs_driver's template parameter
|
||||
- handle point cloud in rs_driver's thread
|
||||
|
||||
## v1.3.0 - 2020-11-10
|
||||
|
||||
### Added
|
||||
|
||||
- Add multi-cast support
|
||||
- Add saved_by_rows argument
|
||||
- Add different point types( XYZI & XYZIRT)
|
||||
|
||||
### Changed
|
||||
- Update driver core, please refer to CHANGELOG in rs_driver for details
|
||||
- Update some documents
|
||||
- Change angle_path argument to hiding parameter
|
||||
|
||||
### Removed
|
||||
|
||||
- Remove RSAUTO for lidar type
|
||||
- Remove device_ip argument
|
||||
|
||||
## v1.2.1 - 2020-09-04
|
||||
|
||||
### Fixed
|
||||
- Fix bug in driver core, please refer to changelog in rs_driver for details.
|
||||
|
||||
## v1.2.0 - 2020-09-01
|
||||
|
||||
### Added
|
||||
- Add camera software trigger (base on target angle)
|
||||
|
||||
### Changed
|
||||
- Update driver core, please refer to changelog in rs_driver for details
|
||||
- Update the compiler version from C++11 to C++14
|
||||
|
||||
## v1.1.0 - 2020-07-01
|
||||
|
||||
### Added
|
||||
- Add ROS2 support
|
||||
|
||||
### Changed
|
||||
- Replace while loop with cv.wait
|
||||
- Update the vector copy part
|
||||
- Update the program structure
|
||||
|
||||
### Removed
|
||||
- Remove some unused variables in message struct
|
||||
|
||||
## v1.0.0 - 2020-06-01
|
||||
|
||||
### Added
|
||||
- New program structure
|
||||
- Support ROS & Protobuf-UDP functions
|
||||
|
||||
|
||||
210
src/airy/rslidar_sdk-main/CMakeLists.txt
Normal file
@ -0,0 +1,210 @@
|
||||
cmake_minimum_required(VERSION 3.5)
|
||||
cmake_policy(SET CMP0048 NEW)
|
||||
project(rslidar_sdk)
|
||||
|
||||
#=======================================
|
||||
# Custom Point Type (XYZI,XYZIRT, XYZIF, XYZIRTF)
|
||||
#=======================================
|
||||
set(POINT_TYPE XYZI)
|
||||
|
||||
option(ENABLE_TRANSFORM "Enable transform functions" OFF)
|
||||
if(${ENABLE_TRANSFORM})
|
||||
add_definitions("-DENABLE_TRANSFORM")
|
||||
find_package(Eigen3 REQUIRED)
|
||||
include_directories(${EIGEN3_INCLUDE_DIR})
|
||||
endif(${ENABLE_TRANSFORM})
|
||||
|
||||
option(ENABLE_EPOLL_RECEIVE "Receive packets with epoll() instead of select()" OFF)
|
||||
if(${ENABLE_EPOLL_RECEIVE})
|
||||
add_definitions("-DENABLE_EPOLL_RECEIVE")
|
||||
endif(${ENABLE_EPOLL_RECEIVE})
|
||||
|
||||
option(ENABLE_MODIFY_RECVBUF "Enable modify size of RECVBUF" ON)
|
||||
if(${ENABLE_MODIFY_RECVBUF})
|
||||
add_definitions("-DENABLE_MODIFY_RECVBUF")
|
||||
endif(${ENABLE_MODIFY_RECVBUF})
|
||||
|
||||
option(ENABLE_WAIT_IF_QUEUE_EMPTY "Enable waiting for a while in handle thread if the queue is empty" OFF)
|
||||
if(${ENABLE_WAIT_IF_QUEUE_EMPTY})
|
||||
add_definitions("-DENABLE_WAIT_IF_QUEUE_EMPTY")
|
||||
endif(${ENABLE_WAIT_IF_QUEUE_EMPTY})
|
||||
|
||||
option(ENABLE_DIFOP_PARSE "Enable parsing DIFOP Packet" ON)
|
||||
if(${ENABLE_DIFOP_PARSE})
|
||||
add_definitions("-DENABLE_DIFOP_PARSE")
|
||||
endif(${ENABLE_DIFOP_PARSE})
|
||||
|
||||
option(ENABLE_STAMP_WITH_LOCAL "Enable stamp point cloud with local time" OFF)
|
||||
if(${ENABLE_STAMP_WITH_LOCAL})
|
||||
add_definitions("-DENABLE_STAMP_WITH_LOCAL")
|
||||
endif(${ENABLE_STAMP_WITH_LOCAL})
|
||||
|
||||
|
||||
option(ENABLE_SOURCE_PACKET_LEGACY "Enable ROS Source of MSOP/DIFOP Packet v1.3.x" OFF)
|
||||
if(${ENABLE_SOURCE_PACKET_LEGACY})
|
||||
add_definitions("-DENABLE_SOURCE_PACKET_LEGACY")
|
||||
endif(${ENABLE_SOURCE_PACKET_LEGACY})
|
||||
|
||||
option(ENABLE_IMU_DATA_PARSE "Enable imu data parse" OFF)
|
||||
if(${ENABLE_IMU_DATA_PARSE})
|
||||
|
||||
message(=============================================================)
|
||||
message("-- Enable imu data parse")
|
||||
message(=============================================================)
|
||||
|
||||
add_definitions("-DENABLE_IMU_DATA_PARSE")
|
||||
|
||||
endif(${ENABLE_IMU_DATA_PARSE})
|
||||
|
||||
#========================
|
||||
# Project details / setup
|
||||
#========================
|
||||
set(PROJECT_NAME rslidar_sdk)
|
||||
|
||||
add_definitions(-DPROJECT_PATH="${PROJECT_SOURCE_DIR}")
|
||||
|
||||
if (CMAKE_BUILD_TYPE STREQUAL "")
|
||||
set(CMAKE_BUILD_TYPE Release)
|
||||
add_definitions(-O3)
|
||||
endif()
|
||||
|
||||
add_definitions(-std=c++17)
|
||||
add_compile_options(-Wall)
|
||||
|
||||
#========================
|
||||
# Point Type Definition
|
||||
#========================
|
||||
if(${POINT_TYPE} STREQUAL "XYZI")
|
||||
add_definitions(-DPOINT_TYPE_XYZI)
|
||||
elseif(${POINT_TYPE} STREQUAL "XYZIRT")
|
||||
add_definitions(-DPOINT_TYPE_XYZIRT)
|
||||
elseif(${POINT_TYPE} STREQUAL "XYZIF")
|
||||
add_definitions(-DPOINT_TYPE_XYZIF)
|
||||
elseif(${POINT_TYPE} STREQUAL "XYZIRTF")
|
||||
add_definitions(-DPOINT_TYPE_XYZIRTF)
|
||||
endif()
|
||||
|
||||
message(=============================================================)
|
||||
message("-- POINT_TYPE is ${POINT_TYPE}")
|
||||
message(=============================================================)
|
||||
|
||||
#========================
|
||||
# Dependencies Setup
|
||||
#========================
|
||||
|
||||
#ROS#
|
||||
find_package(roscpp 1.12 QUIET)
|
||||
|
||||
if(roscpp_FOUND)
|
||||
|
||||
message(=============================================================)
|
||||
message("-- ROS Found. ROS Support is turned On.")
|
||||
message(=============================================================)
|
||||
|
||||
add_definitions(-DROS_FOUND)
|
||||
|
||||
find_package(roslib QUIET)
|
||||
include_directories(${roscpp_INCLUDE_DIRS} ${roslib_INCLUDE_DIRS})
|
||||
set(ROS_LIBS ${roscpp_LIBRARIES} ${roslib_LIBRARIES})
|
||||
|
||||
add_definitions(-DRUN_IN_ROS_WORKSPACE)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
roscpp
|
||||
sensor_msgs
|
||||
roslib)
|
||||
|
||||
catkin_package(CATKIN_DEPENDS
|
||||
sensor_msgs
|
||||
roslib)
|
||||
|
||||
else(roscpp_FOUND)
|
||||
|
||||
message(=============================================================)
|
||||
message("-- ROS Not Found. ROS Support is turned Off.")
|
||||
message(=============================================================)
|
||||
|
||||
endif(roscpp_FOUND)
|
||||
|
||||
#ROS2#
|
||||
find_package(rclcpp QUIET)
|
||||
|
||||
if(rclcpp_FOUND)
|
||||
message(=============================================================)
|
||||
message("-- ROS2 Found. ROS2 Support is turned On.")
|
||||
message(=============================================================)
|
||||
|
||||
add_definitions(-DROS2_FOUND)
|
||||
include_directories(${rclcpp_INCLUDE_DIRS})
|
||||
set(CMAKE_CXX_STANDARD 14)
|
||||
|
||||
find_package(ament_cmake REQUIRED)
|
||||
find_package(sensor_msgs REQUIRED)
|
||||
find_package(rslidar_msg REQUIRED)
|
||||
find_package(std_msgs REQUIRED)
|
||||
|
||||
else(rclcpp_FOUND)
|
||||
message(=============================================================)
|
||||
message("-- ROS2 Not Found. ROS2 Support is turned Off.")
|
||||
message(=============================================================)
|
||||
endif(rclcpp_FOUND)
|
||||
|
||||
#Others#
|
||||
find_package(yaml-cpp REQUIRED)
|
||||
|
||||
#Include directory#
|
||||
include_directories(${PROJECT_SOURCE_DIR}/src)
|
||||
|
||||
#Driver core#
|
||||
add_subdirectory(src/rs_driver)
|
||||
find_package(rs_driver REQUIRED)
|
||||
include_directories(${rs_driver_INCLUDE_DIRS})
|
||||
|
||||
#========================
|
||||
# Build Setup
|
||||
#========================
|
||||
|
||||
add_executable(rslidar_sdk_node
|
||||
node/rslidar_sdk_node.cpp
|
||||
src/manager/node_manager.cpp)
|
||||
|
||||
target_link_libraries(rslidar_sdk_node
|
||||
${YAML_CPP_LIBRARIES}
|
||||
${rs_driver_LIBRARIES})
|
||||
|
||||
#Ros#
|
||||
if(roscpp_FOUND)
|
||||
|
||||
target_link_libraries(rslidar_sdk_node
|
||||
${ROS_LIBS})
|
||||
|
||||
install(TARGETS rslidar_sdk_node
|
||||
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
|
||||
|
||||
endif(roscpp_FOUND)
|
||||
|
||||
#Ros2#
|
||||
if(rclcpp_FOUND)
|
||||
|
||||
ament_target_dependencies(rslidar_sdk_node
|
||||
rclcpp
|
||||
std_msgs
|
||||
sensor_msgs
|
||||
rslidar_msg)
|
||||
|
||||
install(TARGETS
|
||||
rslidar_sdk_node
|
||||
DESTINATION lib/${PROJECT_NAME})
|
||||
|
||||
install(DIRECTORY
|
||||
launch
|
||||
config
|
||||
rviz
|
||||
DESTINATION share/${PROJECT_NAME})
|
||||
|
||||
ament_package()
|
||||
|
||||
endif(rclcpp_FOUND)
|
||||
|
||||
19
src/airy/rslidar_sdk-main/LICENSE
Normal file
@ -0,0 +1,19 @@
|
||||
Copyright (c) 2020 RoboSense
|
||||
All rights reserved
|
||||
|
||||
By downloading, copying, installing or using the software you agree to this license. If you do not agree to this license, do not download, install, copy or use the software.
|
||||
|
||||
License Agreement
|
||||
For RoboSense LiDAR SDK Library
|
||||
(3-clause BSD License)
|
||||
|
||||
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
|
||||
|
||||
1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
|
||||
|
||||
2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
|
||||
|
||||
3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used to endorse or promote products derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
|
||||
186
src/airy/rslidar_sdk-main/README.md
Normal file
@ -0,0 +1,186 @@
|
||||
# 1 **rslidar_sdk**
|
||||
|
||||
[中文介绍](README_CN.md)
|
||||
|
||||
|
||||
|
||||
## 1 Introduction
|
||||
|
||||
**rslidar_sdk** is the Software Development Kit of the RoboSense Lidar based on Ubuntu. It contains:
|
||||
|
||||
+ The lidar driver core [rs_driver](https://github.com/RoboSense-LiDAR/rs_driver),
|
||||
+ The ROS support,
|
||||
+ The ROS2 support,
|
||||
|
||||
To get point cloud through ROS/ROS2, please just use this SDK.
|
||||
|
||||
To integrate the Lidar driver into your own projects, please use the rs_driver.
|
||||
|
||||
### 1.1 LiDAR Supported
|
||||
|
||||
- RS-LiDAR-16
|
||||
- RS-LiDAR-32
|
||||
- RS-Bpearl
|
||||
- RS-Helios
|
||||
- RS-Helios-16P
|
||||
- RS-Ruby-128
|
||||
- RS-Ruby-80
|
||||
- RS-Ruby-48
|
||||
- RS-Ruby-Plus-128
|
||||
- RS-Ruby-Plus-80
|
||||
- RS-Ruby-Plus-48
|
||||
- RS-LiDAR-M1
|
||||
- RS-LiDAR-M2
|
||||
- RS-LiDAR-M3
|
||||
- RS-LiDAR-E1
|
||||
- RS-LiDAR-MX
|
||||
- RS-LiDAR-AIRY
|
||||
|
||||
### 1.2 Point Type Supported
|
||||
|
||||
- XYZI - x, y, z, intensity
|
||||
- XYZIRT - x, y, z, intensity, ring, timestamp
|
||||
|
||||
|
||||
|
||||
## 2 Download
|
||||
|
||||
### 2.1 Download via Git
|
||||
|
||||
Download the rslidar_sdk as below. Since it contains the submodule rs_driver, please also use `git submodule` to download the submodule properly.
|
||||
|
||||
|
||||
```sh
|
||||
git clone https://github.com/RoboSense-LiDAR/rslidar_sdk.git
|
||||
cd rslidar_sdk
|
||||
git submodule init
|
||||
git submodule update
|
||||
```
|
||||
|
||||
### 2.2 Download directly
|
||||
|
||||
Instead of using Git, user can also access [rslidar_sdk_release](https://github.com/RoboSense-LiDAR/rslidar_sdk/releases) to download the latest version of rslidar_sdk.
|
||||
|
||||
Please download the **rslidar_sdk.tar.gz** archive instead of Source code. The Source code zip file does not contain the submodule rs_driver, so it has to be downloaded manaully.
|
||||

|
||||
|
||||
|
||||
|
||||
## 3 Dependencies
|
||||
|
||||
### 3.1 ROS
|
||||
|
||||
To run rslidar_sdk in the ROS environment, please install below libraries.
|
||||
+ Ubuntu 16.04 - ROS Kinetic desktop
|
||||
+ Ubuntu 18.04 - ROS Melodic desktop
|
||||
+ Ubuntu 20.04 - ROS Noetic desktop
|
||||
|
||||
For installation, please refer to http://wiki.ros.org.
|
||||
|
||||
**It's highly recommanded to install ros-distro-desktop-full**. If you do so, the corresponding libraries, such as PCL, will be installed at the same time.
|
||||
|
||||
This brings a lot of convenience, since you don't have to handle version conflict.
|
||||
|
||||
### 3.2 ROS2
|
||||
|
||||
To use rslidar_sdk in the ROS2 environment, please install below libraries.
|
||||
+ Ubuntu 16.04 - Not supported
|
||||
+ Ubuntu 18.04 - ROS2 Eloquent desktop
|
||||
+ Ubuntu 20.04 - ROS2 Galactic desktop
|
||||
+ Ubuntu 22.04 - ROS2 Humble desktop
|
||||
|
||||
For installation, please refer to https://index.ros.org/doc/ros2/Installation/Eloquent/Linux-Install-Debians/
|
||||
|
||||
**Please do not install ROS and ROS2 on the same computer, to avoid possible conflict and manually install some libraries, such as Yaml.**
|
||||
|
||||
### 3.3 Yaml (Essential)
|
||||
|
||||
version: >= v0.5.2
|
||||
|
||||
*If ros-distro-desktop-full is installed, this step can be skipped*
|
||||
|
||||
Installation:
|
||||
|
||||
```sh
|
||||
sudo apt-get update
|
||||
sudo apt-get install -y libyaml-cpp-dev
|
||||
```
|
||||
|
||||
### 3.4 libpcap (Essential)
|
||||
|
||||
version: >= v1.7.4
|
||||
|
||||
Installation:
|
||||
|
||||
```sh
|
||||
sudo apt-get install -y libpcap-dev
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 4 Compile & Run
|
||||
|
||||
|
||||
### 4.1 Compile with ROS catkin tools
|
||||
|
||||
(1) Create a new workspace folder, and create a *src* folder in it. Then put the rslidar_sdk project into the *src* folder.
|
||||
|
||||
(2) Go back to the root of workspace, run the following commands to compile and run. (if using zsh, replace the 2nd command with *source devel/setup.zsh*).
|
||||
|
||||
```sh
|
||||
catkin_make
|
||||
source devel/setup.bash
|
||||
roslaunch rslidar_sdk start.launch
|
||||
```
|
||||
|
||||
### 4.2 Compile with ROS2 colcon
|
||||
|
||||
(1) Create a new workspace folder, and create a *src* folder in it. Then put the rslidar_sdk project in the *src* folder.
|
||||
|
||||
(2) Download the packet definition project in ROS2 through [link](https://github.com/RoboSense-LiDAR/rslidar_msg), then put the project rslidar_msg in the *src* folder you just created.
|
||||
|
||||
(3) Go back to the root of workspace, run the following commands to compile and run. (if using zsh, replace the 2nd command with *source install/setup.zsh*).
|
||||
```sh
|
||||
colcon build
|
||||
source install/setup.bash
|
||||
ros2 launch rslidar_sdk start.py
|
||||
```
|
||||
|
||||
Another version of start.py may be used, since it is different on different versios of ROS2. For example, elequent_start.py is used instead for ROS2 elequent.
|
||||
|
||||
|
||||
|
||||
## 5 Introduction to parameters
|
||||
|
||||
To change behaviors of rslidar_sdk, change its parameters. please read the following links for detail information.
|
||||
|
||||
[Intro to parameters](doc/intro/02_parameter_intro.md)
|
||||
|
||||
[Intro to hidden parameters](doc/intro/03_hiding_parameters_intro.md)
|
||||
|
||||
|
||||
|
||||
## 6 Quick start
|
||||
|
||||
Below are some quick guides to use rslidar_sdk.
|
||||
|
||||
[Connect to online LiDAR and send point cloud through ROS](doc/howto/06_how_to_decode_online_lidar.md)
|
||||
|
||||
[Decode PCAP file and send point cloud through ROS](doc/howto/08_how_to_decode_pcap_file.md)
|
||||
|
||||
[Change Point Type](doc/howto/05_how_to_change_point_type.md)
|
||||
|
||||
|
||||
|
||||
## 7 Advanced Topics
|
||||
|
||||
[Online Lidar - Advanced topics](doc/howto/07_online_lidar_advanced_topics.md)
|
||||
|
||||
[PCAP file - Advanced topics](doc/howto/09_pcap_file_advanced_topics.md)
|
||||
|
||||
[Coordinate Transformation](doc/howto/10_how_to_use_coordinate_transformation.md)
|
||||
|
||||
[Record rosbag & Replay it](doc/howto/11_how_to_record_replay_packet_rosbag.md)
|
||||
|
||||
|
||||
|
||||
180
src/airy/rslidar_sdk-main/README_CN.md
Normal file
@ -0,0 +1,180 @@
|
||||
# 1 **rslidar_sdk**
|
||||
|
||||
[English Version](README.md)
|
||||
|
||||
|
||||
|
||||
## 1.1 工程简介
|
||||
|
||||
**rslidar_sdk** 是速腾聚创在Ubuntu环境下的雷达驱动软件包。它包括:
|
||||
+ 雷达驱动内核[rs_driver](https://github.com/RoboSense-LiDAR/rs_driver),
|
||||
+ ROS拓展功能,
|
||||
+ ROS2拓展功能
|
||||
|
||||
如果希望基于ROS/ROS2进行二次开发,可以使用本软件包。配合ROS/ROS2自带的可视化工具rviz,可以查看点云。
|
||||
|
||||
如果希望将雷达驱动集成到自己的工程,作更深一步的二次开发,请基于rs_driver进行开发。
|
||||
|
||||
### 1.1.1 支持的雷达型号
|
||||
|
||||
- RS-LiDAR-16
|
||||
- RS-LiDAR-32
|
||||
- RS-Bpearl
|
||||
- RS-Helios
|
||||
- RS-Helios-16P
|
||||
- RS-Ruby-128
|
||||
- RS-Ruby-80
|
||||
- RS-Ruby-48
|
||||
- RS-Ruby-Plus-128
|
||||
- RS-Ruby-Plus-80
|
||||
- RS-Ruby-Plus-48
|
||||
- RS-LiDAR-M1
|
||||
- RS-LiDAR-M2
|
||||
- RS-LiDAR-M3
|
||||
- RS-LiDAR-E1
|
||||
- RS-LiDAR-MX
|
||||
- RS-LiDAR-AIRY
|
||||
|
||||
### 1.1.2 支持的点类型
|
||||
|
||||
- XYZI - x, y, z, intensity
|
||||
- XYZIRT - x, y, z, intensity, ring, timestamp
|
||||
|
||||
|
||||
|
||||
## 1.2 下载
|
||||
|
||||
### 1.2.1 使用 git clone
|
||||
|
||||
rslidar_sdk项目包含子模块驱动内核rs_driver。在执行git clone后,还需要执行相关指令,初始化并更新子模块。
|
||||
|
||||
```sh
|
||||
git clone https://github.com/RoboSense-LiDAR/rslidar_sdk.git
|
||||
cd rslidar_sdk
|
||||
git submodule init
|
||||
git submodule update
|
||||
```
|
||||
|
||||
### 1.2.2 直接下载
|
||||
|
||||
用户可以直接访问 [rslidar_sdk_release](https://github.com/RoboSense-LiDAR/rslidar_sdk/releases) 下载最新版本的rslidar_sdk.
|
||||
|
||||
请下载 **rslidar_sdk.tar.gz** 压缩包,不要下载Source code。因为Source code压缩包内不包含子模块rs_driver的代码, 用户还需自行下载rs_driver的代码放入其中才行。
|
||||

|
||||
|
||||
|
||||
|
||||
## 1.3 依赖介绍
|
||||
|
||||
### 1.3.1 ROS
|
||||
|
||||
在ROS环境下使用雷达驱动,需要安装ROS相关依赖库。
|
||||
+ Ubuntu 16.04 - ROS Kinetic desktop
|
||||
+ Ubuntu 18.04 - ROS Melodic desktop
|
||||
+ Ubuntu 20.04 - ROS Noetic desktop
|
||||
|
||||
安装方法请参考 http://wiki.ros.org。
|
||||
|
||||
**强烈建议安装ROS desktop-full版。这个过程会自动安装一些兼容版本的依赖库,如PCL库等。这样可以避免花大量时间,去逐个安装和配置它们**。
|
||||
|
||||
### 1.3.2 ROS2
|
||||
|
||||
在ROS2环境下使用雷达驱动,需要安装ROS2相关依赖库。
|
||||
+ Ubuntu 16.04 - 不支持
|
||||
+ Ubuntu 18.04 - ROS2 Eloquent desktop
|
||||
+ Ubuntu 20.04 - ROS2 Galactic desktop
|
||||
+ Ubuntu 22.04 - ROS2 Humble desktop
|
||||
|
||||
安装方法请参考 https://index.ros.org/doc/ros2/Installation/Eloquent/Linux-Install-Debians/
|
||||
|
||||
**请不要在一台电脑上同时安装ROS和ROS2,以避免可能的版本冲突,和手工安装其他库(如Yaml)的麻烦。**
|
||||
|
||||
### 1.3.3 Yaml (必需)
|
||||
|
||||
版本号: >= v0.5.2
|
||||
|
||||
*若已安装ROS desktop-full, 可跳过*
|
||||
|
||||
安装方法如下:
|
||||
|
||||
```sh
|
||||
sudo apt-get update
|
||||
sudo apt-get install -y libyaml-cpp-dev
|
||||
```
|
||||
|
||||
### 1.3.4 libpcap (必需)
|
||||
|
||||
版本号: >= v1.7.4
|
||||
|
||||
安装方法如下:
|
||||
|
||||
```sh
|
||||
sudo apt-get install -y libpcap-dev
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 1.4 编译、运行
|
||||
|
||||
### 1.4.1 依赖于ROS-catkin编译
|
||||
|
||||
(1) 新建一个文件夹作为工作空间,然后再新建一个名为*src*的文件夹, 将rslidar_sdk工程放入*src*文件夹内。
|
||||
|
||||
(2) 返回工作空间目录,执行以下命令即可编译&运行(若使用.zsh,将第二句指令替换为 *source devel/setup.zsh*)。
|
||||
|
||||
```sh
|
||||
catkin_make
|
||||
source devel/setup.bash
|
||||
roslaunch rslidar_sdk start.launch
|
||||
```
|
||||
|
||||
### 1.4.2 依赖于ROS2-colcon编译
|
||||
|
||||
(1) 新建一个文件夹作为工作空间,然后再新建一个名为*src*的文件夹, 将rslidar_sdk工程放入*src*文件夹内。
|
||||
|
||||
(2) 通过[链接](https://github.com/RoboSense-LiDAR/rslidar_msg),下载ROS2环境下的雷达packet消息定义,将rslidar_msg工程也放在刚刚新建的*src*文件夹内,与rslidar_sdk并列。
|
||||
|
||||
(3) 返回工作空间目录,执行以下命令即可编译、运行。如果使用.zsh,将第二行替换为*source install/setup.zsh*。
|
||||
|
||||
```sh
|
||||
colcon build
|
||||
source install/setup.bash
|
||||
ros2 launch rslidar_sdk start.py
|
||||
```
|
||||
|
||||
不同ROS2版本start.py的格式可能不同,请使用对应版本的start.py。如ROS2 Elequent,请使用elequent_start.py。
|
||||
|
||||
|
||||
|
||||
## 1.5 参数介绍
|
||||
|
||||
rslidar_sdk的功能通过配置参数文件来实现,请仔细阅读。
|
||||
|
||||
[参数介绍](doc/intro/02_parameter_intro_CN.md)
|
||||
|
||||
[隐藏参数介绍](doc/intro/03_hiding_parameters_intro_CN.md)
|
||||
|
||||
|
||||
|
||||
## 1.6 快速上手
|
||||
|
||||
以下是一些常用功能的使用指南。
|
||||
|
||||
[连接在线雷达数据并发送点云到ROS](doc/howto/06_how_to_decode_online_lidar_CN.md)
|
||||
|
||||
[解析PCAP包并发送点云到ROS](doc/howto/08_how_to_decode_pcap_file_CN.md)
|
||||
|
||||
[切换点类型](doc/howto/05_how_to_change_point_type_CN.md)
|
||||
|
||||
|
||||
|
||||
## 1.7 使用进阶
|
||||
|
||||
[在线雷达-高级主题](doc/howto/07_online_lidar_advanced_topics_CN.md)
|
||||
|
||||
[PCAP文件-高级主题](doc/howto/09_pcap_file_advanced_topics_CN.md)
|
||||
|
||||
[点云坐标变换](doc/howto/10_how_to_use_coordinate_transformation_CN.md)
|
||||
|
||||
[录制ROS数据包然后播放它](doc/howto/11_how_to_record_replay_packet_rosbag_CN.md)
|
||||
|
||||
50
src/airy/rslidar_sdk-main/config/config.yaml
Normal file
@ -0,0 +1,50 @@
|
||||
common:
|
||||
msg_source:
|
||||
1 # 0: not use Lidar
|
||||
# 1: packet message comes from online Lidar
|
||||
# 2: packet message comes from ROS or ROS2
|
||||
# 3: packet message comes from Pcap file
|
||||
send_packet_ros: false # true: Send packets through ROS or ROS2(Used to record packet)
|
||||
send_point_cloud_ros: true # true: Send point cloud through ROS or ROS2
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type:
|
||||
RSAIRY # LiDAR type - RS16, RS32, RSBP, RSAIRY, RSHELIOS, RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48,
|
||||
# RSM1, RSM1_JUMBO, RSM2, RSM3, RSE1, RSMX.
|
||||
|
||||
msop_port: 6699 # Msop port of lidar
|
||||
difop_port: 7788 # Difop port of lidar
|
||||
imu_port:
|
||||
0 # IMU port of lidar(only for RSAIRY, RSE1), 0 means no imu.
|
||||
# If you want to use IMU, please first set ENABLE_IMU_DATA_PARSE to ON in CMakeLists.txt
|
||||
user_layer_bytes: 0 # Bytes of user layer. thers is no user layer if it is 0
|
||||
tail_layer_bytes: 0 # Bytes of tail layer. thers is no tail layer if it is 0
|
||||
|
||||
min_distance: 0.01 # Minimum distance of point cloud
|
||||
max_distance: 200 # Maximum distance of point cloud
|
||||
use_lidar_clock:
|
||||
true # true--Use the lidar clock as the message timestamp
|
||||
# false-- Use the system clock as the timestamp
|
||||
dense_points: false # true: discard NAN points; false: reserve NAN points
|
||||
|
||||
ts_first_point:
|
||||
true # true: time-stamp point cloud with the first point; false: with the last point;
|
||||
# these parameters are used from mechanical lidar
|
||||
|
||||
start_angle: 0 # Start angle of point cloud
|
||||
end_angle:
|
||||
360 # End angle of point cloud
|
||||
|
||||
|
||||
# When msg_source is 3, the following parameters will be used
|
||||
pcap_repeat: true # true: The pcap bag will repeat play
|
||||
pcap_rate: 1.0 # Rate to read the pcap file
|
||||
pcap_path: /home/robosense/lidar.pcap #The path of pcap file
|
||||
|
||||
ros:
|
||||
ros_frame_id: rslidar #Frame id of packet message and point cloud message
|
||||
ros_recv_packet_topic: /rslidar_packets #Topic used to receive lidar packets from ROS
|
||||
ros_send_packet_topic: /rslidar_packets #Topic used to send lidar packets through ROS
|
||||
ros_send_imu_data_topic: /rslidar_imu_data #Topic used to send imu data through ROS
|
||||
ros_send_point_cloud_topic: /rslidar_points #Topic used to send point cloud through ROS
|
||||
ros_queue_length: 100 #Topic QoS history depth
|
||||
92
src/airy/rslidar_sdk-main/config/config_double.yaml
Normal file
@ -0,0 +1,92 @@
|
||||
common:
|
||||
msg_source:
|
||||
1 # 0: not use Lidar
|
||||
# 1: packet message comes from online Lidar
|
||||
# 2: packet message comes from ROS or ROS2
|
||||
# 3: packet message comes from Pcap file
|
||||
send_packet_ros: false # true: Send packets through ROS or ROS2(Used to record packet)
|
||||
send_point_cloud_ros: true # true: Send point cloud through ROS or ROS2
|
||||
lidar:
|
||||
- driver: # front_lidar
|
||||
lidar_type:
|
||||
RSAIRY # LiDAR type - RS16, RS32, RSBP, RSAIRY, RSHELIOS, RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48,
|
||||
# RSM1, RSM1_JUMBO, RSM2, RSM3, RSE1, RSMX.
|
||||
|
||||
msop_port: 6699 # Msop port of lidar
|
||||
difop_port: 7788 # Difop port of lidar
|
||||
imu_port:
|
||||
0 # IMU port of lidar(only for RSAIRY, RSE1), 0 means no imu.
|
||||
# If you want to use IMU, please first set ENABLE_IMU_DATA_PARSE to ON in CMakeLists.txt
|
||||
user_layer_bytes: 0 # Bytes of user layer. thers is no user layer if it is 0
|
||||
tail_layer_bytes: 0 # Bytes of tail layer. thers is no tail layer if it is 0
|
||||
|
||||
min_distance: 0.01 # Minimum distance of point cloud
|
||||
max_distance: 200 # Maximum distance of point cloud
|
||||
use_lidar_clock:
|
||||
true # true--Use the lidar clock as the message timestamp
|
||||
# false-- Use the system clock as the timestamp
|
||||
dense_points: false # true: discard NAN points; false: reserve NAN points
|
||||
|
||||
ts_first_point:
|
||||
true # true: time-stamp point cloud with the first point; false: with the last point;
|
||||
# these parameters are used from mechanical lidar
|
||||
|
||||
start_angle: 0 # Start angle of point cloud
|
||||
end_angle:
|
||||
360 # End angle of point cloud
|
||||
|
||||
|
||||
# When msg_source is 3, the following parameters will be used
|
||||
pcap_repeat: true # true: The pcap bag will repeat play
|
||||
pcap_rate: 1.0 # Rate to read the pcap file
|
||||
pcap_path: /home/robosense/lidar.pcap #The path of pcap file
|
||||
|
||||
ros:
|
||||
ros_frame_id: rslidar #Frame id of packet message and point cloud message
|
||||
ros_recv_packet_topic: /rslidar_packets/front_lidar #Topic used to receive lidar packets from ROS
|
||||
ros_send_packet_topic: /rslidar_packets/front_lidar #Topic used to send lidar packets through ROS
|
||||
ros_send_imu_data_topic: /rslidar_imu_data/front_lidar #Topic used to send imu data through ROS
|
||||
ros_send_point_cloud_topic: /rslidar_points #Topic used to send point cloud through ROS
|
||||
ros_queue_length: 100 #Topic QoS history depth
|
||||
|
||||
- driver: # rear_lidar
|
||||
lidar_type:
|
||||
RSAIRY # LiDAR type - RS16, RS32, RSBP, RSAIRY, RSHELIOS, RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48,
|
||||
# RSM1, RSM1_JUMBO, RSM2, RSM3, RSE1, RSMX.
|
||||
|
||||
msop_port: 9966 # Msop port of lidar
|
||||
difop_port: 8877 # Difop port of lidar
|
||||
imu_port:
|
||||
0 # IMU port of lidar(only for RSAIRY, RSE1), 0 means no imu.
|
||||
# If you want to use IMU, please first set ENABLE_IMU_DATA_PARSE to ON in CMakeLists.txt
|
||||
user_layer_bytes: 0 # Bytes of user layer. thers is no user layer if it is 0
|
||||
tail_layer_bytes: 0 # Bytes of tail layer. thers is no tail layer if it is 0
|
||||
|
||||
min_distance: 0.01 # Minimum distance of point cloud
|
||||
max_distance: 200 # Maximum distance of point cloud
|
||||
use_lidar_clock:
|
||||
true # true--Use the lidar clock as the message timestamp
|
||||
# false-- Use the system clock as the timestamp
|
||||
dense_points: false # true: discard NAN points; false: reserve NAN points
|
||||
|
||||
ts_first_point:
|
||||
true # true: time-stamp point cloud with the first point; false: with the last point;
|
||||
# these parameters are used from mechanical lidar
|
||||
|
||||
start_angle: 0 # Start angle of point cloud
|
||||
end_angle:
|
||||
360 # End angle of point cloud
|
||||
|
||||
|
||||
# When msg_source is 3, the following parameters will be used
|
||||
pcap_repeat: true # true: The pcap bag will repeat play
|
||||
pcap_rate: 1.0 # Rate to read the pcap file
|
||||
pcap_path: /home/robosense/lidar.pcap #The path of pcap file
|
||||
|
||||
ros:
|
||||
ros_frame_id: rslidar #Frame id of packet message and point cloud message
|
||||
ros_recv_packet_topic: /rslidar_packets/rear_lidar #Topic used to receive lidar packets from ROS
|
||||
ros_send_packet_topic: /rslidar_packets/rear_lidar #Topic used to send lidar packets through ROS
|
||||
ros_send_imu_data_topic: /rslidar_imu_data/rear_lidar #Topic used to send imu data through ROS
|
||||
ros_send_point_cloud_topic: /rslidar_points #Topic used to send point cloud through ROS
|
||||
ros_queue_length: 100 #Topic QoS history depth
|
||||
50
src/airy/rslidar_sdk-main/config/config_front.yaml
Normal file
@ -0,0 +1,50 @@
|
||||
common:
|
||||
msg_source:
|
||||
1 # 0: not use Lidar
|
||||
# 1: packet message comes from online Lidar
|
||||
# 2: packet message comes from ROS or ROS2
|
||||
# 3: packet message comes from Pcap file
|
||||
send_packet_ros: false # true: Send packets through ROS or ROS2(Used to record packet)
|
||||
send_point_cloud_ros: true # true: Send point cloud through ROS or ROS2
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type:
|
||||
RSAIRY # LiDAR type - RS16, RS32, RSBP, RSAIRY, RSHELIOS, RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48,
|
||||
# RSM1, RSM1_JUMBO, RSM2, RSM3, RSE1, RSMX.
|
||||
|
||||
msop_port: 6699 # Msop port of lidar
|
||||
difop_port: 7788 # Difop port of lidar
|
||||
imu_port:
|
||||
0 # IMU port of lidar(only for RSAIRY, RSE1), 0 means no imu.
|
||||
# If you want to use IMU, please first set ENABLE_IMU_DATA_PARSE to ON in CMakeLists.txt
|
||||
user_layer_bytes: 0 # Bytes of user layer. thers is no user layer if it is 0
|
||||
tail_layer_bytes: 0 # Bytes of tail layer. thers is no tail layer if it is 0
|
||||
|
||||
min_distance: 0.01 # Minimum distance of point cloud
|
||||
max_distance: 200 # Maximum distance of point cloud
|
||||
use_lidar_clock:
|
||||
true # true--Use the lidar clock as the message timestamp
|
||||
# false-- Use the system clock as the timestamp
|
||||
dense_points: false # true: discard NAN points; false: reserve NAN points
|
||||
|
||||
ts_first_point:
|
||||
true # true: time-stamp point cloud with the first point; false: with the last point;
|
||||
# these parameters are used from mechanical lidar
|
||||
|
||||
start_angle: 0 # Start angle of point cloud
|
||||
end_angle:
|
||||
360 # End angle of point cloud
|
||||
|
||||
|
||||
# When msg_source is 3, the following parameters will be used
|
||||
pcap_repeat: true # true: The pcap bag will repeat play
|
||||
pcap_rate: 1.0 # Rate to read the pcap file
|
||||
pcap_path: /home/robosense/lidar.pcap #The path of pcap file
|
||||
|
||||
ros:
|
||||
ros_frame_id: front_lidar #Frame id of packet message and point cloud message
|
||||
ros_recv_packet_topic: /rslidar_packets #Topic used to receive lidar packets from ROS
|
||||
ros_send_packet_topic: /rslidar_packets #Topic used to send lidar packets through ROS
|
||||
ros_send_imu_data_topic: /rslidar_imu_data #Topic used to send imu data through ROS
|
||||
ros_send_point_cloud_topic: /rslidar_points/front_lidar #Topic used to send point cloud through ROS
|
||||
ros_queue_length: 100 #Topic QoS history depth
|
||||
50
src/airy/rslidar_sdk-main/config/config_rear.yaml
Normal file
@ -0,0 +1,50 @@
|
||||
common:
|
||||
msg_source:
|
||||
1 # 0: not use Lidar
|
||||
# 1: packet message comes from online Lidar
|
||||
# 2: packet message comes from ROS or ROS2
|
||||
# 3: packet message comes from Pcap file
|
||||
send_packet_ros: false # true: Send packets through ROS or ROS2(Used to record packet)
|
||||
send_point_cloud_ros: true # true: Send point cloud through ROS or ROS2
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type:
|
||||
RSAIRY # LiDAR type - RS16, RS32, RSBP, RSAIRY, RSHELIOS, RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48,
|
||||
# RSM1, RSM1_JUMBO, RSM2, RSM3, RSE1, RSMX.
|
||||
|
||||
msop_port: 9966 # Msop port of lidar
|
||||
difop_port: 8877 # Difop port of lidar
|
||||
imu_port:
|
||||
0 # IMU port of lidar(only for RSAIRY, RSE1), 0 means no imu.
|
||||
# If you want to use IMU, please first set ENABLE_IMU_DATA_PARSE to ON in CMakeLists.txt
|
||||
user_layer_bytes: 0 # Bytes of user layer. thers is no user layer if it is 0
|
||||
tail_layer_bytes: 0 # Bytes of tail layer. thers is no tail layer if it is 0
|
||||
|
||||
min_distance: 0.01 # Minimum distance of point cloud
|
||||
max_distance: 200 # Maximum distance of point cloud
|
||||
use_lidar_clock:
|
||||
true # true--Use the lidar clock as the message timestamp
|
||||
# false-- Use the system clock as the timestamp
|
||||
dense_points: false # true: discard NAN points; false: reserve NAN points
|
||||
|
||||
ts_first_point:
|
||||
true # true: time-stamp point cloud with the first point; false: with the last point;
|
||||
# these parameters are used from mechanical lidar
|
||||
|
||||
start_angle: 0 # Start angle of point cloud
|
||||
end_angle:
|
||||
360 # End angle of point cloud
|
||||
|
||||
|
||||
# When msg_source is 3, the following parameters will be used
|
||||
pcap_repeat: true # true: The pcap bag will repeat play
|
||||
pcap_rate: 1.0 # Rate to read the pcap file
|
||||
pcap_path: /home/robosense/lidar.pcap #The path of pcap file
|
||||
|
||||
ros:
|
||||
ros_frame_id: rear_lidar #Frame id of packet message and point cloud message
|
||||
ros_recv_packet_topic: /rslidar_packets #Topic used to receive lidar packets from ROS
|
||||
ros_send_packet_topic: /rslidar_packets #Topic used to send lidar packets through ROS
|
||||
ros_send_imu_data_topic: /rslidar_imu_data #Topic used to send imu data through ROS
|
||||
ros_send_point_cloud_topic: /rslidar_points/rear_lidar #Topic used to send point cloud through ROS
|
||||
ros_queue_length: 100 #Topic QoS history depth
|
||||
47
src/airy/rslidar_sdk-main/create_debian.sh
Executable file
@ -0,0 +1,47 @@
|
||||
#! /usr/bin/env bash
|
||||
|
||||
## install the python-bloom fakeroot
|
||||
|
||||
function install_pkg()
|
||||
{
|
||||
pkg_found=$(dpkg -l | grep ${1})
|
||||
if [[ $? -eq 0 ]]
|
||||
then
|
||||
echo "${1} already installed."
|
||||
else
|
||||
echo "Install ${1} ..."
|
||||
sudo apt-get install ${1} -y
|
||||
fi
|
||||
}
|
||||
|
||||
install_pkg python-bloom
|
||||
install_pkg fakeroot
|
||||
|
||||
echo -e "\n\033[1;32m ~~ (1). Delete old debian folders in the directory...\033[0m"
|
||||
rm -rf debian/ obj-x86_64-linux-gnu/
|
||||
|
||||
echo -e "\n\033[1;32m ~~ (2). Delete any backup files...\033[0m"
|
||||
find . -type f -name '*~' -delete
|
||||
|
||||
echo -e "\n\033[1;32m ~~ (3). Create debian packages...\033[0m\n"
|
||||
bloom-generate rosdebian --os-name ubuntu --os-version `echo $(lsb_release -sc)` --ros-distro `echo ${ROS_DISTRO}`
|
||||
|
||||
# sed 's#dh_shlibdeps*#dh_shlibdeps --dpkg-shlibdeps-params=--ignore-missing-info#g' debian/rules
|
||||
## when dpkg-shlibdeps: error: no dependency information found for
|
||||
## adding bellow code to debian/rules
|
||||
##
|
||||
## override_dh_shlibdeps:
|
||||
## dh_shlibdeps --dpkg-shlibdeps-params=--ignore-missing-info
|
||||
## It is necessary to insert a TAB instead of spaces before "dh_shlibdeps ..."
|
||||
|
||||
target_string=$(grep "dh_shlibdeps " debian/rules)
|
||||
replace_string=" dh_shlibdeps --dpkg-shlibdeps-params=--ignore-missing-info"
|
||||
sed -i "s#${target_string}#${replace_string}#g" debian/rules
|
||||
|
||||
fakeroot debian/rules binary
|
||||
|
||||
echo -e "\n\033[1;32m ~~ (4). Delete old debian folders in the directory...\033[0m"
|
||||
rm -rf debian/ obj-x86_64-linux-gnu/
|
||||
|
||||
echo -e "\n\033[1;32m ~~ (5). Delete any backup files...\033[0m"
|
||||
find . -type f -name '*~' -delete
|
||||
@ -0,0 +1,115 @@
|
||||
# 4 如何与rslidar_sdk_node v1.3.x共存?
|
||||
|
||||
|
||||
|
||||
## 4.1 问题描述
|
||||
|
||||
`rslidar_sdk_node` `v1.3.x`和`v1.5.x`的配置方式不同。除了如下两个可能有交互的场景外, 两者各自运行,没有关系。
|
||||
|
||||
+ `rslidar_sdk_node`在主题`/rslidar_points`下发布点云,rosbag订阅并录制到一个cloud rosbag文件。后面rosbag又会回放这个文件,发布到`/rslidar_points`,`rslidar_sdk_node`订阅并播放它。
|
||||
|
||||
+ `rslidar_sdk_node`在主题`/rslidar_packets`下发布原始的`MSOP/DIFOP Packet`,rosbag订阅并录制到一个packet rosbag文件。后面rosbag又会回放这个文件到`/rslidar_packets`,`rslidar_sdk_node`订阅并播放它。
|
||||
|
||||
第一种场景下,`v1.3.x`和`v1.5.x`发布的点云格式相同,所以`v1.3.x`录制的点云,在`v1.5.x`上播放是没有问题的。
|
||||
|
||||
第二种场景下,`v1.3.x`将MSOP/DIFOP Packet分别发布在两个主题`/rslidar_packets`和`/rslidar_packets_difop`下,而`v1.5.x`将MSOP/DIFOP Packet发布在单个主题`/rslidar_packets`下,而且`v1.3.x`和`v1.5.x`的消息定义也不同,所以`v1.3.x`录制的packet rosbag在`v1.5.x`上不能播放。ROS会检测出这两种格式的MD5 Checksum不匹配并报错。
|
||||
|
||||
本文说明如何配置`rslidar_sdk` `v1.5.x`,让它在第二种场景下可以同时播放`v1.3.x`和`v1.5.x`的packet rosbag。
|
||||
|
||||
|
||||
|
||||
## 4.2 场景说明
|
||||
|
||||
场景说明如下。
|
||||
+ 2个雷达,`Lidar1`是运行`v1.3.x`的雷达,`Lidar2`是运行`v1.5.x`的雷达。
|
||||
+ 1台主机,用于分析`Lidar1`和`Lidar2`的数据。
|
||||
|
||||

|
||||
|
||||
## 4.3 步骤
|
||||
|
||||
|
||||
### 4.3.1 配置 v1.3.x 雷达
|
||||
|
||||
使用`v1.3.x` `rslidar_sdk_node`录制pacekt rosbag。
|
||||
|
||||
按照默认的`config.yaml`的配置,消息发布到主题`/rslidar_packets`和`/rslidar_packets_difop`下。
|
||||
|
||||
```
|
||||
common:
|
||||
msg_source: 1 #0: not use Lidar
|
||||
#1: packet message comes from online Lidar
|
||||
#2: packet message comes from ROS or ROS2
|
||||
#3: packet message comes from Pcap file
|
||||
#4: packet message comes from Protobuf-UDP
|
||||
#5: point cloud comes from Protobuf-UDP
|
||||
send_packet_ros: true #true: Send packets through ROS or ROS2(Used to record packet)
|
||||
send_point_cloud_ros: true #true: Send point cloud through ROS or ROS2
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSM1 #LiDAR type - RS16, RS32, RSBP, RSHELIOS, RS128, RS80, RSM1
|
||||
msop_port: 6699 #Msop port of lidar
|
||||
difop_port: 7788 #Difop port of lidar
|
||||
ros:
|
||||
ros_send_packet_topic: /rslidar_packets #Topic used to send lidar packets through ROS
|
||||
ros_send_point_cloud_topic: /rslidar_points #Topic used to send point cloud through ROS
|
||||
```
|
||||
|
||||
### 4.3.2 配置 v1.5.x 雷达
|
||||
|
||||
使用`v1.5.6` `rslidar_sdk_node`录制packet rosbag。
|
||||
|
||||
为了与`v1.3.2`的消息区别,将消息输出到主题`/rslidar_packets_v2`下。
|
||||
|
||||
```
|
||||
common:
|
||||
msg_source: 1 #0: not use Lidar
|
||||
#1: packet message comes from online Lidar
|
||||
#2: packet message comes from ROS or ROS2
|
||||
#3: packet message comes from Pcap file
|
||||
send_packet_ros: true #true: Send packets through ROS or ROS2(Used to record packet)
|
||||
send_point_cloud_ros: true #true: Send point cloud through ROS or ROS2
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSM1 #LiDAR type - RS16, RS32, RSBP, RSHELIOS, RS128, RS80, RS48, RSM1
|
||||
msop_port: 6699 #Msop port of lidar
|
||||
difop_port: 7788 #Difop port of lidar
|
||||
ros:
|
||||
ros_send_packet_topic: /rslidar_packets_v2 #Topic used to send lidar packets through ROS
|
||||
ros_send_point_cloud_topic: /rslidar_points #Topic used to send point cloud through ROS
|
||||
```
|
||||
|
||||
|
||||
### 4.3.3 配置 v1.5.x 主机
|
||||
|
||||
+ 打开CMake编译选项`ENABLE_SOURCE_PACKET_LEGACY=ON`,编译`rslidar_sdk`。
|
||||
|
||||
```
|
||||
# CMakeLists.txt
|
||||
|
||||
option(ENABLE_SOURCE_PACKET_LEGACY "Enable ROS Source of MSOP/DIFOP Packet v1.3.x" ON)
|
||||
```
|
||||
|
||||
+ 在`config.yaml`中,增加一个配置项`ros_recv_packet_legacy_topic`: `/rslidar_packets`。这样`rslidar_sdk_node`将同时订阅两个主题。
|
||||
+ 订阅`/rslidar_packets`和`/rslidar_packets_difop`,读入`v1.3.x`的消息
|
||||
+ 订阅`/rslidar_packets_v2`,读入`v1.5.x`的消息
|
||||
|
||||
```
|
||||
common:
|
||||
msg_source: 1 #0: not use Lidar
|
||||
#1: packet message comes from online Lidar
|
||||
#2: packet message comes from ROS or ROS2
|
||||
#3: packet message comes from Pcap file
|
||||
send_packet_ros: false #true: Send packets through ROS or ROS2(Used to record packet)
|
||||
send_point_cloud_ros: true #true: Send point cloud through ROS or ROS2
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSM1 #LiDAR type - RS16, RS32, RSBP, RSHELIOS, RS128, RS80, RS48, RSM1
|
||||
msop_port: 6699 #Msop port of lidar
|
||||
difop_port: 7788 #Difop port of lidar
|
||||
ros:
|
||||
ros_recv_packet_legacy_topic: /rslidar_packets #Topic used to receive lidar packets from ROS
|
||||
ros_recv_packet_topic: /rslidar_packets_v2 #Topic used to receive lidar packets from ROS
|
||||
ros_send_point_cloud_topic: /rslidar_points #Topic used to send point cloud through ROS
|
||||
```
|
||||
|
||||
@ -0,0 +1,165 @@
|
||||
# 5 How to change point type
|
||||
|
||||
|
||||
|
||||
## 5.1 Introduction
|
||||
|
||||
This document illustrates how to change the point type.
|
||||
|
||||
In ```CMakeLists.txt``` of the project, change the variable `POINT_TYPE`. Remember to **rebuild** the project after changing it.
|
||||
|
||||
```cmake
|
||||
#=======================================
|
||||
# Custom Point Type (XYZI,XYZIRT, XYZIF, XYZIRTF)
|
||||
#=======================================
|
||||
set(POINT_TYPE XYZI)
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 5.2 XYZI
|
||||
|
||||
If `POINT_TYPE` is `XYZI`, rslidar_sdk uses the RoboSense defined type as below.
|
||||
|
||||
```c++
|
||||
struct PointXYZI
|
||||
{
|
||||
float x;
|
||||
float y;
|
||||
float z;
|
||||
uint8_t intensity;
|
||||
};
|
||||
```
|
||||
|
||||
rslidar_sdk transforms point cloud of `PointXYZI` to ROS message of `PointCloud2`,and publish it.
|
||||
|
||||
```c++
|
||||
sensor_msgs::PointCloud2 ros_msg;
|
||||
int offset = 0;
|
||||
offset = addPointField(ros_msg, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
|
||||
//
|
||||
// copy points from point cloud of `PointXYZI` to `PointCloud2`
|
||||
//
|
||||
...
|
||||
|
||||
```
|
||||
|
||||
Here `intensity` of `PointCloud2` is `float` type, not `uint8_t`. This is because most ROS based applications require `intensity` of `float` type.
|
||||
|
||||
|
||||
|
||||
## 5.3 XYZIRT
|
||||
|
||||
If `POINT_TYPE` is `XYZIRT`, rslidar_sdk uses the RoboSense defined type as below.
|
||||
|
||||
```c++
|
||||
struct PointXYZIRT
|
||||
{
|
||||
float x;
|
||||
float y;
|
||||
float z;
|
||||
uint8_t intensity;
|
||||
uint16_t ring;
|
||||
double timestamp;
|
||||
};
|
||||
```
|
||||
|
||||
rslidar_sdk transforms point cloud of `PointXYZIRT` to ROS message of `PointCloud2`,and publish it.
|
||||
|
||||
```c++
|
||||
sensor_msgs::PointCloud2 ros_msg;
|
||||
int offset = 0;
|
||||
offset = addPointField(ros_msg, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
#if defined(POINT_TYPE_XYZIRT) || defined(POINT_TYPE_XYZIRTF)
|
||||
offset = addPointField(ros_msg, "ring", 1, sensor_msgs::PointField::UINT16, offset);
|
||||
offset = addPointField(ros_msg, "timestamp", 1, sensor_msgs::PointField::FLOAT64, offset);
|
||||
#endif
|
||||
|
||||
//
|
||||
// copy points from point cloud of `PointXYZIRT` to `PointCloud2`
|
||||
//
|
||||
...
|
||||
|
||||
```
|
||||
## 5.4 XYZIF
|
||||
|
||||
If `POINT_TYPE` is `XYZIF`, rslidar_sdk uses the RoboSense defined type as below.
|
||||
|
||||
```c++
|
||||
struct PointXYZIF
|
||||
{
|
||||
float x;
|
||||
float y;
|
||||
float z;
|
||||
uint8_t intensity;
|
||||
uint16_t ring;
|
||||
double timestamp;
|
||||
};
|
||||
```
|
||||
|
||||
rslidar_sdk transforms point cloud of `PointXYZIF` to ROS message of `PointCloud2`,and publish it.
|
||||
|
||||
```c++
|
||||
sensor_msgs::PointCloud2 ros_msg;
|
||||
int offset = 0;
|
||||
offset = addPointField(ros_msg, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
#if defined(POINT_TYPE_XYZIF) || defined(POINT_TYPE_XYZIRTF)
|
||||
offset = addPointField(ros_msg, "feature", 1, sensor_msgs::PointField::UINT8, offset);
|
||||
#endif
|
||||
|
||||
//
|
||||
// copy points from point cloud of `PointXYZIF` to `PointCloud2`
|
||||
//
|
||||
...
|
||||
|
||||
```
|
||||
## 5.5 XYZIRTF
|
||||
|
||||
If `POINT_TYPE` is `XYZIRTF`, rslidar_sdk uses the RoboSense defined type as below.
|
||||
|
||||
```c++
|
||||
struct PointXYZIRTF
|
||||
{
|
||||
float x;
|
||||
float y;
|
||||
float z;
|
||||
uint8_t intensity;
|
||||
uint16_t ring;
|
||||
double timestamp;
|
||||
};
|
||||
```
|
||||
|
||||
rslidar_sdk transforms point cloud of `PointXYZIRTF` to ROS message of `PointCloud2`,and publish it.
|
||||
|
||||
```c++
|
||||
sensor_msgs::PointCloud2 ros_msg;
|
||||
int offset = 0;
|
||||
offset = addPointField(ros_msg, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
#if defined(POINT_TYPE_XYZIRT) || defined(POINT_TYPE_XYZIRTF)
|
||||
offset = addPointField(ros_msg, "ring", 1, sensor_msgs::PointField::UINT16, offset);
|
||||
offset = addPointField(ros_msg, "timestamp", 1, sensor_msgs::PointField::FLOAT64, offset);
|
||||
#endif
|
||||
#if defined(POINT_TYPE_XYZIF) || defined(POINT_TYPE_XYZIRTF)
|
||||
offset = addPointField(ros_msg, "feature", 1, sensor_msgs::PointField::UINT8, offset);
|
||||
#endif
|
||||
|
||||
//
|
||||
// copy points from point cloud of `PointXYZIRTF` to `PointCloud2`
|
||||
//
|
||||
...
|
||||
|
||||
```
|
||||
|
||||
@ -0,0 +1,162 @@
|
||||
# 5 如何改变点类型的定义
|
||||
|
||||
|
||||
|
||||
## 5.1 简介
|
||||
|
||||
本文档介绍如何改变点类型的定义。
|
||||
|
||||
在项目的```CMakeLists.txt```文件中设置`POINT_TYPE`变量。修改后,需要重新编译整个工程。
|
||||
|
||||
```cmake
|
||||
#=======================================
|
||||
# Custom Point Type (XYZI,XYZIRT, XYZIF, XYZIRTF)
|
||||
#=======================================
|
||||
set(POINT_TYPE XYZI)
|
||||
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 5.2 XYZI
|
||||
|
||||
`POINT_TYPE`为`XYZI`时,rslidar_sdk使用RoboSense自定义的点类型```PointXYZI```.
|
||||
|
||||
```c++
|
||||
struct PointXYZI
|
||||
{
|
||||
float x;
|
||||
float y;
|
||||
float z;
|
||||
uint8_t intensity;
|
||||
};
|
||||
```
|
||||
|
||||
rslidar_sdk将基于`PointXYZI`的点云,转换为ROS的`PointCloud2`消息,再发布出去。
|
||||
|
||||
```c++
|
||||
sensor_msgs::PointCloud2 ros_msg;
|
||||
int offset = 0;
|
||||
offset = addPointField(ros_msg, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
|
||||
//
|
||||
// copy points from point cloud of `PointXYZI` to `PointCloud2`
|
||||
//
|
||||
...
|
||||
```
|
||||
|
||||
这里`PointCloud2`中的`intensity`是`float`类型,而不是`uint8_t`类型。这是因为大多数基于ROS的程序都希望`float`类型的`intensity`。
|
||||
|
||||
|
||||
|
||||
## 5.3 XYZIRT
|
||||
|
||||
`POINT_TYPE`为`XYZIRT`时,rslidar_sdk使用RoboSense自定义的点类型```PointXYZRT```。
|
||||
|
||||
```c++
|
||||
struct PointXYZIRT
|
||||
{
|
||||
float x;
|
||||
float y;
|
||||
float z;
|
||||
uint8_t intensity;
|
||||
uint16_t ring;
|
||||
double timestamp;
|
||||
};
|
||||
```
|
||||
|
||||
rslidar_sdk将基于`PointXYZIRT`的点云,转换为ROS的PointCloud2消息,再发布出去。
|
||||
|
||||
```c++
|
||||
sensor_msgs::PointCloud2 ros_msg;
|
||||
int offset = 0;
|
||||
offset = addPointField(ros_msg, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
#if defined(POINT_TYPE_XYZIRT) || defined(POINT_TYPE_XYZIRTF)
|
||||
offset = addPointField(ros_msg, "ring", 1, sensor_msgs::PointField::UINT16, offset);
|
||||
offset = addPointField(ros_msg, "timestamp", 1, sensor_msgs::PointField::FLOAT64, offset);
|
||||
#endif
|
||||
|
||||
//
|
||||
// copy points from point cloud of `PointXYZIRT` to `PointCloud2`
|
||||
//
|
||||
...
|
||||
```
|
||||
## 5.4 XYZIF
|
||||
|
||||
`POINT_TYPE`为`XYZIF`时,rslidar_sdk使用RoboSense自定义的点类型```PointXYZIF```。
|
||||
|
||||
```c++
|
||||
struct PointXYZIF
|
||||
{
|
||||
float x;
|
||||
float y;
|
||||
float z;
|
||||
uint8_t intensity;
|
||||
uint8_t feature;
|
||||
};
|
||||
```
|
||||
|
||||
rslidar_sdk将基于`PointXYZIF`的点云,转换为ROS的PointCloud2消息,再发布出去。
|
||||
|
||||
```c++
|
||||
sensor_msgs::PointCloud2 ros_msg;
|
||||
int offset = 0;
|
||||
offset = addPointField(ros_msg, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
#if defined(POINT_TYPE_XYZIF) || defined(POINT_TYPE_XYZIRTF)
|
||||
offset = addPointField(ros_msg, "feature", 1, sensor_msgs::PointField::UINT8, offset);
|
||||
#endif
|
||||
|
||||
//
|
||||
// copy points from point cloud of `PointXYZIF` to `PointCloud2`
|
||||
//
|
||||
...
|
||||
```
|
||||
## 5.5 XYZIRTF
|
||||
|
||||
`POINT_TYPE`为`XYZIRTF`时,rslidar_sdk使用RoboSense自定义的点类型```PointXYZIRTF```。
|
||||
|
||||
```c++
|
||||
struct PointXYZIRTF
|
||||
{
|
||||
float x;
|
||||
float y;
|
||||
float z;
|
||||
uint8_t intensity;
|
||||
uint16_t ring;
|
||||
double timestamp;
|
||||
uint8_t feature;
|
||||
};
|
||||
```
|
||||
|
||||
rslidar_sdk将基于`PointXYZIRTF`的点云,转换为ROS的PointCloud2消息,再发布出去。
|
||||
|
||||
```c++
|
||||
sensor_msgs::PointCloud2 ros_msg;
|
||||
int offset = 0;
|
||||
offset = addPointField(ros_msg, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
offset = addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::FLOAT32, offset);
|
||||
#if defined(POINT_TYPE_XYZIRT) || defined(POINT_TYPE_XYZIRTF)
|
||||
offset = addPointField(ros_msg, "ring", 1, sensor_msgs::PointField::UINT16, offset);
|
||||
offset = addPointField(ros_msg, "timestamp", 1, sensor_msgs::PointField::FLOAT64, offset);
|
||||
#endif
|
||||
#if defined(POINT_TYPE_XYZIF) || defined(POINT_TYPE_XYZIRTF)
|
||||
offset = addPointField(ros_msg, "feature", 1, sensor_msgs::PointField::UINT8, offset);
|
||||
#endif
|
||||
|
||||
//
|
||||
// copy points from point cloud of `PointXYZIRTF` to `PointCloud2`
|
||||
//
|
||||
...
|
||||
```
|
||||
|
||||
@ -0,0 +1,70 @@
|
||||
# 6 How to decode on-line LiDAR
|
||||
|
||||
## 6.1 Introduction
|
||||
|
||||
This document illustrates how to connect to an on-line LiDAR, and send point cloud to ROS.
|
||||
|
||||
Please make sure you have read the LiDAR user-guide and [Intro to parameters](../intro/02_parameter_intro.md) before reading this document.
|
||||
|
||||
|
||||
|
||||
## 6.2 Steps
|
||||
|
||||
### 6.2.1 Get the LiDAR port number
|
||||
|
||||
Please follow the instructions in LiDAR user-guide, to connect the LiDAR, and set up your computer's ip address.
|
||||
|
||||
Please check the LiDAR user-guide, or use the 3rd-party tool(such as WireShark), to get your LiDAR's MSOP port number and DIFOP port number. The default values are ```msop-6699, difop-7788```.
|
||||
|
||||
### 6.2.2 Set up the configuration file
|
||||
|
||||
#### 6.2.2.1 common part
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 1
|
||||
send_packet_ros: false
|
||||
send_point_cloud_ros: true
|
||||
```
|
||||
|
||||
The message come from the LiDAR, so set ```msg_source = 1```.
|
||||
|
||||
Send point cloud to ROS, so set ```send_point_cloud_ros = true```.
|
||||
|
||||
#### 6.2.2.2 lidar-driver part
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RS128
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
start_angle: 0
|
||||
end_angle: 360
|
||||
min_distance: 0.2
|
||||
max_distance: 200
|
||||
use_lidar_clock: true
|
||||
```
|
||||
|
||||
Set the ```lidar_type``` to your LiDAR type.
|
||||
|
||||
Set the ```msop_port```,```difop_port``` and ```difop_port``` to your LiDAR's port number.
|
||||
|
||||
#### 6.2.2.3 lidar-ros part
|
||||
|
||||
```yaml
|
||||
ros:
|
||||
ros_frame_id: rslidar
|
||||
ros_recv_packet_topic: /rslidar_packets
|
||||
ros_send_packet_topic: /rslidar_packets
|
||||
ros_send_imu_data_topic: /rslidar_imu_data
|
||||
ros_send_point_cloud_topic: /rslidar_points
|
||||
```
|
||||
|
||||
Set the ```rslidar_imu_data``` and ```ros_send_point_cloud_topic``` to the topic you want to send to.
|
||||
|
||||
### 6.2.3 Run
|
||||
|
||||
Run the program.
|
||||
|
||||
@ -0,0 +1,74 @@
|
||||
# 6 如何连接在线雷达
|
||||
|
||||
|
||||
|
||||
## 6.1 简介
|
||||
|
||||
本文档描述如何连接在线雷达,并发送点云数据到ROS。
|
||||
|
||||
在阅读本文档之前, 请确保已经阅读过雷达用户手册和[参数简介](../intro/02_parameter_intro_CN.md) 。
|
||||
|
||||
|
||||
|
||||
## 6.2 步骤
|
||||
|
||||
### 6.2.1 获取数据端口号
|
||||
|
||||
根据雷达用户手册连接雷达, 并设置好您的电脑的IP地址。
|
||||
|
||||
请参考雷达用户手册,或使用第三方工具(如WireShark等)得到雷达的MSOP端口号和DIFOP端口号。端口的默认值分别为```6699```和```7788```。
|
||||
|
||||
### 6.2.2 设置参数文件
|
||||
|
||||
设置参数文件```config.yaml```。
|
||||
|
||||
#### 6.2.2.1 common部分
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 1
|
||||
send_packet_ros: false
|
||||
send_point_cloud_ros: true
|
||||
```
|
||||
|
||||
消息来源于在线雷达,因此请设置```msg_source=1```。
|
||||
|
||||
将点云发送到ROS以便查看,因此设置 ```send_point_cloud_ros = true``` 。
|
||||
|
||||
#### 6.2.2.2 lidar-driver部分
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
start_angle: 0
|
||||
end_angle: 360
|
||||
min_distance: 0.2
|
||||
max_distance: 200
|
||||
use_lidar_clock: true
|
||||
```
|
||||
|
||||
将 ```lidar_type``` 设置为LiDAR类型 。
|
||||
|
||||
设置 ```msop_port``` 、 ```difop_port``` 和 ```imu_port``` 为雷达数据端口号。
|
||||
|
||||
#### 6.2.2.3 lidar-ros部分
|
||||
|
||||
```yaml
|
||||
ros:
|
||||
ros_frame_id: rslidar
|
||||
ros_recv_packet_topic: /rslidar_packets
|
||||
ros_send_packet_topic: /rslidar_packets
|
||||
ros_send_imu_data_topic: /rslidar_imu_data
|
||||
ros_send_point_cloud_topic: /rslidar_points
|
||||
```
|
||||
|
||||
将 ```rslidar_imu_data``` 和```ros_send_point_cloud_topic``` 设置为发送Imu数据和发送点云的话题。
|
||||
|
||||
### 6.2.3 运行
|
||||
|
||||
运行程序。
|
||||
|
||||
@ -0,0 +1,200 @@
|
||||
# 7 Online LiDAR - Advanced Topics
|
||||
|
||||
|
||||
|
||||
## 7.1 Introduction
|
||||
|
||||
The RoboSense LiDAR may work
|
||||
|
||||
+ in unicast/multicast/broadcast mode,
|
||||
+ with VLAN layer
|
||||
+ with user layers.
|
||||
+ Also rslidar_sdk supports multi-LiDARs.
|
||||
|
||||
This document illustrates how to configure rslidar_sdk in each case.
|
||||
|
||||
Before reading this document, please be sure that you have read:
|
||||
+ LiDAR user-guide
|
||||
+ [Intro to parameters](../intro/02_parameter_intro.md)
|
||||
+ [Decode online LiDAR](./06_how_to_decode_online_lidar.md)
|
||||
|
||||
|
||||
|
||||
## 7.2 Unicast, Multicast and Broadcast
|
||||
|
||||
### 7.2.1 Broadcast mode
|
||||
|
||||
The Lidar sends MSOP/DIFOP packets to the host machine (rslidar_sdk runs on it). For simplicity, the DIFOP port is ommited here.
|
||||
+ The Lidar sends to `255.255.255.255` : `6699`, and the host binds to port `6699`.
|
||||

|
||||
|
||||
Below is how to configure `config.yaml`.
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 1
|
||||
send_point_cloud_ros: true
|
||||
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
ros:
|
||||
ros_frame_id: rslidar
|
||||
ros_send_point_cloud_topic: /rslidar_points
|
||||
```
|
||||
|
||||
The `common` part and the `lidar-ros` part is listed here. They will be ommited in the following examples, since they are not changed.
|
||||
|
||||
### 7.2.2 Unicast mode
|
||||
|
||||
To reduce the network load, the Lidar is suggested to work in unicast mode.
|
||||
+ The Lidar sends to `192.168.1.102` : `6699`, and the host binds to port `6699`.
|
||||

|
||||
|
||||
Below is how to configure `config.yaml`. In fact, it same with the broadcast mode.
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
```
|
||||
|
||||
### 7.2.3 Multicast mode
|
||||
|
||||
The Lidar may also works in multicast mode.
|
||||
+ The lidar sends to `224.1.1.1`:`6699`
|
||||
+ The host binds to port `6699`. And it makes local NIC (Network Interface Card) join the multicast group `224.1.1.1`. The local NIC's IP is `192.168.1.102`.
|
||||

|
||||
|
||||
Below is how to configure `config.yaml`.
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
group_address: 224.1.1.1
|
||||
host_address: 192.168.1.102
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 7.3 Multiple LiDARs
|
||||
|
||||
### 7.3.1 Different remote ports
|
||||
|
||||
If you have two or more Lidars, it is suggested to set different remote ports.
|
||||
+ First Lidar sends to `192.168.1.102`:`6699`, and the first driver instance binds to `6699`.
|
||||
+ Second Lidar sends to `192.168.1.102`:`5599`, and the second driver instance binds to `5599`.
|
||||

|
||||
|
||||
Below is how to configure `config.yaml`.
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6698
|
||||
difop_port: 7789
|
||||
imu_port: 6689
|
||||
```
|
||||
|
||||
### 7.3.2 Different remote IPs
|
||||
|
||||
An alternate way is to set different remote IPs.
|
||||
+ The host has two NICs: `192.168.1.102` and `192.168.1.103`.
|
||||
+ First Lidar sends to `192.168.1.102`:`6699`, and the first driver instance binds to `192.168.1.102:6699`.
|
||||
+ Second Lidar sends to `192.168.1.103`:`6699`, and the second driver instance binds to `192.168.1.103:6699`.
|
||||

|
||||
|
||||
Below is how to configure `config.yaml`.
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
host_address: 192.168.1.102
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
host_address: 192.168.1.103
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 7.4 VLAN
|
||||
|
||||
In some user cases, The Lidar may work on VLAN. Its packets have a VLAN layer.
|
||||

|
||||
|
||||
The driver cannot parse this packet. Instead, it depends on a virtual NIC to strip the VLAN layer.
|
||||
|
||||
Below is an example.
|
||||
+ The Lidar works on VLAN `80`. It sends packets to `192.168.1.102` : `6699`. The packet has a VLAN layer.
|
||||
+ Suppose there is a physical NIC `eno1` on the host. It receives packets with VLAN layer.
|
||||

|
||||
|
||||
To strip the VLAN layer, create a virtual NIC `eno1.80` on `eno1`, and assign IP `192.168.1.102` to it.
|
||||
|
||||
```
|
||||
sudo apt-get install vlan -y
|
||||
sudo modprobe 8021q
|
||||
|
||||
sudo vconfig add eno1 80
|
||||
sudo ifconfig eno1.80 192.168.1.102 up
|
||||
```
|
||||
|
||||
Now the driver may take `eno1.80` as a general NIC, and receives packets without VLAN layer.
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 7.5 User Layer, Tail Layer
|
||||
|
||||
In some user cases, User may add extra layers before or after the MSOP/DIFOP packet.
|
||||
+ USER_LAYER is before the packet and TAIL_LAYER is after it.
|
||||

|
||||
|
||||
These extra layers are parts of UDP data. The driver can strip them.
|
||||
|
||||
To strip them, just give their lengths in bytes.
|
||||
|
||||
In the following example, USER_LAYER is 8 bytes, and TAIL_LAYER is 4 bytes.
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
user_layer_bytes: 8
|
||||
tail_layer_bytes: 4
|
||||
```
|
||||
|
||||
@ -0,0 +1,199 @@
|
||||
# 7 在线雷达 - 高级主题
|
||||
|
||||
|
||||
|
||||
## 7.1 简介
|
||||
|
||||
RoboSense雷达可以工作在如下的场景。
|
||||
|
||||
+ 单播/组播/广播模式。
|
||||
+ 运行在VLAN协议上。
|
||||
+ 向Packet加入用户自己的层。
|
||||
+ 接入多个雷达。
|
||||
|
||||
本文描述在这些场景下如何配置rslidar_sdk。
|
||||
|
||||
在阅读本文档之前, 请确保已经阅读过:
|
||||
+ 雷达用户手册
|
||||
+ [参数介绍](../intro/02_parameter_intro_CN.md)
|
||||
+ [连接在线雷达](./06_how_to_decode_online_lidar_CN.md)
|
||||
|
||||
|
||||
|
||||
## 7.2 单播、组播、广播
|
||||
|
||||
### 7.2.1 广播
|
||||
|
||||
雷达发送 MSOP/DIFOP Packet到电脑主机。为简单起见,如下的图没有显示DIFOP端口。
|
||||
+ 雷达发送Packet到 `255.255.255.255` : `6699`, rslidar_sdk绑定到主机的端口 `6699`.
|
||||

|
||||
|
||||
如下是配置`config.yaml`的方式。
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 1
|
||||
send_point_cloud_ros: true
|
||||
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
ros:
|
||||
ros_frame_id: rslidar
|
||||
ros_send_point_cloud_topic: /rslidar_points
|
||||
```
|
||||
|
||||
这里列出了`common`部分和`lidar-ros`部分的设置。这两部分设置将在本文中后面的例子沿用,不再列出。
|
||||
|
||||
### 7.2.2 单播
|
||||
|
||||
为了减少网络负载,建议雷达使用单播模式。
|
||||
+ 雷达发送Packet到 `192.168.1.102` : `6699`, rslidar_sdk绑定端口 `6699`。
|
||||

|
||||
|
||||
如下是配置`config.yaml`的方式。这实际上与广播的方式一样。
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
```
|
||||
|
||||
### 7.2.3 组播
|
||||
|
||||
雷达也可以工作在组播模式。
|
||||
+ 雷达发送Packet到 `224.1.1.1`:`6699`
|
||||
+ rslidar_sdk绑定到端口 `6699`。同时它将IP地址为`192.168.1.102`的本地网络接口加入组播组`224.1.1.1`。
|
||||

|
||||
|
||||
如下是配置`config.yaml`的方式。
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
group_address: 224.1.1.1
|
||||
host_address: 192.168.1.102
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 7.3 多个雷达的情况
|
||||
|
||||
### 7.3.1 不同的目标端口
|
||||
|
||||
如果有两个或多个雷达,首选的配置是让它们有不同的目标端口。
|
||||
+ 第一个雷达发送Packet到 `192.168.1.102`:`6699`, 给rslidar_sdk配置的第一个driver节点绑定到`6699`。
|
||||
+ 第二个雷达发送Packet到 `192.168.1.102`:`5599`, 给rslidar_sdk配置的第二个driver节点绑定到`5599`。
|
||||

|
||||
|
||||
如下是配置`config.yaml`的方式。
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6698
|
||||
difop_port: 7789
|
||||
imu_port: 6689
|
||||
```
|
||||
|
||||
### 7.3.2 不同的目标IP
|
||||
|
||||
也可以让多个雷达使用不同的目标IP。
|
||||
+ 主机有两个网卡, IP地址分别为`192.168.1.102` 和 `192.168.1.103`。
|
||||
+ 第一个雷达发送Packet到 `192.168.1.102`:`6699`, 给rslidar_sdk配置的第一个driver节点绑定到`192.168.1.102:6699`。
|
||||
+ 第二个雷达发送Packet到 `192.168.1.103`:`6699`, 给rslidar_sdk配置的第二个driver节点绑定到`192.168.1.103:6699`。
|
||||

|
||||
|
||||
如下是配置`config.yaml`的方式。
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
host_address: 192.168.1.102
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
host_address: 192.168.1.103
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 7.4 VLAN
|
||||
|
||||
在某些场景下,雷达工作在VLAN层之上。MSOP/DIFOP Packet有VLAN层,如下图。
|
||||

|
||||
|
||||
rslidar_sdk不能解析VLAN层。
|
||||
|
||||
需要一个虚拟网卡来剥除掉这一层。举例如下。
|
||||
|
||||
+ 雷达工作在VLAN id为`80`的VLAN层上。它发送Packet到`192.168.1.102` : `6699`,Packet有VLAN层。
|
||||
+ 假设主机上有一个支持VLAN的物理网卡`eno1`. 它接收带VLAN层的Packet。
|
||||

|
||||
|
||||
要剥离VLAN层,需要基于`eno1`,创建一个虚拟网卡`eno1.80`, 并且将它的IP设置为`192.168.1.102`。
|
||||
|
||||
```shell
|
||||
sudo apt-get install vlan -y
|
||||
sudo modprobe 8021q
|
||||
|
||||
sudo vconfig add eno1 80
|
||||
sudo ifconfig eno1.80 192.168.1.102 up
|
||||
```
|
||||
|
||||
现在,rslidar_sdk可以将`eno1.80`当做一个一般的网卡来处理,从这里接收不带VLAN层的Packet.
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 7.5 User Layer, Tail Layer
|
||||
|
||||
在某些场景下,用户可能在MSOP/DIFOP数据前后加入自己的层。
|
||||
+ 在前面的是USER_LAYER,在后面的是TAIL_LAYER。
|
||||

|
||||
|
||||
这两个层是UDP数据的一部分,所以rslidar_sdk可以自己剥除它们。只需要指出这两个层的长度就可以了。
|
||||
|
||||
在下面的例子中,USER_LAYER是8字节,TAIL_LAYER是4字节。
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
user_layer_bytes: 8
|
||||
tail_layer_bytes: 4
|
||||
```
|
||||
|
||||
@ -0,0 +1,79 @@
|
||||
# 8 How to decode PCAP file
|
||||
|
||||
|
||||
|
||||
## 8.1 Introduction
|
||||
|
||||
This document illustrates how to decode PCAP file, and send point cloud to ROS.
|
||||
|
||||
Please make sure you have read the LiDAR user-guide and [Intro to parameters](../intro/02_parameter_intro.md) before reading this document.
|
||||
|
||||
|
||||
|
||||
## 8.2 Steps
|
||||
|
||||
### 8.2.1 Get the LiDAR port number
|
||||
|
||||
Please check the LiDAR user-guide, or use the 3rd-party tool(such as WireShark), to get your LiDAR's MSOP port number and DIFOP port number. The default values are ```msop-6699, difop-7788```.
|
||||
|
||||
### 8.2.2 Set up the configuration file
|
||||
|
||||
Set up the configuration file `config.yaml`.
|
||||
|
||||
#### 8.2.2.1 common part
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 3
|
||||
send_packet_ros: false
|
||||
send_point_cloud_ros: true
|
||||
```
|
||||
|
||||
The messages come from the PCAP bag, so set ```msg_source = 3```.
|
||||
|
||||
Send point cloud to ROS, so set ```send_point_cloud_ros = true```.
|
||||
|
||||
#### 8.2.2.2 lidar-driver part
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
start_angle: 0
|
||||
end_angle: 360
|
||||
min_distance: 0.2
|
||||
max_distance: 200
|
||||
use_lidar_clock: true
|
||||
pcap_path: /home/robosense/lidar.pcap
|
||||
```
|
||||
|
||||
Set the ```pcap_path``` to the absolute path of the PCAP file.
|
||||
|
||||
Set the ```lidar_type``` to your LiDAR type.
|
||||
|
||||
Set the ```msop_port```,```difop_port``` and ```difop_port``` to your LiDAR's port number.
|
||||
|
||||
#### 8.2.2.3 lidar-ros part
|
||||
|
||||
```yaml
|
||||
ros:
|
||||
ros_frame_id: rslidar
|
||||
ros_recv_packet_topic: /rslidar_packets
|
||||
ros_send_packet_topic: /rslidar_packets
|
||||
ros_send_imu_data_topic: /rslidar_imu_data
|
||||
ros_send_point_cloud_topic: /rslidar_points
|
||||
```
|
||||
|
||||
Set the ```rslidar_imu_data``` and ```ros_send_point_cloud_topic``` to the topic you want to send to.
|
||||
|
||||
### 8.2.3 Run
|
||||
|
||||
Run the program.
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
@ -0,0 +1,74 @@
|
||||
# 8 如何解码PCAP文件
|
||||
|
||||
|
||||
|
||||
## 8.1 简介
|
||||
|
||||
本文档展示如何解码PCAP文件, 并发送点云数据到ROS。
|
||||
|
||||
在阅读本文档之前,请确保已阅读雷达用户手册和 [参数简介](../intro/02_parameter_intro_CN.md) 。
|
||||
|
||||
|
||||
|
||||
## 8.2 步骤
|
||||
|
||||
### 8.2.1 获取数据的端口号
|
||||
|
||||
请参考雷达用户手册,或者使用第三方工具(WireShark等)抓包,得到雷达的目标MSOP端口和目标DIFOP端口。端口的默认值分别为`6699`和`7788`。
|
||||
|
||||
### 8.2.2 设置参数文件
|
||||
|
||||
设置参数文件```config.yaml```。
|
||||
|
||||
#### 8.2.2.1 common部分
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 3
|
||||
send_packet_ros: false
|
||||
send_point_cloud_ros: true
|
||||
```
|
||||
|
||||
消息来自PCAP包,所以设置 ```msg_source = 3``` 。
|
||||
|
||||
将点云发送到ROS以便查看,所以设置 ```send_point_cloud_ros = true``` 。
|
||||
|
||||
#### 8.2.2.2 lidar-driver部分
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
start_angle: 0
|
||||
end_angle: 360
|
||||
min_distance: 0.2
|
||||
max_distance: 200
|
||||
use_lidar_clock: true
|
||||
pcap_path: /home/robosense/lidar.pcap
|
||||
```
|
||||
|
||||
将```pcap_path``` 设置为PCAP文件的全路径。
|
||||
|
||||
将 ```lidar_type``` 设置为LiDAR类型。
|
||||
|
||||
设置 ```msop_port``` 、 ```difop_port``` 和 ```imu_port``` 为雷达数据端口号。
|
||||
|
||||
#### 8.2.2.3 lidar-ros部分
|
||||
|
||||
```yaml
|
||||
ros:
|
||||
ros_frame_id: rslidar
|
||||
ros_recv_packet_topic: /rslidar_packets
|
||||
ros_send_packet_topic: /rslidar_packets
|
||||
ros_send_imu_data_topic: /rslidar_imu_data
|
||||
ros_send_point_cloud_topic: /rslidar_points
|
||||
```
|
||||
|
||||
将 ```rslidar_imu_data``` 和```ros_send_point_cloud_topic``` 设置为发送Imu数据和发送点云的话题。
|
||||
|
||||
### 8.2.3 运行
|
||||
|
||||
运行程序。
|
||||
@ -0,0 +1,94 @@
|
||||
# 9 PCAP File - Advanced Topics
|
||||
|
||||
|
||||
|
||||
## 9.1 Introduction
|
||||
|
||||
The RoboSense LiDAR may work
|
||||
+ in unicast/multicast/broadcast mode,
|
||||
+ with VLAN layer
|
||||
+ with user layers.
|
||||
+ Also rslidar_sdk supports multi-LiDARs.
|
||||
|
||||
This document illustrates how to configure rslidar_sdk in each case.
|
||||
|
||||
Before reading this document, please be sure that you have read:
|
||||
+ LiDAR user-guide
|
||||
+ [Intro to parameters](../intro/02_parameter_intro.md)
|
||||
+ [Online LiDAR - Advanced Topics](./07_online_lidar_advanced_topics.md)
|
||||
|
||||
|
||||
|
||||
## 9.2 General Case
|
||||
|
||||
Generally, below code is for decoding a PCAP file in these cases.
|
||||
+ Broadcast/multicast/unicast mode
|
||||
+ There are multiple LiDars in a file.
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 3
|
||||
send_point_cloud_ros: true
|
||||
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
pcap_path: /home/robosense/lidar.pcap
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
ros:
|
||||
ros_frame_id: rslidar
|
||||
ros_send_point_cloud_topic: /rslidar_points
|
||||
```
|
||||
|
||||
The only exception is "Multiple Lidars with same ports but different IPs", which is not supported now.
|
||||
|
||||
|
||||
|
||||
## 9.3 VLAN
|
||||
|
||||
In some user cases, The LiDar may work on VLAN. Its packets have a VLAN layer.
|
||||

|
||||
|
||||
rs_driver decodes PCAP file and gets all parts of MSOP packets, including the VLAN layer.
|
||||
|
||||
To strip the VLAN layer, just set `use_vlan: true`.
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
pcap_path: /home/robosense/lidar.pcap
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
use_vlan: true
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 9.4 User Layer, Tail Layer
|
||||
|
||||
In some user cases, User may add extra layers before or/and after the MSOP/DIFOP packet.
|
||||
+ USER_LAYER is before the packet and TAIL_LAYER is after it.
|
||||

|
||||
|
||||
These extra layers are parts of UDP data. The driver can strip them.
|
||||
|
||||
To strip them, just give their lengths in bytes.
|
||||
|
||||
In the following example, USER_LAYER is 8 bytes, and TAIL_LAYER is 4 bytes.
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
pcap_path: /home/robosense/lidar.pcap
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
user_layer_bytes: 8
|
||||
tail_layer_bytes: 4
|
||||
```
|
||||
|
||||
@ -0,0 +1,92 @@
|
||||
# 9 PCAP文件 - 高级主题
|
||||
|
||||
|
||||
|
||||
## 9.1 简介
|
||||
|
||||
RoboSense雷达可以工作在如下场景。
|
||||
+ 单播/组播/广播模式
|
||||
+ 运行在VLAN协议上
|
||||
+ 向Packet中加入用户自己的层
|
||||
+ 接入多个雷达
|
||||
|
||||
本文说明在每种场景下,如何配置rslidar_sdk。
|
||||
|
||||
在阅读本文之前,请先阅读:
|
||||
+ 雷达用户使用手册
|
||||
+ [参数介绍](../intro/02_parameter_intro_CN.md)
|
||||
+ [在线雷达-高级主题](./07_online_lidar_advanced_topics_CN.md)
|
||||
|
||||
|
||||
|
||||
## 9.2 一般场景
|
||||
|
||||
在下列场景下,使用如下配置解码PCAP文件。
|
||||
+ 广播/组播/单播模式
|
||||
+ PCAP文件中有多个雷达
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 3
|
||||
send_point_cloud_ros: true
|
||||
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
pcap_path: /home/robosense/lidar.pcap
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
ros:
|
||||
ros_frame_id: rslidar
|
||||
ros_send_point_cloud_topic: /rslidar_points
|
||||
```
|
||||
|
||||
一个例外是:PCAP文件中有多个雷达数据,但这些雷达目的端口相同,使用不同的目的IP地址来区分。这种情况不支持。
|
||||
|
||||
|
||||
|
||||
## 9.3 VLAN
|
||||
|
||||
有些场景下,雷达工作在VLAN环境下。这时MSOP/DIFOP包带VLAN层,如下图。
|
||||

|
||||
|
||||
rs_driver使用libpcap库解析PCAP文件,可以得到完整的、包括VLAN层的MSOP/DIFOP包。
|
||||
|
||||
要剥除VLAN层,只需要设置`use_vlan: true`。
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
pcap_path: /home/robosense/lidar.pcap
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
use_vlan: true
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 9.4 User Layer, Tail Layer
|
||||
|
||||
某些场景下,用户可能在MSOP/DIFOP数据前后加入自己的层。
|
||||
+ USER_LAYER 在MSOP/DIFOP数据之前,TAIL_LAYER在MSOP/DIFOP数据之后。
|
||||

|
||||
|
||||
这些层是UDP数据的一部分,所以rs_driver可以自己剥除他们。只需要告诉它每个层的字节数就可以。
|
||||
|
||||
如下的例子中,指定USER_LAYER为8字节,TAIL_LAYER为4字节。
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
pcap_path: /home/robosense/lidar.pcap
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
user_layer_bytes: 8
|
||||
tail_layer_bytes: 4
|
||||
```
|
||||
|
||||
@ -0,0 +1,80 @@
|
||||
# 10 How to use coordinate transformation
|
||||
|
||||
|
||||
|
||||
## 10.1 Introduction
|
||||
|
||||
rslidar_sdk can transform the coordinate of point cloud. This document illustrate how to do so.
|
||||
|
||||
Please check the [Intro to hiding parameters](../intro/03_hiding_parameters_intro.md) for more details. Here is an example of the config.yaml.
|
||||
|
||||
|
||||
|
||||
## 10.2 Dependencies
|
||||
|
||||
rslidar_sdk depends on the libeigen library to do coordinate transformation. Please install it first.
|
||||
|
||||
```bash
|
||||
sudo apt-get install libeigen3-dev
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 10.3 Compile
|
||||
|
||||
To enable transformation, set the CMake option ```ENABLE_TRANSFORM```to be ```ON```.
|
||||
|
||||
- Compile directly
|
||||
|
||||
```bash
|
||||
cmake -DENABLE_TRANSFORM=ON ..
|
||||
```
|
||||
|
||||
- ROS
|
||||
|
||||
```bash
|
||||
catkin_make -DENABLE_TRANSFORM=ON
|
||||
```
|
||||
|
||||
- ROS2
|
||||
|
||||
```bash
|
||||
colcon build --cmake-args '-DENABLE_TRANSFORM=ON'
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 10.4 Set LiDAR parameters
|
||||
|
||||
In the `lidar-driver` part of `config.yaml`, set the hiding parameter`x`, `y`, `z`, `roll`, `pitch` ,`yaw`.
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 1
|
||||
send_packet_ros: false
|
||||
send_point_cloud_ros: true
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
start_angle: 0
|
||||
end_angle: 360
|
||||
min_distance: 0.2
|
||||
max_distance: 200
|
||||
use_lidar_clock: true
|
||||
pcap_path: /home/robosense/lidar.pcap
|
||||
x: 1
|
||||
y: 0
|
||||
z: 2.5
|
||||
roll: 0.1
|
||||
pitch: 0.2
|
||||
yaw: 1.57
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 10.5 Run
|
||||
|
||||
Run the program.
|
||||
@ -0,0 +1,80 @@
|
||||
# 10 如何使用坐标变换功能
|
||||
|
||||
|
||||
|
||||
## 10.1 简介
|
||||
|
||||
rslidar_sdk支持对点云进行坐标变换,本文档展示如何作这种变换。
|
||||
|
||||
在阅读本文档之前,请确保已阅读雷达用户手册和[隐藏参数介绍](../intro/03_hiding_parameters_intro_CN.md)。
|
||||
|
||||
|
||||
|
||||
## 10.2 依赖库
|
||||
|
||||
rslidar_sdk的坐标变换基于libeigen库,所以要先安装它。
|
||||
|
||||
```bash
|
||||
sudo apt-get install libeigen3-dev
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 10.3 编译
|
||||
|
||||
要启用坐标变换,编译rslidar_sdk时,需要将```ENABLE_TRANSFORM```选项设置为```ON```.
|
||||
|
||||
- 直接编译
|
||||
|
||||
```bash
|
||||
cmake -DENABLE_TRANSFORM=ON ..
|
||||
```
|
||||
|
||||
- ROS
|
||||
|
||||
```bash
|
||||
catkin_make -DENABLE_TRANSFORM=ON
|
||||
```
|
||||
|
||||
- ROS2
|
||||
|
||||
```bash
|
||||
colcon build --cmake-args '-DENABLE_TRANSFORM=ON'
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 10.4 设置雷达参数
|
||||
|
||||
在`config.yaml`中,设置`lidar-lidar`部分的参数`x`、, `y`、 `z`、 `roll`、 `pitch` 、`yaw`。
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 1
|
||||
send_packet_ros: false
|
||||
send_point_cloud_ros: true
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
start_angle: 0
|
||||
end_angle: 360
|
||||
min_distance: 0.2
|
||||
max_distance: 200
|
||||
use_lidar_clock: true
|
||||
pcap_path: /home/robosense/lidar.pcap
|
||||
x: 1
|
||||
y: 0
|
||||
z: 2.5
|
||||
roll: 0.1
|
||||
pitch: 0.2
|
||||
yaw: 1.57
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 10.5 运行
|
||||
|
||||
运行程序。
|
||||
@ -0,0 +1,110 @@
|
||||
# 11 How to record and replay Packet rosbag
|
||||
|
||||
|
||||
|
||||
## 11.1 Introduction
|
||||
|
||||
This document illustrates how to record and replay MSOP/DIFOP Packet rosbag.
|
||||
|
||||
It is possible to record the point cloud message into a rosbag and replay it, but the point cloud rosbag is very large. rslidar_sdk provides a better way - record packet rosbag and replay it.
|
||||
|
||||
Please be sure you have read the LiDAR user-guide and [Connect to online LiDAR and send point cloud through ROS](./06_how_to_decode_online_lidar.md).
|
||||
|
||||
|
||||
|
||||
## 11.2 Record
|
||||
|
||||
### 11.2.1 Send packet to ROS
|
||||
|
||||
Here suppose that you have connected to an on-line LiDAR, and have sent the point cloud to ROS.
|
||||
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 1
|
||||
send_packet_ros: true
|
||||
send_point_cloud_ros: true
|
||||
```
|
||||
|
||||
To record packets, set ```send_packet_ros = true```.
|
||||
|
||||
### 11.2.2 Record the topic of packet
|
||||
|
||||
To change the topic of packet, change ```ros_send_packet_topic```. This topic sends out both MSOP and DIFOP packets.
|
||||
|
||||
```yaml
|
||||
ros:
|
||||
ros_frame_id: rslidar
|
||||
ros_recv_packet_topic: /rslidar_packets
|
||||
ros_send_packet_topic: /rslidar_packets
|
||||
ros_send_imu_data_topic: /rslidar_imu_data
|
||||
ros_send_point_cloud_topic: /rslidar_points
|
||||
```
|
||||
|
||||
Record rosbag as below.
|
||||
|
||||
```sh
|
||||
rosbag record /rslidar_packets -O bag
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 11.3 Replay
|
||||
|
||||
Suppose you have recorded a rosbag, which contains MSOP/DIFOP packets with the topic ```/rslidar_packets```.
|
||||
|
||||
### 11.3.1 Set Packet Source
|
||||
|
||||
In `config.yaml`, set the `common` part.
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 2
|
||||
send_packet_ros: false
|
||||
send_point_cloud_ros: true
|
||||
```
|
||||
|
||||
Packet is from the ROS, so set ```msg_source = 2```.
|
||||
|
||||
To send point cloud to ROS, set ```send_point_cloud_ros = true```.
|
||||
|
||||
### 11.3.2 Set parameters of Lidar
|
||||
|
||||
In `config.yaml`, set the `lidar-driver` part.
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
start_angle: 0
|
||||
end_angle: 360
|
||||
min_distance: 0.2
|
||||
max_distance: 200
|
||||
use_lidar_clock: true
|
||||
```
|
||||
|
||||
Set the ```lidar_type``` to your LiDAR type.
|
||||
|
||||
### 11.3.3 Set Topic of packet.
|
||||
|
||||
In `config.yaml`, set the `lidar-ros` part.
|
||||
|
||||
```yaml
|
||||
ros:
|
||||
ros_frame_id: rslidar
|
||||
ros_recv_packet_topic: /rslidar_packets
|
||||
ros_send_packet_topic: /rslidar_packets
|
||||
ros_send_imu_data_topic: /rslidar_imu_data
|
||||
ros_send_point_cloud_topic: /rslidar_points
|
||||
```
|
||||
|
||||
To receive MSOP/DIFOP packest, set ```ros_recv_packet_topic``` to the topic in the rosbag.
|
||||
|
||||
### 11.3.4 Run
|
||||
|
||||
Run the demo, and replay rosbag.
|
||||
|
||||
|
||||
@ -0,0 +1,113 @@
|
||||
# 11 如何录制与回放 Packet rosbag
|
||||
|
||||
|
||||
|
||||
## 11.1 简介
|
||||
|
||||
本文档展示如何记录与回放MSOP/DIFOP rosbag。
|
||||
|
||||
使用ROS可以录制点云rosbag消息并回放,但点云包非常大,所以rslidar_sdk提供更好的选择,也就是录制Packet rosbag并回放。
|
||||
|
||||
在阅读本文档之前, 请先阅读雷达用户手册和 [连接在线雷达并发送点云到ROS](./06_how_to_decode_online_lidar_CN.md) 。
|
||||
|
||||
|
||||
|
||||
## 11.2 录制
|
||||
|
||||
### 11.2.1 将MSOP/DIFOP Packet发送至ROS
|
||||
|
||||
这里假设已经连接在线雷达,并能发送点云到ROS。
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 1
|
||||
send_packet_ros: true
|
||||
send_point_cloud_ros: true
|
||||
```
|
||||
|
||||
要录制Packet, 设置 ```send_packet_ros = true```。
|
||||
|
||||
### 11.2.2 根据话题录制rosbag
|
||||
|
||||
修改```ros_send_packet_topic```, 来改变发送的话题。这个话题包括MSOP Packet和DIFOP Packet。
|
||||
|
||||
```yaml
|
||||
ros:
|
||||
ros_frame_id: rslidar
|
||||
ros_recv_packet_topic: /rslidar_packets
|
||||
ros_send_packet_topic: /rslidar_packets
|
||||
ros_send_imu_data_topic: /rslidar_imu_data
|
||||
ros_send_point_cloud_topic: /rslidar_points
|
||||
```
|
||||
|
||||
ROS录制rosbag的指令如下。
|
||||
|
||||
```bash
|
||||
rosbag record /rslidar_packets -O bag
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 11.3 回放
|
||||
|
||||
假设录制了一个rosbag,其中包含话题为 `/rslidar_packets` 的MSOP/DIFOP Packet。
|
||||
|
||||
### 11.3.1 设置Packet源
|
||||
|
||||
配置`config.yaml`的`common`部分。
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 2
|
||||
send_packet_ros: false
|
||||
send_point_cloud_ros: true
|
||||
```
|
||||
|
||||
MSOP/DIFOP Packet来自ROS rosbag,因此设置 ```msg_source = 2``` 。
|
||||
|
||||
将点云发送到ROS,因此设置 ```send_point_cloud_ros = true```。
|
||||
|
||||
### 11.3.2 设置雷达参数
|
||||
|
||||
配置`config.yaml`的`lidar-driver`部分。
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSAIRY
|
||||
msop_port: 6699
|
||||
difop_port: 7788
|
||||
imu_port: 6688
|
||||
start_angle: 0
|
||||
end_angle: 360
|
||||
min_distance: 0.2
|
||||
max_distance: 200
|
||||
use_lidar_clock: true
|
||||
```
|
||||
|
||||
将 ```lidar_type``` 设置为LiDAR类型 。
|
||||
|
||||
### 11.3.3 设置接收Packet的主题
|
||||
|
||||
设置`config.yaml`的`lidar-ros`部分。
|
||||
|
||||
```yaml
|
||||
ros:
|
||||
ros_frame_id: rslidar
|
||||
ros_recv_packet_topic: /rslidar_packets
|
||||
ros_send_packet_topic: /rslidar_packets
|
||||
ros_send_imu_data_topic: /rslidar_imu_data
|
||||
ros_send_point_cloud_topic: /rslidar_points
|
||||
```
|
||||
|
||||
将 ```ros_recv_packet_topic``` 设置为rosbag中MSOP/DIFOP Packet的话题。
|
||||
|
||||
|
||||
|
||||
### 11.3.4 运行
|
||||
|
||||
运行程序,回放rosbag。
|
||||
|
||||
|
||||
|
||||
|
||||
35
src/airy/rslidar_sdk-main/doc/howto/12_how_to_create_deb.md
Normal file
@ -0,0 +1,35 @@
|
||||
# 12 How to create deb
|
||||
|
||||
|
||||
|
||||
## 12.1 Introduction
|
||||
|
||||
Generating a ".deb" installable file is useful.
|
||||
|
||||
|
||||
|
||||
## 12.2 Create deb
|
||||
|
||||
Just run the shell script:
|
||||
```
|
||||
./create_debian.sh
|
||||
```
|
||||
The deb file will be generated in the parent directory of `rslidar_sdk`.
|
||||
|
||||
|
||||
## 12.3 Use the deb
|
||||
|
||||
Install the deb and set the right config_path. If leave the config_path empty, it will use the `config.yaml` in the ros package path.
|
||||
|
||||
```
|
||||
<launch>
|
||||
<node pkg="rslidar_sdk" name="rslidar_sdk_node" type="rslidar_sdk_node" output="screen">
|
||||
<param name="config_path" value=""/>
|
||||
</node>
|
||||
<!-- rviz -->
|
||||
<node pkg="rviz" name="rviz" type="rviz" args="-d $(find rslidar_sdk)/rviz/rviz.rviz" />
|
||||
</launch>
|
||||
```
|
||||
|
||||
|
||||
|
||||
BIN
src/airy/rslidar_sdk-main/doc/howto/img/04_01_packet_rosbag.png
Normal file
|
After Width: | Height: | Size: 44 KiB |
BIN
src/airy/rslidar_sdk-main/doc/howto/img/07_01_broadcast.png
Normal file
|
After Width: | Height: | Size: 11 KiB |
BIN
src/airy/rslidar_sdk-main/doc/howto/img/07_02_unicast.png
Normal file
|
After Width: | Height: | Size: 10 KiB |
BIN
src/airy/rslidar_sdk-main/doc/howto/img/07_03_multicast.png
Normal file
|
After Width: | Height: | Size: 12 KiB |
|
After Width: | Height: | Size: 23 KiB |
|
After Width: | Height: | Size: 23 KiB |
BIN
src/airy/rslidar_sdk-main/doc/howto/img/07_06_vlan_layer.png
Normal file
|
After Width: | Height: | Size: 8.0 KiB |
BIN
src/airy/rslidar_sdk-main/doc/howto/img/07_07_vlan.png
Normal file
|
After Width: | Height: | Size: 15 KiB |
BIN
src/airy/rslidar_sdk-main/doc/howto/img/07_08_user_layer.png
Normal file
|
After Width: | Height: | Size: 10 KiB |
272
src/airy/rslidar_sdk-main/doc/intro/02_parameter_intro.md
Normal file
@ -0,0 +1,272 @@
|
||||
# 2 Introduction to Parameters
|
||||
|
||||
rslidar_sdk reads parameters from the configuration file ```config.yaml```, which is stored in ```rslidar_sdk/config```.
|
||||
|
||||
`config.yaml` contains two parts, the `common` part and the `lidar` part.
|
||||
|
||||
rslidar_sdk supports multi-LiDARs case. The `common` part is shared by all LiDARs, while in the `lidar` part, each child node is for an individual Lidar.
|
||||
|
||||
**config.yaml is indentation sensitive! Please make sure the indentation is not changed after adjusting the parameters!**
|
||||
|
||||
|
||||
|
||||
## 2.1 Common
|
||||
|
||||
The `common` part specifies the source of LiDAR packets, and where to publish point clouds and packets.
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 1
|
||||
send_packet_ros: false
|
||||
send_point_cloud_ros: false
|
||||
```
|
||||
|
||||
- msg_source
|
||||
|
||||
- 0 -- Unused. Never set this parameter to 0.
|
||||
|
||||
- 1 -- LiDAR packets come from on-line LiDARs. For more details, please refer to [Connect to online LiDAR and send point cloud through ROS](../howto/06_how_to_decode_online_lidar.md)
|
||||
|
||||
- 2 -- LiDAR packets come from ROS/ROS2. It is used to decode from an off-line rosbag. For more details, please refer to [Record rosbag & Replay it](../howto/11_how_to_record_replay_packet_rosbag.md)
|
||||
|
||||
- 3 -- LiDAR packets come from a PCAP bag. For more details, please refer to [Decode PCAP file and send point cloud through ROS](../howto/08_how_to_decode_pcap_file.md)
|
||||
|
||||
- send_packet_ros
|
||||
|
||||
- true -- LiDAR packets will be sent to ROS/ROS2.
|
||||
|
||||
*The ROS Packet message is of a customized message type, so you can't print its content via the ROS `echo` command. This option is used to record off-line Packet rosbags. For more details, please refer to the case of msg_source=2.*
|
||||
|
||||
- send_point_cloud_ros
|
||||
|
||||
- true -- The LiDAR point cloud will be sent to ROS/ROS2.
|
||||
|
||||
*The ROS point cloud type is the ROS official defined type -- sensor_msgs/PointCloud2, so it can be visualized on the ROS `rviz` tool directly. It is not suggested to record the point cloud to rosbag, because its size may be very large. Please record Packets instead. Refer to the case of msg_source=2.*
|
||||
|
||||
|
||||
|
||||
## 2.2 lidar
|
||||
|
||||
The `lidar` part needs to be adjusted for every LiDAR seperately.
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSM1 # LiDAR type - RS16, RS32, RSBP, RSAIRY, RSHELIOS, RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48,
|
||||
# RSM1, RSM1_JUMBO, RSM2, RSM3, RSE1, RSMX.
|
||||
|
||||
msop_port: 6699 # Msop port of lidar
|
||||
difop_port: 7788 # Difop port of lidar
|
||||
imu_port: 0 # IMU port of lidar(only for RSAIRY, RSE1), 0 means no imu.
|
||||
# If you want to use IMU, please first set ENABLE_IMU_DATA_PARSE to ON in CMakeLists.txt
|
||||
user_layer_bytes: 0 # Bytes of user layer. thers is no user layer if it is 0
|
||||
tail_layer_bytes: 0 # Bytes of tail layer. thers is no tail layer if it is 0
|
||||
|
||||
|
||||
min_distance: 0.2 # Minimum distance of point cloud
|
||||
max_distance: 200 # Maximum distance of point cloud
|
||||
use_lidar_clock: true # true--Use the lidar clock as the message timestamp
|
||||
# false-- Use the system clock as the timestamp
|
||||
dense_points: false # true: discard NAN points; false: reserve NAN points
|
||||
|
||||
ts_first_point: true # true: time-stamp point cloud with the first point; false: with the last point;
|
||||
# these parameters are used from mechanical lidar
|
||||
|
||||
start_angle: 0 # Start angle of point cloud
|
||||
end_angle: 360 # End angle of point cloud
|
||||
|
||||
# When msg_source is 3, the following parameters will be used
|
||||
pcap_repeat: true # true: The pcap bag will repeat play
|
||||
pcap_rate: 1.0 # Rate to read the pcap file
|
||||
pcap_path: /home/robosense/lidar.pcap #The path of pcap file
|
||||
|
||||
ros:
|
||||
ros_frame_id: rslidar #Frame id of packet message and point cloud message
|
||||
ros_recv_packet_topic: /rslidar_packets #Topic used to receive lidar packets from ROS
|
||||
ros_send_packet_topic: /rslidar_packets #Topic used to send lidar packets through ROS
|
||||
ros_send_imu_data_topic: /rslidar_imu_data #Topic used to send imu data through ROS
|
||||
ros_send_point_cloud_topic: /rslidar_points #Topic used to send point cloud through ROS
|
||||
```
|
||||
|
||||
- lidar_type
|
||||
|
||||
Supported LiDAR types are listed in the README file.
|
||||
|
||||
- msop_port, difop_port, imu_port
|
||||
|
||||
The MSOP/DIFOP/IMU port to receive LiDAR packets. *If no data is received, please check these parameters first.*
|
||||
|
||||
- user_layer_bytes, tail_layer_bytes
|
||||
|
||||
The number of bytes of the user layer and tail layer.
|
||||
|
||||
- min_distance, max_distance
|
||||
|
||||
The minimum distance and maximum distance of the point cloud.
|
||||
|
||||
- use_lidar_clock
|
||||
|
||||
- true -- Use the Lidar clock as the message timestamp
|
||||
- false -- Use the host machine clock as the message timestamp
|
||||
|
||||
- dense_points
|
||||
|
||||
Whether to discard NAN points. The default value is ```false```.
|
||||
- Discard if ```true```
|
||||
- reserve if ```false```.
|
||||
|
||||
- ts_first_point
|
||||
|
||||
Stamp the point cloud with the first point or the last one. Stamp with the first point if ```true```, else stamp with the last point if ```false```. The default value is ```false```.
|
||||
|
||||
- start_angle, end_angle
|
||||
|
||||
The start angle and end angle of the point cloud, which should be in the range of 0~360°. *`start_angle` can be larger than `end_angle`*.
|
||||
|
||||
- pcap_path
|
||||
|
||||
The full path of the PCAP file. Valid if msg_source = 3.
|
||||
|
||||
- ros_send_by_rows
|
||||
|
||||
Meaningful only for Mechanical Lidars, and valid if dense_points = false。
|
||||
- true -- send point cloud row by row
|
||||
- false -- send point cloud clolumn by column
|
||||
|
||||
|
||||
|
||||
## 2.3 Examples
|
||||
|
||||
### 2.3.1 Single Lidar Case
|
||||
|
||||
Connect to 1 LiDAR of RSM1, and send point cloud to ROS.
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 1 # 0: not use Lidar
|
||||
# 1: packet message comes from online Lidar
|
||||
# 2: packet message comes from ROS or ROS2
|
||||
# 3: packet message comes from Pcap file
|
||||
send_packet_ros: false # true: Send packets through ROS or ROS2(Used to record packet)
|
||||
send_point_cloud_ros: true # true: Send point cloud through ROS or ROS2
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSM1 # LiDAR type - RS16, RS32, RSBP, RSAIRY, RSHELIOS, RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48,
|
||||
# RSM1, RSM1_JUMBO, RSM2, RSM3, RSE1, RSMX.
|
||||
|
||||
msop_port: 6699 # Msop port of lidar
|
||||
difop_port: 7788 # Difop port of lidar
|
||||
imu_port: 0 # IMU port of lidar(only for RSAIRY, RSE1), 0 means no imu.
|
||||
# If you want to use IMU, please first set ENABLE_IMU_DATA_PARSE to ON in CMakeLists.txt
|
||||
user_layer_bytes: 0 # Bytes of user layer. thers is no user layer if it is 0
|
||||
tail_layer_bytes: 0 # Bytes of tail layer. thers is no tail layer if it is 0
|
||||
|
||||
|
||||
min_distance: 0.2 # Minimum distance of point cloud
|
||||
max_distance: 200 # Maximum distance of point cloud
|
||||
use_lidar_clock: true # true--Use the lidar clock as the message timestamp
|
||||
# false-- Use the system clock as the timestamp
|
||||
dense_points: false # true: discard NAN points; false: reserve NAN points
|
||||
|
||||
ts_first_point: true # true: time-stamp point cloud with the first point; false: with the last point;
|
||||
# these parameters are used from mechanical lidar
|
||||
|
||||
start_angle: 0 # Start angle of point cloud
|
||||
end_angle: 360 # End angle of point cloud
|
||||
|
||||
# When msg_source is 3, the following parameters will be used
|
||||
pcap_repeat: true # true: The pcap bag will repeat play
|
||||
pcap_rate: 1.0 # Rate to read the pcap file
|
||||
pcap_path: /home/robosense/lidar.pcap #The path of pcap file
|
||||
|
||||
ros:
|
||||
ros_frame_id: rslidar #Frame id of packet message and point cloud message
|
||||
ros_recv_packet_topic: /rslidar_packets #Topic used to receive lidar packets from ROS
|
||||
ros_send_packet_topic: /rslidar_packets #Topic used to send lidar packets through ROS
|
||||
ros_send_imu_data_topic: /rslidar_imu_data #Topic used to send imu data through ROS
|
||||
ros_send_point_cloud_topic: /rslidar_points #Topic used to send point cloud through ROS
|
||||
```
|
||||
|
||||
### 2.3.2 Multi Lidar Case
|
||||
|
||||
Connect to 1 LiDAR of RSM1, and 1 LiDAR of RSE1, and send point cloud to ROS.
|
||||
|
||||
*Pay attention to the indentation of the `lidar` part*
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 1
|
||||
send_packet_ros: false
|
||||
send_point_cloud_ros: true
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSM1 # LiDAR type - RS16, RS32, RSBP, RSAIRY, RSHELIOS, RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48,
|
||||
# RSM1, RSM1_JUMBO, RSM2, RSM3, RSE1, RSMX.
|
||||
|
||||
msop_port: 6699 # Msop port of lidar
|
||||
difop_port: 7788 # Difop port of lidar
|
||||
imu_port: 0 # IMU port of lidar(only for RSAIRY, RSE1), 0 means no imu.
|
||||
# If you want to use IMU, please first set ENABLE_IMU_DATA_PARSE to ON in CMakeLists.txt
|
||||
user_layer_bytes: 0 # Bytes of user layer. thers is no user layer if it is 0
|
||||
tail_layer_bytes: 0 # Bytes of tail layer. thers is no tail layer if it is 0
|
||||
|
||||
|
||||
min_distance: 0.2 # Minimum distance of point cloud
|
||||
max_distance: 200 # Maximum distance of point cloud
|
||||
use_lidar_clock: true # true--Use the lidar clock as the message timestamp
|
||||
# false-- Use the system clock as the timestamp
|
||||
dense_points: false # true: discard NAN points; false: reserve NAN points
|
||||
|
||||
ts_first_point: true # true: time-stamp point cloud with the first point; false: with the last point;
|
||||
# these parameters are used from mechanical lidar
|
||||
|
||||
start_angle: 0 # Start angle of point cloud
|
||||
end_angle: 360 # End angle of point cloud
|
||||
|
||||
# When msg_source is 3, the following parameters will be used
|
||||
pcap_repeat: true # true: The pcap bag will repeat play
|
||||
pcap_rate: 1.0 # Rate to read the pcap file
|
||||
pcap_path: /home/robosense/lidar.pcap #The path of pcap file
|
||||
|
||||
ros:
|
||||
ros_frame_id: rslidar #Frame id of packet message and point cloud message
|
||||
ros_recv_packet_topic: /left/rslidar_packets #Topic used to receive lidar packets from ROS
|
||||
ros_send_packet_topic: /left/rslidar_packets #Topic used to send lidar packets through ROS
|
||||
ros_send_imu_data_topic: /left/rslidar_imu_data #Topic used to send imu data through ROS
|
||||
ros_send_point_cloud_topic: /left/rslidar_points #Topic used to send point cloud through ROS
|
||||
|
||||
- driver:
|
||||
lidar_type: RSE1 # LiDAR type - RS16, RS32, RSBP, RSAIRY, RSHELIOS, RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48,
|
||||
# RSM1, RSM1_JUMBO, RSM2, RSM3, RSE1, RSMX.
|
||||
msop_port: 6699 # Msop port of lidar
|
||||
difop_port: 7788 # Difop port of lidar
|
||||
|
||||
user_layer_bytes: 0 # Bytes of user layer. thers is no user layer if it is 0
|
||||
tail_layer_bytes: 0 # Bytes of tail layer. thers is no tail layer if it is 0
|
||||
|
||||
|
||||
min_distance: 0.2 # Minimum distance of point cloud
|
||||
max_distance: 200 # Maximum distance of point cloud
|
||||
use_lidar_clock: true # true--Use the lidar clock as the message timestamp
|
||||
# false-- Use the system clock as the timestamp
|
||||
dense_points: false # true: discard NAN points; false: reserve NAN points
|
||||
|
||||
ts_first_point: true # true: time-stamp point cloud with the first point; false: with the last point;
|
||||
# these parameters are used from mechanical lidar
|
||||
|
||||
start_angle: 0 # Start angle of point cloud
|
||||
end_angle: 360 # End angle of point cloud
|
||||
|
||||
# When msg_source is 3, the following parameters will be used
|
||||
pcap_repeat: true # true: The pcap bag will repeat play
|
||||
pcap_rate: 1.0 # Rate to read the pcap file
|
||||
pcap_path: /home/robosense/lidar.pcap #The path of pcap file
|
||||
|
||||
ros:
|
||||
ros_frame_id: rslidar #Frame id of packet message and point cloud message
|
||||
ros_recv_packet_topic: /right/rslidar_packets #Topic used to receive lidar packets from ROS
|
||||
ros_send_packet_topic: /right/rslidar_packets #Topic used to send lidar packets through ROS
|
||||
ros_send_imu_data_topic: /right/rslidar_imu_data #Topic used to send imu data through ROS
|
||||
ros_send_point_cloud_topic: /right/rslidar_points #Topic used to send point cloud through ROS
|
||||
```
|
||||
|
||||
276
src/airy/rslidar_sdk-main/doc/intro/02_parameter_intro_CN.md
Normal file
@ -0,0 +1,276 @@
|
||||
# 2 参数介绍
|
||||
|
||||
rslidar_sdk读取配置文件 ```config.yaml```,得到所有的参数。```config.yaml```在```rslidar_sdk/config```文件夹中。
|
||||
|
||||
**config.yaml遵循YAML格式。该格式对缩进有严格要求。修改config.yaml之后,请确保每行开头的缩进仍保持一致!**
|
||||
|
||||
config.yaml包括两部分:common部分 和 lidar部分。
|
||||
|
||||
rslidar_sdk支持多个雷达。common部分为所有雷达共享。lidar部分,每一个子节点对应一个雷达,针对这个雷达的实际情况分别设置。
|
||||
|
||||
|
||||
|
||||
## 2.1 common部分
|
||||
|
||||
common部分设置雷达消息的源(Packet或点云从哪来)和目标(Packet或点云发布到哪去)。
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 1
|
||||
send_packet_ros: false
|
||||
send_point_cloud_ros: false
|
||||
```
|
||||
|
||||
- msg_source
|
||||
|
||||
- 1 -- 连接在线雷达。更多使用细节,请参考[连接在线雷达并发送点云到ROS](../howto/06_how_to_decode_online_lidar_CN.md)。
|
||||
|
||||
- 2 -- 离线解析ROS/ROS2的Packet包。更多使用细节,请参考 [录制ROS数据包然后播放它](../howto/11_how_to_record_replay_packet_rosbag_CN.md)。
|
||||
|
||||
- 3 -- 离线解析PCAP包。更多使用细节,请参考[离线解析PCAP包并发送点云到ROS](../howto/08_how_to_decode_pcap_file_CN.md)。
|
||||
|
||||
- send_packet_ros
|
||||
|
||||
- true -- 雷达Packet消息将通过ROS/ROS2发出
|
||||
|
||||
*雷达ROS packet消息为速腾聚创自定义ROS消息,用户使用ROS/ROS2 echo命令不能查看消息的具体内容。这个功能用于录制ROS/ROS2的Packet包,更多使用细节,请参考msg_source=2的情况。
|
||||
|
||||
- send_point_cloud_ros
|
||||
|
||||
- true -- 雷达点云消息将通过ROS/ROS2发出
|
||||
|
||||
*点云消息的类型为ROS官方定义的点云类型sensor_msgs/PointCloud2, 用户可以使用Rviz直接查看点云。用户可以录制ROS/ROS2的点云包,但点云包的体积非常大,所以不建议这么做。更好的方式是录制Packet包,请参考send_packet_ros=true的情况。*
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
## 2.2 lidar部分
|
||||
|
||||
lidar部分根据每个雷达的实际情况进行设置。
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSM1 # LiDAR type - RS16, RS32, RSBP, RSAIRY, RSHELIOS, RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48,
|
||||
# RSM1, RSM1_JUMBO, RSM2, RSM3, RSE1, RSMX.
|
||||
|
||||
msop_port: 6699 # Msop port of lidar
|
||||
difop_port: 7788 # Difop port of lidar
|
||||
imu_port: 0 # IMU port of lidar(only for RSAIRY, RSE1), 0 means no imu.
|
||||
# If you want to use IMU, please first set ENABLE_IMU_DATA_PARSE to ON in CMakeLists.txt
|
||||
user_layer_bytes: 0 # Bytes of user layer. thers is no user layer if it is 0
|
||||
tail_layer_bytes: 0 # Bytes of tail layer. thers is no tail layer if it is 0
|
||||
|
||||
|
||||
min_distance: 0.2 # Minimum distance of point cloud
|
||||
max_distance: 200 # Maximum distance of point cloud
|
||||
use_lidar_clock: true # true--Use the lidar clock as the message timestamp
|
||||
# false-- Use the system clock as the timestamp
|
||||
dense_points: false # true: discard NAN points; false: reserve NAN points
|
||||
|
||||
ts_first_point: true # true: time-stamp point cloud with the first point; false: with the last point;
|
||||
# these parameters are used from mechanical lidar
|
||||
|
||||
start_angle: 0 # Start angle of point cloud
|
||||
end_angle: 360 # End angle of point cloud
|
||||
|
||||
# When msg_source is 3, the following parameters will be used
|
||||
pcap_repeat: true # true: The pcap bag will repeat play
|
||||
pcap_rate: 1.0 # Rate to read the pcap file
|
||||
pcap_path: /home/robosense/lidar.pcap #The path of pcap file
|
||||
|
||||
ros:
|
||||
ros_frame_id: rslidar #Frame id of packet message and point cloud message
|
||||
ros_recv_packet_topic: /rslidar_packets #Topic used to receive lidar packets from ROS
|
||||
ros_send_packet_topic: /rslidar_packets #Topic used to send lidar packets through ROS
|
||||
ros_send_imu_data_topic: /rslidar_imu_data #Topic used to send imu data through ROS
|
||||
ros_send_point_cloud_topic: /rslidar_points #Topic used to send point cloud through ROS
|
||||
```
|
||||
|
||||
- lidar_type
|
||||
|
||||
支持的雷达型号在rslidar_sdk的README文件中列出。
|
||||
|
||||
- msop_port, difop_port, imu_port
|
||||
|
||||
接收MSOP/DIFOP/IMU Packet的msop端口号、difop端口号、 Imu端口号。 *若收不到消息,请优先确认这些参数是否配置正确。*
|
||||
|
||||
- user_layer_bytes, tail_layer_bytes
|
||||
|
||||
用户自定义层和尾部层的字节数。默认为0。
|
||||
|
||||
|
||||
- min_distance, max_distance
|
||||
|
||||
点云的最小距离和最大距离。这个设置是软件屏蔽,会将区域外的点设置为NAN点,不会减小每帧点云的体积。
|
||||
|
||||
- use_lidar_clock
|
||||
|
||||
- true -- 使用雷达时间作为消息时间戳。
|
||||
- false -- 使用电脑主机时间作为消息时间戳。
|
||||
|
||||
- dense_points
|
||||
|
||||
输出的点云中是否剔除NAN points。默认值为false。
|
||||
- true 为剔除,
|
||||
- false为不剔除。
|
||||
|
||||
- ts_first_point
|
||||
|
||||
默认值为false。点云的时间戳是否第一个点的时间。true使用第一个点的时间,false使用第一个点的时间。
|
||||
|
||||
- start_angle, end_angle
|
||||
|
||||
点云消息的起始角度和结束角度。这个设置是软件屏蔽,将区域外的点设置为NAN点,不会减小每帧点云的体积。 start_angle和end_angle的范围是0~360°,**起始角可以大于结束角**.
|
||||
|
||||
- pcap_path
|
||||
|
||||
pcap包的路径。当 msg_source=3 时有效。
|
||||
|
||||
- pcap_rate
|
||||
|
||||
pcap包播放的倍率。当 msg_source=3 时有效。
|
||||
|
||||
- pcap_repeat
|
||||
|
||||
pcap包是否重复播放。当 msg_source=3 时有效。
|
||||
|
||||
|
||||
|
||||
|
||||
## 2.3 示例
|
||||
|
||||
### 2.3.1 单台雷达
|
||||
|
||||
在线连接1台RSM1雷达,并发送点云数据到ROS。
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 1 # 0: not use Lidar
|
||||
# 1: packet message comes from online Lidar
|
||||
# 2: packet message comes from ROS or ROS2
|
||||
# 3: packet message comes from Pcap file
|
||||
send_packet_ros: false # true: Send packets through ROS or ROS2(Used to record packet)
|
||||
send_point_cloud_ros: true # true: Send point cloud through ROS or ROS2
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSM1 # LiDAR type - RS16, RS32, RSBP, RSAIRY, RSHELIOS, RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48,
|
||||
# RSM1, RSM1_JUMBO, RSM2, RSM3, RSE1, RSMX.
|
||||
|
||||
msop_port: 6699 # Msop port of lidar
|
||||
difop_port: 7788 # Difop port of lidar
|
||||
imu_port: 0 # IMU port of lidar(only for RSAIRY, RSE1), 0 means no imu.
|
||||
# If you want to use IMU, please first set ENABLE_IMU_DATA_PARSE to ON in CMakeLists.txt
|
||||
user_layer_bytes: 0 # Bytes of user layer. thers is no user layer if it is 0
|
||||
tail_layer_bytes: 0 # Bytes of tail layer. thers is no tail layer if it is 0
|
||||
|
||||
|
||||
min_distance: 0.2 # Minimum distance of point cloud
|
||||
max_distance: 200 # Maximum distance of point cloud
|
||||
use_lidar_clock: true # true--Use the lidar clock as the message timestamp
|
||||
# false-- Use the system clock as the timestamp
|
||||
dense_points: false # true: discard NAN points; false: reserve NAN points
|
||||
|
||||
ts_first_point: true # true: time-stamp point cloud with the first point; false: with the last point;
|
||||
# these parameters are used from mechanical lidar
|
||||
|
||||
start_angle: 0 # Start angle of point cloud
|
||||
end_angle: 360 # End angle of point cloud
|
||||
|
||||
# When msg_source is 3, the following parameters will be used
|
||||
pcap_repeat: true # true: The pcap bag will repeat play
|
||||
pcap_rate: 1.0 # Rate to read the pcap file
|
||||
pcap_path: /home/robosense/lidar.pcap #The path of pcap file
|
||||
|
||||
ros:
|
||||
ros_frame_id: rslidar #Frame id of packet message and point cloud message
|
||||
ros_recv_packet_topic: /rslidar_packets #Topic used to receive lidar packets from ROS
|
||||
ros_send_packet_topic: /rslidar_packets #Topic used to send lidar packets through ROS
|
||||
ros_send_imu_data_topic: /rslidar_imu_data #Topic used to send imu data through ROS
|
||||
ros_send_point_cloud_topic: /rslidar_points #Topic used to send point cloud through ROS
|
||||
```
|
||||
|
||||
### 2.3.2 多台雷达
|
||||
|
||||
在线连接1台RSM1雷达和1台RSE1雷达,发送点云数据到ROS。
|
||||
|
||||
*注意lidar部分参数的缩进*
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 1
|
||||
send_packet_ros: false
|
||||
send_point_cloud_ros: true
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSM1 # LiDAR type - RS16, RS32, RSBP, RSAIRY, RSHELIOS, RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48,
|
||||
# RSM1, RSM1_JUMBO, RSM2, RSM3, RSE1, RSMX.
|
||||
|
||||
msop_port: 6699 # Msop port of lidar
|
||||
difop_port: 7788 # Difop port of lidar
|
||||
imu_port: 0 # IMU port of lidar(only for RSAIRY, RSE1), 0 means no imu.
|
||||
# If you want to use IMU, please first set ENABLE_IMU_DATA_PARSE to ON in CMakeLists.txt
|
||||
user_layer_bytes: 0 # Bytes of user layer. thers is no user layer if it is 0
|
||||
tail_layer_bytes: 0 # Bytes of tail layer. thers is no tail layer if it is 0
|
||||
|
||||
|
||||
min_distance: 0.2 # Minimum distance of point cloud
|
||||
max_distance: 200 # Maximum distance of point cloud
|
||||
use_lidar_clock: true # true--Use the lidar clock as the message timestamp
|
||||
# false-- Use the system clock as the timestamp
|
||||
dense_points: false # true: discard NAN points; false: reserve NAN points
|
||||
|
||||
ts_first_point: true # true: time-stamp point cloud with the first point; false: with the last point;
|
||||
# these parameters are used from mechanical lidar
|
||||
|
||||
start_angle: 0 # Start angle of point cloud
|
||||
end_angle: 360 # End angle of point cloud
|
||||
|
||||
# When msg_source is 3, the following parameters will be used
|
||||
pcap_repeat: true # true: The pcap bag will repeat play
|
||||
pcap_rate: 1.0 # Rate to read the pcap file
|
||||
pcap_path: /home/robosense/lidar.pcap #The path of pcap file
|
||||
|
||||
ros:
|
||||
ros_frame_id: rslidar #Frame id of packet message and point cloud message
|
||||
ros_recv_packet_topic: /left/rslidar_packets #Topic used to receive lidar packets from ROS
|
||||
ros_send_packet_topic: /left/rslidar_packets #Topic used to send lidar packets through ROS
|
||||
ros_send_imu_data_topic: /left/rslidar_imu_data #Topic used to send imu data through ROS
|
||||
ros_send_point_cloud_topic: /left/rslidar_points #Topic used to send point cloud through ROS
|
||||
|
||||
- driver:
|
||||
lidar_type: RSE1 # LiDAR type - RS16, RS32, RSBP, RSAIRY, RSHELIOS, RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48,
|
||||
# RSM1, RSM1_JUMBO, RSM2, RSM3, RSE1, RSMX.
|
||||
msop_port: 6699 # Msop port of lidar
|
||||
difop_port: 7788 # Difop port of lidar
|
||||
|
||||
user_layer_bytes: 0 # Bytes of user layer. thers is no user layer if it is 0
|
||||
tail_layer_bytes: 0 # Bytes of tail layer. thers is no tail layer if it is 0
|
||||
|
||||
|
||||
min_distance: 0.2 # Minimum distance of point cloud
|
||||
max_distance: 200 # Maximum distance of point cloud
|
||||
use_lidar_clock: true # true--Use the lidar clock as the message timestamp
|
||||
# false-- Use the system clock as the timestamp
|
||||
dense_points: false # true: discard NAN points; false: reserve NAN points
|
||||
|
||||
ts_first_point: true # true: time-stamp point cloud with the first point; false: with the last point;
|
||||
# these parameters are used from mechanical lidar
|
||||
|
||||
start_angle: 0 # Start angle of point cloud
|
||||
end_angle: 360 # End angle of point cloud
|
||||
|
||||
# When msg_source is 3, the following parameters will be used
|
||||
pcap_repeat: true # true: The pcap bag will repeat play
|
||||
pcap_rate: 1.0 # Rate to read the pcap file
|
||||
pcap_path: /home/robosense/lidar.pcap #The path of pcap file
|
||||
|
||||
ros:
|
||||
ros_frame_id: rslidar #Frame id of packet message and point cloud message
|
||||
ros_recv_packet_topic: /right/rslidar_packets #Topic used to receive lidar packets from ROS
|
||||
ros_send_packet_topic: /right/rslidar_packets #Topic used to send lidar packets through ROS
|
||||
ros_send_imu_data_topic: /right/rslidar_imu_data #Topic used to send imu data through ROS
|
||||
ros_send_point_cloud_topic: /right/rslidar_points #Topic used to send point cloud through ROS
|
||||
```
|
||||
|
||||
@ -0,0 +1,89 @@
|
||||
# 3 Introduction to hidden parameters
|
||||
|
||||
In order to make the configuration file as simple as possible, we hide some parameters and use default values for them.
|
||||
|
||||
This document explains the meanings of these hidden parameters.
|
||||
|
||||
|
||||
|
||||
## 3.1 common
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 1
|
||||
send_packet_ros: false
|
||||
send_point_cloud_ros: false
|
||||
send_point_cloud_proto: false
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 3.2 lidar
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSM1 # LiDAR type - RS16, RS32, RSBP, RSAIRY, RSHELIOS, RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48,
|
||||
# RSM1, RSM1_JUMBO, RSM2, RSM3, RSE1, RSMX.
|
||||
|
||||
msop_port: 6699 # Msop port of lidar
|
||||
difop_port: 7788 # Difop port of lidar
|
||||
imu_port: 0 # IMU port of lidar(only for RSAIRY, RSE1), 0 means no imu.
|
||||
# If you want to use IMU, please first set ENABLE_IMU_DATA_PARSE to ON in CMakeLists.txt
|
||||
group_address: 0.0.0.0
|
||||
host_address: 0.0.0.0
|
||||
user_layer_bytes: 0 # Bytes of user layer. thers is no user layer if it is 0
|
||||
tail_layer_bytes: 0 # Bytes of tail layer. thers is no tail layer if it is 0
|
||||
|
||||
|
||||
min_distance: 0.2 # Minimum distance of point cloud
|
||||
max_distance: 200 # Maximum distance of point cloud
|
||||
use_lidar_clock: true # true--Use the lidar clock as the message timestamp
|
||||
# false-- Use the system clock as the timestamp
|
||||
dense_points: false # true: discard NAN points; false: reserve NAN points
|
||||
|
||||
ts_first_point: true # true: time-stamp point cloud with the first point; false: with the last point;
|
||||
# these parameters are used from mechanical lidar
|
||||
|
||||
start_angle: 0 # Start angle of point cloud
|
||||
end_angle: 360 # End angle of point cloud
|
||||
|
||||
# When msg_source is 3, the following parameters will be used
|
||||
pcap_repeat: true # true: The pcap bag will repeat play
|
||||
pcap_rate: 1.0 # Rate to read the pcap file
|
||||
pcap_path: /home/robosense/lidar.pcap #The path of pcap file
|
||||
use_vlan: false
|
||||
|
||||
x: 0
|
||||
y: 0
|
||||
z: 0
|
||||
roll: 0
|
||||
pitch: 0
|
||||
yaw: 0
|
||||
ros:
|
||||
ros_frame_id: rslidar #Frame id of packet message and point cloud message
|
||||
ros_recv_packet_topic: /rslidar_packets #Topic used to receive lidar packets from ROS
|
||||
ros_send_packet_topic: /rslidar_packets #Topic used to send lidar packets through ROS
|
||||
ros_send_imu_data_topic: /rslidar_imu_data #Topic used to send imu data through ROS
|
||||
ros_send_point_cloud_topic: /rslidar_points #Topic used to send point cloud through ROS
|
||||
ros_send_by_rows: false
|
||||
```
|
||||
|
||||
- ```config_from_file``` -- Whether to read Lidar configuration from file. Only used for debug purpose, and can be ignored.
|
||||
- ```angle_path``` -- The path of the angle.csv. Only used for debug purpose and can be ignored.
|
||||
- ```ts_first_point``` -- Stamp the point cloud with the first point or the last one. Stamp with the first point if ```true```, else stamp with the last point if ```false```. The default value is ```false```.
|
||||
- ```split_frame_mode``` -- The way to split the LiDAR frames. Default value is ```1```.
|
||||
- 1 -- Split frame depending on the split_angle
|
||||
- 2 -- Split frame depending on a fixed number of blocks
|
||||
- 3 -- Split frame depending on num_blks_split
|
||||
|
||||
- ```split_angle``` -- The angle(in degree) to split frames. Only be used when ```split_frame_mode = 1```. The default value is ```0```.
|
||||
- ```num_blks_split``` -- The number of blocks in one frame. Only be used when ```split_frame_mode = 3```.
|
||||
- ```wait_for_difop``` -- If ```false```, the driver will not wait for difop packet(including lidar configuration data, especially angle data to calculate x, y, z), and send out the point cloud immediately. The default value is ```true```.
|
||||
- ```group_address``` -- If use multi-cast function, this parameter needs to be set correctly. For more details, please refer to [Online LiDAR - Advanced Topics](../howto/07_online_lidar_advanced_topics.md)
|
||||
- ```host_address``` -- Needed in two conditions. If the host receives packets from multiple Lidars via different IP addresses, use this parameter to specify destination IPs of the Lidars; If group_address is set, it should be set, so it will be joined into the multicast group.
|
||||
- ```x, y, z, roll, pitch, yaw ``` -- The parameters to do coordinate transformation. If the coordinate transformation function is enabled in driver core, the output point cloud will be transformed based on these parameters. For more details, please refer to [Coordinate Transformation](../howto/10_how_to_use_coordinate_transformation.md)
|
||||
- ```use_vlan``` -- Whether to use VLAN. The default value is ```false```. This parameter is only needed for pcap file. If it contains packets with VLAN layer, ```use_vlan``` should set to true. In the case of online Lidar, the VLAN layer is stripped by the protocol layer, so use_vlan can be ignored.
|
||||
- ```ros_send_by_rows```This only applies to mechanical lidar and is only valid when dense_points=false.
|
||||
-True - When sending a point cloud, arrange the points in a row by row order
|
||||
-False - When sending a point cloud, arrange the points in a column by column order
|
||||
@ -0,0 +1,86 @@
|
||||
# 3 隐藏参数介绍
|
||||
|
||||
为了使配置文件config.yaml尽可能简洁,我们隐藏了部分不常用的参数,在代码中使用默认值。
|
||||
|
||||
本文档将详细介绍这些隐藏参数。用户可根据需要,将它们加入参数文件,重新设置。
|
||||
|
||||
|
||||
|
||||
## 3.1 common
|
||||
|
||||
```yaml
|
||||
common:
|
||||
msg_source: 1
|
||||
send_packet_ros: false
|
||||
send_point_cloud_ros: false
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 3.2 lidar
|
||||
|
||||
```yaml
|
||||
lidar:
|
||||
- driver:
|
||||
lidar_type: RSM1 # LiDAR type - RS16, RS32, RSBP, RSAIRY, RSHELIOS, RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48,
|
||||
# RSM1, RSM1_JUMBO, RSM2, RSM3, RSE1, RSMX.
|
||||
|
||||
msop_port: 6699 # Msop port of lidar
|
||||
difop_port: 7788 # Difop port of lidar
|
||||
imu_port: 0 # IMU port of lidar(only for RSAIRY, RSE1), 0 means no imu.
|
||||
# If you want to use IMU, please first set ENABLE_IMU_DATA_PARSE to ON in CMakeLists.txt
|
||||
group_address: 0.0.0.0
|
||||
host_address: 0.0.0.0
|
||||
user_layer_bytes: 0 # Bytes of user layer. thers is no user layer if it is 0
|
||||
tail_layer_bytes: 0 # Bytes of tail layer. thers is no tail layer if it is 0
|
||||
|
||||
|
||||
min_distance: 0.2 # Minimum distance of point cloud
|
||||
max_distance: 200 # Maximum distance of point cloud
|
||||
use_lidar_clock: true # true--Use the lidar clock as the message timestamp
|
||||
# false-- Use the system clock as the timestamp
|
||||
dense_points: false # true: discard NAN points; false: reserve NAN points
|
||||
|
||||
ts_first_point: true # true: time-stamp point cloud with the first point; false: with the last point;
|
||||
# these parameters are used from mechanical lidar
|
||||
|
||||
start_angle: 0 # Start angle of point cloud
|
||||
end_angle: 360 # End angle of point cloud
|
||||
ros_send_by_rows:
|
||||
# When msg_source is 3, the following parameters will be used
|
||||
pcap_repeat: true # true: The pcap bag will repeat play
|
||||
pcap_rate: 1.0 # Rate to read the pcap file
|
||||
pcap_path: /home/robosense/lidar.pcap #The path of pcap file
|
||||
use_vlan: false
|
||||
|
||||
x: 0
|
||||
y: 0
|
||||
z: 0
|
||||
roll: 0
|
||||
pitch: 0
|
||||
yaw: 0
|
||||
ros:
|
||||
ros_frame_id: rslidar #Frame id of packet message and point cloud message
|
||||
ros_recv_packet_topic: /rslidar_packets #Topic used to receive lidar packets from ROS
|
||||
ros_send_packet_topic: /rslidar_packets #Topic used to send lidar packets through ROS
|
||||
ros_send_imu_data_topic: /rslidar_imu_data #Topic used to send imu data through ROS
|
||||
ros_send_point_cloud_topic: /rslidar_points #Topic used to send point cloud through ROS
|
||||
ros_send_by_rows: false
|
||||
```
|
||||
|
||||
- ```config_from_file``` -- 默认值为false, 是否从外参文件读入雷达配置信息,仅用于调试,可忽略。
|
||||
- ```angle_path``` -- angle.csv外参文件的路径,仅用于调试,可忽略。
|
||||
- ```split_frame_mode``` -- 分帧模式设置,默认值为```1```。
|
||||
- 1 -- 角度分帧
|
||||
- 2 -- 固定block数分帧
|
||||
- 3 -- 自定义block数分帧
|
||||
- ```split_angle``` -- 用于分帧的角度(单位为度), 在```split_frame_mode = 1``` 时才生效,默认值为```0```。
|
||||
- ```num_blks_split``` -- 用于分帧的包数,在 ```split_frame_mode = 3```时才生效,默认值为1。
|
||||
- ```wait_for_difop``` -- 若设置为false, 驱动将不会等待DIFOP包(包含配置数据,尤其是角度信息),而是立即解析MSOP包并发出点云。 默认值为```true```,也就是必须要有DIFOP包才会进行点云解析。
|
||||
- ```group_address``` -- 如果雷达为组播模式,此参数需要被设置为组播的地址。具体使用方式可以参考[在线雷达 - 高级主题](../howto/07_online_lidar_advanced_topics_CN.md) 。
|
||||
- ```host_address``` -- 有两种情况需要这个选项。如果主机上通过多个IP地址接收多个雷达的数据,则可以将此参数指定为雷达的目标IP;如果设置了group_address,那也需要设置host_address,以便将这个IP地址的网卡加入组播组。
|
||||
- ```x, y, z, roll, pitch, yaw ``` -- 坐标变换参数,若启用了内核的坐标变换功能,将会使用此参数输出经过变换后的点云。x, y, z, 单位为```米```, roll, pitch, yaw, 单位为```弧度```。具体使用方式可以参考 [坐标变换功能](../howto/10_how_to_use_coordinate_transformation_CN.md) 。
|
||||
- ```use_vlan``` -- 默认为false,指定是否使用vlan。如果pcap文件中的packet带vlan层,则需要设置这个选项为true。其他情况下不需要。在线雷达的情况下,协议层到达驱动时,已经剥离vlan层,所以不需要设置这个选项。
|
||||
- ```ros_send_by_rows```只对机械式雷达有意义,且只有当dense_points = false时才有效。
|
||||
- true -- 发送点云时,按照一行一行的顺序排列点
|
||||
- false -- 发送点云时,按照一列一列的顺序排列点
|
||||
|
After Width: | Height: | Size: 15 KiB |
|
After Width: | Height: | Size: 93 KiB |
|
After Width: | Height: | Size: 9.2 KiB |
|
After Width: | Height: | Size: 183 KiB |
|
After Width: | Height: | Size: 263 KiB |
|
After Width: | Height: | Size: 255 KiB |
250
src/airy/rslidar_sdk-main/doc/src_intro/rslidar_sdk_intro_CN.md
Normal file
@ -0,0 +1,250 @@
|
||||
# rslidar_sdk v1.5.17 源代码解析
|
||||
|
||||
|
||||
|
||||
## 1 简介
|
||||
|
||||
rslidar_sdk是基于ROS/ROS2的雷达驱动。rslidar_sdk依赖rs_driver接收和解析MSOP/DIFOP Packet。
|
||||
|
||||
rslidar_sdk的基本功能如下:
|
||||
+ 从在线雷达或PCAP文件得到点云和Imu数据,通过ROS话题`/rslidar_points`和`/rslidar_imu_data`发布。使用者可以订阅这个两个话题,在rviz中看到点云和IMU数据。
|
||||
+ 从在线雷达得到原始的MSOP/DIFOP/IMU Packet,通过ROS话题`/rslidar_packets`发布。使用者可以订阅这个话题,将Packet记录到rosbag文件。
|
||||
+ 从ROS话题`/rslidar_packets`得到MSOP/DIFOP/IMU Packet,解析得到点云,再发布到话题`/rslidar_points`。
|
||||
+ 这里的话题`/rslidar_packets`,由使用者通过回放Packet rosbag文件发布。
|
||||
|
||||
|
||||
|
||||
## 2 Source 与 Destination
|
||||
|
||||
如前面所说,rslidar_sdk从在线雷达、PCAP文件、ROS话题这三种源得到MSOP/DIFOP/IMU Packet,将Packet发布到ROS话题`/rslidar_packets`,将点云发布到目标 - ROS话题`/rslidar_points`, 将Imu数据发布到目标 - ROS话题`/rslidar_imu_data`。
|
||||
+ Source定义源接口
|
||||
+ DestinationPointCloud定义发送点云和Imu数据的目标接口。
|
||||
+ DestinationPacket定义发送MSOP/DIFOP/IMU Packet的目标接口。
|
||||
|
||||
<img src="./img/class_source_destination.png" alt="source" width="50%" height="50%">
|
||||
|
||||
### 2.1 DestinationPointCloud
|
||||
|
||||
DestinationPointCloud定义发送点云的接口。
|
||||
+ 虚拟成员函数init()对DestinationPointCloud实例初始化
|
||||
+ 虚拟成员函数start()启动实例
|
||||
+ 虚拟成员函数sendPointCloud()发送PointCloud消息
|
||||
+ 虚拟成员函数sendImuData()发送Imu数据
|
||||
|
||||
### 2.2 DestinationPacket
|
||||
|
||||
DestinationPacket定义发送MSOP/DIFOP Packet的接口。
|
||||
+ 虚拟成员函数init()对DestinationPacket实例初始化
|
||||
+ 虚拟成员函数start()启动实例
|
||||
+ 虚拟成员函数sendPacket()启动发送Packet消息
|
||||
|
||||
### 2.3 Source
|
||||
|
||||
Source是定义源的接口。
|
||||
|
||||
+ 成员`src_type_`是源的类型
|
||||
|
||||
```
|
||||
enum SourceType
|
||||
{
|
||||
MSG_FROM_LIDAR = 1,
|
||||
MSG_FROM_ROS_PACKET = 2,
|
||||
MSG_FROM_PCAP = 3,
|
||||
};
|
||||
```
|
||||
|
||||
+ 成员`pc_cb_vec_[]`中是一组DestinationPointCloud的实例。
|
||||
+ 成员函数sendPointCloud()调用`point_cb_vec_[]`中的实例,发送点云消息。
|
||||
+ 成员`pkt_cb_vec_[]`中是一组DestinationPacket实例。
|
||||
+ 成员函数sendPacket()将Packet消息发送到`pkt_cb_vec_[]`中的实例中。
|
||||
|
||||
+ 虚拟成员函数init()初始化Source实例
|
||||
+ 虚拟成员函数start()启动实例
|
||||
+ 虚拟成员函数regPointCloudCallback()将PointCloudDestination实例注册到`point_cb_vec_[]`。
|
||||
+ 虚拟成员函数regPacketCallback()将PacketDestination实例注册到`packet_cb_vec_[]`。
|
||||
|
||||
### 2.4 DestinationPointCloudRos
|
||||
|
||||
DestinationPointCloudRos在ROS话题`/rslidar_points`发布点云。
|
||||
+ 成员`pkt_pub_`是点云数据的ROS话题发布器。
|
||||
+ 成员`imu_pub_`是IMU数据的ROS话题发布器。
|
||||
+ 成员`frame_id_`保存`frame_id`。`frame_id`是坐标系名字。
|
||||
|
||||
<img src="./img/class_destination_pointcloud.png" alt="destination pointcloud ros" width="30%" height="20%">
|
||||
|
||||
#### 2.4.1 DestinationPointCloudRos::init()
|
||||
|
||||
init()初始化DestinationPointCloudRos实例。
|
||||
+ 从YAML文件读入用户配置参数。
|
||||
+ 读入`frame_id`,保存在成员`frame_id_`,默认值是`rslidar`。
|
||||
+ 读入点云的ROS话题名称,保存在本地变量`ros_send_topic_`,默认值是`/rslidar_points`。
|
||||
+ 读入IMU的ROS话题名称,保存在本地变量`ros_send_imu_data_topic`,默认值是`/rslidar_imu_data`。
|
||||
+ 读入点云排列方式参数,保存在成员`send_by_rows_`,默认值是`false`。
|
||||
+ 创建ROS话题发布器,保存在成员`pkt_sub_`.
|
||||
|
||||
#### 2.4.2 DestinationPointCloudRos::sendPointCloud()
|
||||
|
||||
sendPointCloud()在ROS话题`/rslidar_points`发布点云。
|
||||
+ 调用Publisher::publish()发布ROS格式的点云消息。
|
||||
|
||||
#### 2.4.3 DestinationPointCloudRos::sendImuData()
|
||||
|
||||
sendImuData()在ROS话题`/rslidar_imu_data`发布Imu数据。
|
||||
+ 调用Publisher::publish()发布ROS格式的Imu消息。
|
||||
|
||||
### 2.5 DestinationPacketRos
|
||||
|
||||
DestinationPacketRos在ROS话题`/rslidar_packets`发布MSOP/DIFOP Packet。
|
||||
+ 成员`pkt_sub_`是ROS话题发布器。
|
||||
+ 成员`frame_id_`保存`frame_id`。`frame_id`是坐标系名字。
|
||||
|
||||

|
||||
|
||||
#### 2.5.1 DestinationPacketRos::init()
|
||||
|
||||
init()初始化DestinationPacketRos实例。
|
||||
+ 从YAML文件读入用户配置参数。
|
||||
+ 读入`frame_id`,保存在成员`frame_id_`,默认值是`rslidar`
|
||||
+ 读入ROS话题,保存在本地变量`ros_send_topic_`,默认值是`/rslidar_packets`。
|
||||
+ 创建ROS话题发布器,保存在成员`pkt_sub_`.
|
||||
|
||||
#### 2.5.2 DestinationPacketRos::sendPacket()
|
||||
|
||||
sendPacket()在ROS话题`/rslidar_packets`发布MOSP/DIFOP packet。
|
||||
+ 调用Publisher::publish()发布ROS格式的Packet消息。
|
||||
|
||||
### 2.6 SourceDriver
|
||||
|
||||
SourceDriver从在线雷达和PCAP文件得到MSOP/DIFOP/IMU Packet,并解析得到点云和Imu数据。
|
||||
+ 成员`driver_ptr_`是rs_driver驱动的实例,也就是LidarDriver。
|
||||
+ 成员`free_point_cloud_queue_`和`point_cloud_queue_`,分别是空闲点云的队列和待处理点云的队列。
|
||||
+ 成员`point_cloud_handle_thread_`是点云的处理线程。
|
||||
+ 成员`free_imu_data_queue_`和`imu_data_queue_`,分别是空闲Imu数据的队列和待处理Imu数据的队列。
|
||||
+ 成员`imu_data_process_thread_`是Imu数据的处理线程。
|
||||
|
||||
<img src="./img/class_source_driver.png" alt="source driver" width="50%" height="60%">
|
||||
|
||||
#### 2.6.1 SourceDriver::init()
|
||||
|
||||
init()初始化SourceDriver实例。
|
||||
+ 读取YAML配置文件,得到雷达的用户配置参数。
|
||||
+ 根据源类型,也就是成员`src_type_`,创建相应类型的LidarDriver实例,也就是成员`driver_ptr_`。
|
||||
+ `src_type_`是在SourceDriver中的构造函数中指定的。
|
||||
+ 调用LidarDriver::regPointCloudCallback(),注册回调函数。这里是getPointCloud()和putPointCloud()。前者给`driver_ptr_`提供空闲点云,后者从`driver_ptr_`得到填充好的点云。
|
||||
+ 注意,这里没有注册MSOP/DIFOP Packet的回调函数,因为Packet是按需获取的。这时为了避免不必要地消耗CPU资源。
|
||||
+ 调用LidarDriver::regImuDataCallback(),注册回调函数。这里是getImuData()和putImuData()。前者给`driver_ptr_`提供空闲Imu数据,后者从`driver_ptr_`得到填充好的Imu数据。
|
||||
+ 调用LidarDriver::init(),初始化`driver_ptr_`。
|
||||
+ 创建、启动点云处理线程`point_cloud_handle_thread_`, 线程函数是processPointCloud()。
|
||||
+ 创建、启动IMU处理线程`imu_data_process_thread_`, 线程函数是processImuData()。
|
||||
|
||||
|
||||
#### 2.6.2 SourceDriver::getPointCloud()
|
||||
|
||||
getPointCloud()给成员`driver_ptr_`提供空闲的点云。
|
||||
+ 优先从成员`free_point_cloud_queue_`得到点云。
|
||||
+ 如果得不到,分配新的点云。
|
||||
|
||||
#### 2.6.3 SourceDriver::putPointCloud()
|
||||
|
||||
putPointCloud()给从成员`driver_ptr_`得到填充好的点云。
|
||||
+ 将得到的点云推送到成员`point_cloud_queue_`,等待处理。
|
||||
|
||||
#### 2.6.4 SourceDriver::processPointCloud()
|
||||
|
||||
processPointCloud()处理点云。在while循环中,
|
||||
+ 从待处理点云的队列`point_cloud_queue_`,得到点云,
|
||||
+ 调用sendPointCloud(),其中调用成员`pc_cb_vec_[]`中的DestinationPointCloud实例,发送点云。
|
||||
+ 回收点云,放入空闲点云的队列`free_cloud_queue_`,待下次使用。
|
||||
|
||||
#### 2.6.5 SourceDriver::getImuData()
|
||||
|
||||
getImuData()给成员`driver_ptr_`提供空闲的Imu数据。
|
||||
+ 优先从成员`free_imu_data_queue_`得到Imu数据。
|
||||
+ 如果得不到,分配新的Imu数据。
|
||||
|
||||
#### 2.6.6 SourceDriver::putImuData()
|
||||
|
||||
putImuData()给从成员`driver_ptr_`得到填充好的Imu数据。
|
||||
+ 将得到的Imu数据推送到成员`imu_data_queue_`,等待处理。
|
||||
|
||||
#### 2.6.7 SourceDriver::processImuData()
|
||||
|
||||
processImuData()处理点云。在while循环中,
|
||||
+ 从待处理点云的队列`imu_data_queue_`,得到点云,
|
||||
+ 调用sendImuData(),其中调用成员`pc_cb_vec_[]`中的DestinationPointCloud实例,发送点云。
|
||||
+ 回收点云,放入空闲点云的队列`free_imu_data_queue_`,待下次使用。
|
||||
|
||||
#### 2.6.8 SourceDriver::regPacketCallback()
|
||||
|
||||
regPacketCallback()用来注册DestinationPacket。
|
||||
+ 调用Source::regPacketCallback(),将DestinationPacket实例,加入成员`pkt_cb_vec_[]`。
|
||||
+ 如果这是首次要求Packet(`pkt_cb_vec_[]`的第1个实例),调用LidarDriver::regPacketCallback(),向`driver_ptr_`注册Packet回调函数,开始接收Packet。回调函数是putPacket()。
|
||||
|
||||
#### 2.6.9 SourceDriver::putPacket()
|
||||
|
||||
putPacket()调用sendPacket(),其中调用成员`pkt_cb_vec_[]`中的所有实例,发送MSOP/DIFOP Packet。
|
||||
|
||||
### 2.7 SourcePacketRos
|
||||
|
||||
SourcePacketRos在ROS话题`/rslidar_packets`得到MSOP/DIFOP Packet,解析后得到点云。
|
||||
+ SourcePacketRos从SourceDriver派生,而不是直接从Source派生,是因为它用SourceDriver解析Packet得到点云。
|
||||
+ 成员`pkt_sub_`,是ROS话题`/rslidar_packets`的订阅器。
|
||||
|
||||
<img src="./img/class_source_packet_ros.png" alt="source packet ros" width="25%" height="60%">
|
||||
|
||||
|
||||
#### 2.7.1 SourcePacketRos::init()
|
||||
|
||||
init()初始化SourcePacketRos实例。
|
||||
+ 调用SourceDriver::init()初始化成员`driver_ptr_`。
|
||||
+ 在SourcePacketRos的构造函数中,SourceType设置为`SourceType::MSG_FROM_ROS_PACKET`。这样,在SourceDriver::init()中,`driver_ptr_`的`input_type`就是`InputType::RAW_PACKET`,它通过LidarDriver::feedPacket接收Packet作为源。
|
||||
+ 解析YAML文件得到雷达的用户配置参数
|
||||
+ 得到接收Packet的话题,默认值为`/rslidar_packets`。
|
||||
+ 创建Packet话题的订阅器,也就是成员`pkt_sub_`,接收函数是putPacket()。
|
||||
|
||||
#### 2.7.2 SourcePacketRos::putPacket()
|
||||
|
||||
putPacket()接收Packet,送到`driver_ptr_`解析。
|
||||
+ 调用LidarDriver::decodePacket(),将Packet喂给`driver_ptr_`。
|
||||
+ 点云的接收,使用SourceDriver的已有实现。
|
||||
|
||||
|
||||
|
||||
## 3 NodeManager
|
||||
|
||||
NodeManager管理Source实例,包括创建、初始化、启动、停止Source。它支持多个源,但是这些源的类型必须相同。
|
||||
+ 成员`sources_[]`是一个Source实例的数组。
|
||||
|
||||

|
||||
|
||||
### 3.1 NodeManager::init()
|
||||
|
||||
init()初始化NodeManger实例。
|
||||
+ 从config.yaml文件得到用户配置参数
|
||||
+ 本地变量`msg_source`,数据源类型
|
||||
+ 本地变量`send_point_cloud_ros`, 是否在ROS话题发送点云。
|
||||
+ 本地变量`send_packet_ros`,是否在ROS话题发送MSOP/DIFOP packet,
|
||||
|
||||
+ 在.yaml文件中遍历数据源。在循环中,
|
||||
+ 根据`msg_source`创建Source实例。
|
||||
+ 如果是在线雷达(`SourceType::MSG_FROM_LIDAR`),创建SourceDriver实例并初始化, 源类型为`MSG_FROM_LIDAR`。
|
||||
+ 如果是PCAP文件(`SourceType::MSG_FROM_PCAP`),创建SourceDriver实例并初始化,源类型为`MSG_FROM_PCAP`。
|
||||
+ 如果是ROS话题(`SourceType::MSG_FROM_ROS_PACKET`), 创建SourcePacketRos并初始化。SourcePacketRos构造函数已将源类型设置为`MSG_FROM_ROS_PACKET`
|
||||
+ 如果在ROS话题发送点云(`send_point_cloud_ros` = `true`),则创建DestinationPointCloudRos实例、初始化,调用Source::regPointCloudCallback(),将它加入Source的`pc_cb_vec_[]`。
|
||||
+ 如果在ROS话题发送Packet(`send_packet_ros` = `true`),则创建DestinationPacketRos实例、初始化,调用Source::regPacketCallback()将它加入Source的`pkt_cb_vec_[]`。
|
||||
+ 将Source实例,加入成员`sources_[]`。
|
||||
|
||||
### 3.2 NodeManager::start()
|
||||
|
||||
start()启动成员`sources_[]`中的所有实例。
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
BIN
src/airy/rslidar_sdk-main/img/01_01_download_page.png
Normal file
|
After Width: | Height: | Size: 4.4 KiB |
21
src/airy/rslidar_sdk-main/launch/elequent_start.py
Executable file
@ -0,0 +1,21 @@
|
||||
from launch import LaunchDescription
|
||||
from launch_ros.actions import Node
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
def generate_launch_description():
|
||||
rviz_config=get_package_share_directory('rslidar_sdk')+'/rviz/rviz2.rviz'
|
||||
return LaunchDescription([
|
||||
Node(
|
||||
package='rslidar_sdk',
|
||||
node_namespace='rslidar_sdk',
|
||||
node_name='rslidar_sdk_node',
|
||||
node_executable='rslidar_sdk_node',
|
||||
output='screen'
|
||||
),
|
||||
Node(
|
||||
package='rviz2',
|
||||
node_namespace='rviz2',
|
||||
node_name='rviz2',
|
||||
node_executable='rviz2',
|
||||
arguments=['-d',rviz_config]
|
||||
)
|
||||
])
|
||||
7
src/airy/rslidar_sdk-main/launch/start.launch
Executable file
@ -0,0 +1,7 @@
|
||||
<launch>
|
||||
<node pkg="rslidar_sdk" name="rslidar_sdk_node" type="rslidar_sdk_node" output="screen">
|
||||
<param name="config_path" value=""/>
|
||||
</node>
|
||||
<!-- rviz -->
|
||||
<node pkg="rviz" name="rviz" type="rviz" args="-d $(find rslidar_sdk)/rviz/rviz.rviz" />
|
||||
</launch>
|
||||
28
src/airy/rslidar_sdk-main/launch/start.py
Executable file
@ -0,0 +1,28 @@
|
||||
from launch import LaunchDescription
|
||||
from launch_ros.actions import Node
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
|
||||
rviz_config = get_package_share_directory("rslidar_sdk") + "/rviz/rviz2.rviz"
|
||||
|
||||
config_file = "" # your config file path
|
||||
|
||||
return LaunchDescription(
|
||||
[
|
||||
Node(
|
||||
namespace="rslidar_sdk",
|
||||
package="rslidar_sdk",
|
||||
executable="rslidar_sdk_node",
|
||||
output="screen",
|
||||
parameters=[{"config_path": config_file}],
|
||||
),
|
||||
# Node(
|
||||
# namespace="rviz2",
|
||||
# package="rviz2",
|
||||
# executable="rviz2",
|
||||
# arguments=["-d", rviz_config],
|
||||
# ),
|
||||
]
|
||||
)
|
||||
61
src/airy/rslidar_sdk-main/launch/start_double.launch.py
Executable file
@ -0,0 +1,61 @@
|
||||
from launch import LaunchDescription
|
||||
from launch_ros.actions import Node
|
||||
from launch.actions import IncludeLaunchDescription
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
from pathlib import Path
|
||||
import os
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
|
||||
pkg_share = get_package_share_directory("rslidar_sdk")
|
||||
# RViz 配置文件路径
|
||||
rviz_config = os.path.join(pkg_share, "rviz", "rviz2.rviz")
|
||||
# 雷达配置文件路径
|
||||
config_front = os.path.join(pkg_share, "config", "config_front.yaml") # 前雷达
|
||||
config_rear = os.path.join(pkg_share, "config", "config_rear.yaml") # 后雷达
|
||||
|
||||
# 点云合并 launch 文件路径
|
||||
pkg_share_merge = get_package_share_directory("rslidar_pointcloud_merger")
|
||||
merge_launch = os.path.join(pkg_share_merge, "launch", "merge_two_lidars.launch.py")
|
||||
|
||||
# 前雷达节点
|
||||
front_lidar_node = Node(
|
||||
namespace="front_lidar",
|
||||
package="rslidar_sdk",
|
||||
executable="rslidar_sdk_node",
|
||||
name="rslidar_front",
|
||||
output="screen",
|
||||
parameters=[{"config_path": config_front}],
|
||||
)
|
||||
|
||||
# 后雷达节点
|
||||
rear_lidar_node = Node(
|
||||
namespace="rear_lidar",
|
||||
package="rslidar_sdk",
|
||||
executable="rslidar_sdk_node",
|
||||
name="rslidar_rear",
|
||||
output="screen",
|
||||
parameters=[{"config_path": config_rear}],
|
||||
)
|
||||
|
||||
# RViz 可视化节点
|
||||
rviz_node = Node(
|
||||
namespace="", # RViz 一般不加命名空间
|
||||
package="rviz2",
|
||||
executable="rviz2",
|
||||
output="log",
|
||||
arguments=["-d", rviz_config],
|
||||
)
|
||||
|
||||
# 点云合并 launch 文件
|
||||
merge_launch_action = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(merge_launch)
|
||||
)
|
||||
|
||||
# 返回所有节点和 launch 文件
|
||||
return LaunchDescription(
|
||||
# [front_lidar_node, rear_lidar_node, merge_launch_action, rviz_node]
|
||||
[front_lidar_node, rear_lidar_node, merge_launch_action]
|
||||
)
|
||||
136
src/airy/rslidar_sdk-main/node/rslidar_sdk_node.cpp
Normal file
@ -0,0 +1,136 @@
|
||||
/*********************************************************************************************************************
|
||||
Copyright (c) 2020 RoboSense
|
||||
All rights reserved
|
||||
|
||||
By downloading, copying, installing or using the software you agree to this license. If you do not agree to this
|
||||
license, do not download, install, copy or use the software.
|
||||
|
||||
License Agreement
|
||||
For RoboSense LiDAR SDK Library
|
||||
(3-clause BSD License)
|
||||
|
||||
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the
|
||||
following conditions are met:
|
||||
|
||||
1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following
|
||||
disclaimer.
|
||||
|
||||
2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following
|
||||
disclaimer in the documentation and/or other materials provided with the distribution.
|
||||
|
||||
3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used
|
||||
to endorse or promote products derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
|
||||
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
|
||||
WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
|
||||
THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*********************************************************************************************************************/
|
||||
|
||||
#include "manager/node_manager.hpp"
|
||||
|
||||
#include <rs_driver/macro/version.hpp>
|
||||
#include <signal.h>
|
||||
|
||||
#ifdef ROS_FOUND
|
||||
#include <ros/ros.h>
|
||||
#include <ros/package.h>
|
||||
#elif ROS2_FOUND
|
||||
#include <rclcpp/rclcpp.hpp>
|
||||
#endif
|
||||
|
||||
using namespace robosense::lidar;
|
||||
|
||||
#ifdef ROS2_FOUND
|
||||
std::mutex g_mtx;
|
||||
std::condition_variable g_cv;
|
||||
#endif
|
||||
|
||||
static void sigHandler(int sig)
|
||||
{
|
||||
RS_MSG << "RoboSense-LiDAR-Driver is stopping....." << RS_REND;
|
||||
|
||||
#ifdef ROS_FOUND
|
||||
ros::shutdown();
|
||||
#elif ROS2_FOUND
|
||||
g_cv.notify_all();
|
||||
#endif
|
||||
}
|
||||
|
||||
int main(int argc, char** argv)
|
||||
{
|
||||
signal(SIGINT, sigHandler); ///< bind ctrl+c signal with the sigHandler function
|
||||
|
||||
RS_TITLE << "********************************************************" << RS_REND;
|
||||
RS_TITLE << "********** **********" << RS_REND;
|
||||
RS_TITLE << "********** RSLidar_SDK Version: v" << RSLIDAR_VERSION_MAJOR
|
||||
<< "." << RSLIDAR_VERSION_MINOR
|
||||
<< "." << RSLIDAR_VERSION_PATCH << " **********" << RS_REND;
|
||||
RS_TITLE << "********** **********" << RS_REND;
|
||||
RS_TITLE << "********************************************************" << RS_REND;
|
||||
|
||||
#ifdef ROS_FOUND
|
||||
ros::init(argc, argv, "rslidar_sdk_node", ros::init_options::NoSigintHandler);
|
||||
#elif ROS2_FOUND
|
||||
rclcpp::init(argc, argv);
|
||||
#endif
|
||||
|
||||
std::string config_path;
|
||||
|
||||
#ifdef RUN_IN_ROS_WORKSPACE
|
||||
config_path = ros::package::getPath("rslidar_sdk");
|
||||
#else
|
||||
config_path = (std::string)PROJECT_PATH;
|
||||
#endif
|
||||
|
||||
config_path += "/config/config.yaml";
|
||||
|
||||
#ifdef ROS_FOUND
|
||||
ros::NodeHandle priv_hh("~");
|
||||
std::string path;
|
||||
priv_hh.param("config_path", path, std::string(""));
|
||||
#elif ROS2_FOUND
|
||||
std::shared_ptr<rclcpp::Node> nd = rclcpp::Node::make_shared("param_handle");
|
||||
std::string path = nd->declare_parameter<std::string>("config_path", "");
|
||||
#endif
|
||||
|
||||
#if defined(ROS_FOUND) || defined(ROS2_FOUND)
|
||||
if (!path.empty())
|
||||
{
|
||||
config_path = path;
|
||||
}
|
||||
#endif
|
||||
|
||||
YAML::Node config;
|
||||
try
|
||||
{
|
||||
config = YAML::LoadFile(config_path);
|
||||
RS_INFO << "--------------------------------------------------------" << RS_REND;
|
||||
RS_INFO << "Config loaded from PATH:" << RS_REND;
|
||||
RS_INFO << config_path << RS_REND;
|
||||
RS_INFO << "--------------------------------------------------------" << RS_REND;
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
RS_ERROR << "The format of config file " << config_path << " is wrong. Please check (e.g. indentation)." << RS_REND;
|
||||
return -1;
|
||||
}
|
||||
|
||||
std::shared_ptr<NodeManager> demo_ptr = std::make_shared<NodeManager>();
|
||||
demo_ptr->init(config);
|
||||
demo_ptr->start();
|
||||
|
||||
RS_MSG << "RoboSense-LiDAR-Driver is running....." << RS_REND;
|
||||
|
||||
#ifdef ROS_FOUND
|
||||
ros::spin();
|
||||
#elif ROS2_FOUND
|
||||
std::unique_lock<std::mutex> lck(g_mtx);
|
||||
g_cv.wait(lck);
|
||||
#endif
|
||||
|
||||
return 0;
|
||||
}
|
||||
25
src/airy/rslidar_sdk-main/package.xml
Normal file
@ -0,0 +1,25 @@
|
||||
<?xml version="1.0"?>
|
||||
<package format="3">
|
||||
<name>rslidar_sdk</name>
|
||||
<version>1.5.16</version>
|
||||
<description>The rslidar_sdk package</description>
|
||||
<maintainer email="felix.huang@robosense.cn">robosense</maintainer>
|
||||
<license>BSD</license>
|
||||
|
||||
<buildtool_depend condition="$ROS_VERSION == 1">catkin</buildtool_depend>
|
||||
<buildtool_depend condition="$ROS_VERSION == 2">ament_cmake</buildtool_depend>
|
||||
|
||||
<depend>libpcap</depend>
|
||||
<depend condition="$ROS_VERSION == 1">pcl_ros</depend>
|
||||
<depend condition="$ROS_VERSION == 2">rclcpp</depend>
|
||||
<depend condition="$ROS_VERSION == 1">roscpp</depend>
|
||||
<depend condition="$ROS_VERSION == 1">roslib</depend>
|
||||
<depend condition="$ROS_VERSION == 2">rslidar_msg</depend>
|
||||
<depend>sensor_msgs</depend>
|
||||
<depend>std_msgs</depend>
|
||||
<depend>yaml-cpp</depend>
|
||||
|
||||
<export>
|
||||
<build_type condition="$ROS_VERSION == 2">ament_cmake</build_type>
|
||||
</export>
|
||||
</package>
|
||||
164
src/airy/rslidar_sdk-main/rviz/rviz.rviz
Normal file
@ -0,0 +1,164 @@
|
||||
Panels:
|
||||
- Class: rviz/Displays
|
||||
Help Height: 75
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
- /Point Cloud1
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 790
|
||||
- Class: rviz/Selection
|
||||
Name: Selection
|
||||
- Class: rviz/Tool Properties
|
||||
Expanded:
|
||||
- /2D Pose Estimate1
|
||||
- /2D Nav Goal1
|
||||
- /Publish Point1
|
||||
Name: Tool Properties
|
||||
Splitter Ratio: 0.5886790156364441
|
||||
- Class: rviz/Views
|
||||
Expanded:
|
||||
- /Current View1
|
||||
Name: Views
|
||||
Splitter Ratio: 0.5
|
||||
- Class: rviz/Time
|
||||
Experimental: false
|
||||
Name: Time
|
||||
SyncMode: 0
|
||||
SyncSource: Point Cloud
|
||||
- Class: rviz/Displays
|
||||
Help Height: 75
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded: ~
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 366
|
||||
Preferences:
|
||||
PromptSaveOnExit: true
|
||||
Toolbars:
|
||||
toolButtonStyle: 2
|
||||
Visualization Manager:
|
||||
Class: ""
|
||||
Displays:
|
||||
- Alpha: 1
|
||||
Autocompute Intensity Bounds: true
|
||||
Autocompute Value Bounds:
|
||||
Max Value: 10
|
||||
Min Value: -10
|
||||
Value: true
|
||||
Axis: Z
|
||||
Channel Name: intensity
|
||||
Class: rviz/PointCloud2
|
||||
Color: 255; 255; 255
|
||||
Color Transformer: Intensity
|
||||
Decay Time: 0
|
||||
Enabled: true
|
||||
Invert Rainbow: false
|
||||
Max Color: 255; 255; 255
|
||||
Min Color: 0; 0; 0
|
||||
Name: Point Cloud
|
||||
Position Transformer: XYZ
|
||||
Queue Size: 10
|
||||
Selectable: true
|
||||
Size (Pixels): 1.5
|
||||
Size (m): 0.10000000149011612
|
||||
Style: Squares
|
||||
Topic: /rslidar_points
|
||||
Unreliable: false
|
||||
Use Fixed Frame: true
|
||||
Use rainbow: true
|
||||
Value: true
|
||||
- Alpha: 0.5
|
||||
Cell Size: 10
|
||||
Class: rviz/Grid
|
||||
Color: 160; 160; 164
|
||||
Enabled: true
|
||||
Line Style:
|
||||
Line Width: 0.029999999329447746
|
||||
Value: Lines
|
||||
Name: Grid
|
||||
Normal Cell Count: 0
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Plane: XY
|
||||
Plane Cell Count: 50
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Class: rviz/Axes
|
||||
Enabled: true
|
||||
Length: 1
|
||||
Name: Axes
|
||||
Radius: 0.10000000149011612
|
||||
Reference Frame: <Fixed Frame>
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Enabled: true
|
||||
Global Options:
|
||||
Background Color: 48; 48; 48
|
||||
Default Light: true
|
||||
Fixed Frame: /rslidar
|
||||
Frame Rate: 30
|
||||
Name: root
|
||||
Tools:
|
||||
- Class: rviz/Interact
|
||||
Hide Inactive Objects: true
|
||||
- Class: rviz/MoveCamera
|
||||
- Class: rviz/Select
|
||||
- Class: rviz/FocusCamera
|
||||
- Class: rviz/Measure
|
||||
- Class: rviz/SetInitialPose
|
||||
Theta std deviation: 0.2617993950843811
|
||||
Topic: /initialpose
|
||||
X std deviation: 0.5
|
||||
Y std deviation: 0.5
|
||||
- Class: rviz/SetGoal
|
||||
Topic: /move_base_simple/goal
|
||||
- Class: rviz/PublishPoint
|
||||
Single click: true
|
||||
Topic: /clicked_point
|
||||
Value: true
|
||||
Views:
|
||||
Current:
|
||||
Class: rviz/Orbit
|
||||
Distance: 107.46170806884766
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Field of View: 0.7853981852531433
|
||||
Focal Point:
|
||||
X: 1.4133121967315674
|
||||
Y: -0.1708243489265442
|
||||
Z: 1.6932628154754639
|
||||
Focal Shape Fixed Size: true
|
||||
Focal Shape Size: 0.05000000074505806
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Pitch: 0.634796679019928
|
||||
Target Frame: <Fixed Frame>
|
||||
Yaw: 3.9649996757507324
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 1016
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: true
|
||||
QMainWindow State: 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
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: false
|
||||
Width: 2504
|
||||
X: 56
|
||||
Y: 27
|
||||
184
src/airy/rslidar_sdk-main/rviz/rviz2.rviz
Normal file
@ -0,0 +1,184 @@
|
||||
Panels:
|
||||
- Class: rviz_common/Displays
|
||||
Help Height: 78
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
- /PointCloud21
|
||||
- /Axes1
|
||||
- /Axes2
|
||||
- /Axes3
|
||||
Splitter Ratio: 0.5564202070236206
|
||||
Tree Height: 787
|
||||
- Class: rviz_common/Selection
|
||||
Name: Selection
|
||||
- Class: rviz_common/Tool Properties
|
||||
Expanded:
|
||||
- /2D Goal Pose1
|
||||
- /Publish Point1
|
||||
Name: Tool Properties
|
||||
Splitter Ratio: 0.5886790156364441
|
||||
- Class: rviz_common/Views
|
||||
Expanded:
|
||||
- /Current View1
|
||||
Name: Views
|
||||
Splitter Ratio: 0.5
|
||||
Visualization Manager:
|
||||
Class: ""
|
||||
Displays:
|
||||
- Alpha: 0.5
|
||||
Cell Size: 1
|
||||
Class: rviz_default_plugins/Grid
|
||||
Color: 160; 160; 164
|
||||
Enabled: true
|
||||
Line Style:
|
||||
Line Width: 0.029999999329447746
|
||||
Value: Lines
|
||||
Name: Grid
|
||||
Normal Cell Count: 0
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Plane: XY
|
||||
Plane Cell Count: 30
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Autocompute Intensity Bounds: true
|
||||
Autocompute Value Bounds:
|
||||
Max Value: 30.831819534301758
|
||||
Min Value: -6.263338565826416
|
||||
Value: true
|
||||
Axis: Z
|
||||
Channel Name: intensity
|
||||
Class: rviz_default_plugins/PointCloud2
|
||||
Color: 255; 255; 255
|
||||
Color Transformer: Intensity
|
||||
Decay Time: 0
|
||||
Enabled: true
|
||||
Invert Rainbow: false
|
||||
Max Color: 255; 255; 255
|
||||
Max Intensity: 255
|
||||
Min Color: 0; 0; 0
|
||||
Min Intensity: 1
|
||||
Name: PointCloud2
|
||||
Position Transformer: XYZ
|
||||
Selectable: true
|
||||
Size (Pixels): 3
|
||||
Size (m): 0.05000000074505806
|
||||
Style: Points
|
||||
Topic:
|
||||
Depth: 5
|
||||
Durability Policy: Volatile
|
||||
Filter size: 10
|
||||
History Policy: Keep Last
|
||||
Reliability Policy: Reliable
|
||||
Value: /rslidar_points
|
||||
Use Fixed Frame: true
|
||||
Use rainbow: true
|
||||
Value: true
|
||||
- Class: rviz_default_plugins/Axes
|
||||
Enabled: true
|
||||
Length: 1
|
||||
Name: Axes
|
||||
Radius: 0.10000000149011612
|
||||
Reference Frame: front_lidar
|
||||
Value: true
|
||||
- Class: rviz_default_plugins/Axes
|
||||
Enabled: true
|
||||
Length: 1
|
||||
Name: Axes
|
||||
Radius: 0.10000000149011612
|
||||
Reference Frame: rear_lidar
|
||||
Value: true
|
||||
- Class: rviz_default_plugins/Axes
|
||||
Enabled: true
|
||||
Length: 1
|
||||
Name: Axes
|
||||
Radius: 0.10000000149011612
|
||||
Reference Frame: rslidar
|
||||
Value: true
|
||||
Enabled: true
|
||||
Global Options:
|
||||
Background Color: 48; 48; 48
|
||||
Fixed Frame: rslidar
|
||||
Frame Rate: 30
|
||||
Name: root
|
||||
Tools:
|
||||
- Class: rviz_default_plugins/Interact
|
||||
Hide Inactive Objects: true
|
||||
- Class: rviz_default_plugins/MoveCamera
|
||||
- Class: rviz_default_plugins/Select
|
||||
- Class: rviz_default_plugins/FocusCamera
|
||||
- Class: rviz_default_plugins/Measure
|
||||
Line color: 128; 128; 0
|
||||
- Class: rviz_default_plugins/SetInitialPose
|
||||
Covariance x: 0.25
|
||||
Covariance y: 0.25
|
||||
Covariance yaw: 0.06853891909122467
|
||||
Topic:
|
||||
Depth: 5
|
||||
Durability Policy: Volatile
|
||||
History Policy: Keep Last
|
||||
Reliability Policy: Reliable
|
||||
Value: /initialpose
|
||||
- Class: rviz_default_plugins/SetGoal
|
||||
Topic:
|
||||
Depth: 5
|
||||
Durability Policy: Volatile
|
||||
History Policy: Keep Last
|
||||
Reliability Policy: Reliable
|
||||
Value: /goal_pose
|
||||
- Class: rviz_default_plugins/PublishPoint
|
||||
Single click: true
|
||||
Topic:
|
||||
Depth: 5
|
||||
Durability Policy: Volatile
|
||||
History Policy: Keep Last
|
||||
Reliability Policy: Reliable
|
||||
Value: /clicked_point
|
||||
Transformation:
|
||||
Current:
|
||||
Class: rviz_default_plugins/TF
|
||||
Value: true
|
||||
Views:
|
||||
Current:
|
||||
Class: rviz_default_plugins/Orbit
|
||||
Distance: 60.19597625732422
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Focal Point:
|
||||
X: 1.080678939819336
|
||||
Y: -0.35503947734832764
|
||||
Z: 0.8869286775588989
|
||||
Focal Shape Fixed Size: true
|
||||
Focal Shape Size: 0.05000000074505806
|
||||
Invert Z Axis: true
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Pitch: 1.5697963237762451
|
||||
Target Frame: <Fixed Frame>
|
||||
Value: Orbit (rviz)
|
||||
Yaw: 3.1403956413269043
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 1016
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: false
|
||||
QMainWindow State: 000000ff00000000fd0000000400000000000002040000039efc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000039e000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000039efc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d0000039e000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d006501000000000000045000000000000000000000041b0000039e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: false
|
||||
Width: 1850
|
||||
X: 70
|
||||
Y: 27
|
||||
167
src/airy/rslidar_sdk-main/src/manager/node_manager.cpp
Normal file
@ -0,0 +1,167 @@
|
||||
/*********************************************************************************************************************
|
||||
Copyright (c) 2020 RoboSense
|
||||
All rights reserved
|
||||
|
||||
By downloading, copying, installing or using the software you agree to this license. If you do not agree to this
|
||||
license, do not download, install, copy or use the software.
|
||||
|
||||
License Agreement
|
||||
For RoboSense LiDAR SDK Library
|
||||
(3-clause BSD License)
|
||||
|
||||
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the
|
||||
following conditions are met:
|
||||
|
||||
1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following
|
||||
disclaimer.
|
||||
|
||||
2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following
|
||||
disclaimer in the documentation and/or other materials provided with the distribution.
|
||||
|
||||
3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used
|
||||
to endorse or promote products derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
|
||||
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
|
||||
WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
|
||||
THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*********************************************************************************************************************/
|
||||
|
||||
#include "manager/node_manager.hpp"
|
||||
#include "source/source_driver.hpp"
|
||||
#include "source/source_pointcloud_ros.hpp"
|
||||
#include "source/source_packet_ros.hpp"
|
||||
|
||||
namespace robosense
|
||||
{
|
||||
namespace lidar
|
||||
{
|
||||
|
||||
void NodeManager::init(const YAML::Node& config)
|
||||
{
|
||||
YAML::Node common_config = yamlSubNodeAbort(config, "common");
|
||||
|
||||
int msg_source = 0;
|
||||
yamlRead<int>(common_config, "msg_source", msg_source, 0);
|
||||
|
||||
bool send_packet_ros;
|
||||
yamlRead<bool>(common_config, "send_packet_ros", send_packet_ros, false);
|
||||
|
||||
bool send_point_cloud_ros;
|
||||
yamlRead<bool>(common_config, "send_point_cloud_ros", send_point_cloud_ros, false);
|
||||
|
||||
bool send_point_cloud_proto;
|
||||
yamlRead<bool>(common_config, "send_point_cloud_proto", send_point_cloud_proto, false);
|
||||
|
||||
bool send_packet_proto;
|
||||
yamlRead<bool>(common_config, "send_packet_proto", send_packet_proto, false);
|
||||
|
||||
YAML::Node lidar_config = yamlSubNodeAbort(config, "lidar");
|
||||
|
||||
for (uint8_t i = 0; i < lidar_config.size(); ++i)
|
||||
{
|
||||
std::shared_ptr<Source> source;
|
||||
|
||||
switch (msg_source)
|
||||
{
|
||||
case SourceType::MSG_FROM_LIDAR: // online lidar
|
||||
|
||||
RS_INFO << "------------------------------------------------------" << RS_REND;
|
||||
RS_INFO << "Receive Packets From : Online LiDAR" << RS_REND;
|
||||
RS_INFO << "Msop Port: " << lidar_config[i]["driver"]["msop_port"].as<uint16_t>() << RS_REND;
|
||||
RS_INFO << "Difop Port: " << lidar_config[i]["driver"]["difop_port"].as<uint16_t>() << RS_REND;
|
||||
RS_INFO << "------------------------------------------------------" << RS_REND;
|
||||
|
||||
source = std::make_shared<SourceDriver>(SourceType::MSG_FROM_LIDAR);
|
||||
source->init(lidar_config[i]);
|
||||
break;
|
||||
|
||||
case SourceType::MSG_FROM_ROS_PACKET: // pkt from ros
|
||||
|
||||
RS_INFO << "------------------------------------------------------" << RS_REND;
|
||||
RS_INFO << "Receive Packets From : ROS" << RS_REND;
|
||||
RS_INFO << "Msop Topic: " << lidar_config[i]["ros"]["ros_recv_packet_topic"].as<std::string>() << RS_REND;
|
||||
RS_INFO << "------------------------------------------------------" << RS_REND;
|
||||
|
||||
source = std::make_shared<SourcePacketRos>();
|
||||
source->init(lidar_config[i]);
|
||||
break;
|
||||
|
||||
case SourceType::MSG_FROM_PCAP: // pcap
|
||||
|
||||
RS_INFO << "------------------------------------------------------" << RS_REND;
|
||||
RS_INFO << "Receive Packets From : Pcap" << RS_REND;
|
||||
RS_INFO << "Msop Port: " << lidar_config[i]["driver"]["msop_port"].as<uint16_t>() << RS_REND;
|
||||
RS_INFO << "Difop Port: " << lidar_config[i]["driver"]["difop_port"].as<uint16_t>() << RS_REND;
|
||||
RS_INFO << "------------------------------------------------------" << RS_REND;
|
||||
|
||||
source = std::make_shared<SourceDriver>(SourceType::MSG_FROM_PCAP);
|
||||
source->init(lidar_config[i]);
|
||||
break;
|
||||
|
||||
default:
|
||||
RS_ERROR << "Unsupported LiDAR message source:" << msg_source << "." << RS_REND;
|
||||
exit(-1);
|
||||
}
|
||||
|
||||
if (send_packet_ros)
|
||||
{
|
||||
RS_DEBUG << "------------------------------------------------------" << RS_REND;
|
||||
RS_DEBUG << "Send Packets To : ROS" << RS_REND;
|
||||
RS_DEBUG << "Msop Topic: " << lidar_config[i]["ros"]["ros_send_packet_topic"].as<std::string>() << RS_REND;
|
||||
RS_DEBUG << "------------------------------------------------------" << RS_REND;
|
||||
|
||||
std::shared_ptr<DestinationPacket> dst = std::make_shared<DestinationPacketRos>();
|
||||
dst->init(lidar_config[i]);
|
||||
source->regPacketCallback(dst);
|
||||
}
|
||||
|
||||
if (send_point_cloud_ros)
|
||||
{
|
||||
RS_DEBUG << "------------------------------------------------------" << RS_REND;
|
||||
RS_DEBUG << "Send PointCloud To : ROS" << RS_REND;
|
||||
RS_DEBUG << "PointCloud Topic: " << lidar_config[i]["ros"]["ros_send_point_cloud_topic"].as<std::string>()
|
||||
<< RS_REND;
|
||||
RS_DEBUG << "------------------------------------------------------" << RS_REND;
|
||||
|
||||
std::shared_ptr<DestinationPointCloud> dst = std::make_shared<DestinationPointCloudRos>();
|
||||
dst->init(lidar_config[i]);
|
||||
source->regPointCloudCallback(dst);
|
||||
}
|
||||
|
||||
sources_.emplace_back(source);
|
||||
}
|
||||
}
|
||||
|
||||
void NodeManager::start()
|
||||
{
|
||||
for (auto& iter : sources_)
|
||||
{
|
||||
if (iter != nullptr)
|
||||
{
|
||||
iter->start();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void NodeManager::stop()
|
||||
{
|
||||
for (auto& iter : sources_)
|
||||
{
|
||||
if (iter != nullptr)
|
||||
{
|
||||
iter->stop();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
NodeManager::~NodeManager()
|
||||
{
|
||||
stop();
|
||||
}
|
||||
|
||||
} // namespace lidar
|
||||
} // namespace robosense
|
||||
61
src/airy/rslidar_sdk-main/src/manager/node_manager.hpp
Normal file
@ -0,0 +1,61 @@
|
||||
/*********************************************************************************************************************
|
||||
Copyright (c) 2020 RoboSense
|
||||
All rights reserved
|
||||
|
||||
By downloading, copying, installing or using the software you agree to this license. If you do not agree to this
|
||||
license, do not download, install, copy or use the software.
|
||||
|
||||
License Agreement
|
||||
For RoboSense LiDAR SDK Library
|
||||
(3-clause BSD License)
|
||||
|
||||
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the
|
||||
following conditions are met:
|
||||
|
||||
1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following
|
||||
disclaimer.
|
||||
|
||||
2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following
|
||||
disclaimer in the documentation and/or other materials provided with the distribution.
|
||||
|
||||
3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used
|
||||
to endorse or promote products derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
|
||||
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
|
||||
WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
|
||||
THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*********************************************************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "utility/yaml_reader.hpp"
|
||||
#include "source/source.hpp"
|
||||
|
||||
namespace robosense
|
||||
{
|
||||
namespace lidar
|
||||
{
|
||||
|
||||
class NodeManager
|
||||
{
|
||||
public:
|
||||
|
||||
void init(const YAML::Node& config);
|
||||
void start();
|
||||
void stop();
|
||||
|
||||
~NodeManager();
|
||||
NodeManager() = default;
|
||||
|
||||
private:
|
||||
|
||||
std::vector<Source::Ptr> sources_;
|
||||
};
|
||||
|
||||
} // namespace lidar
|
||||
} // namespace robosense
|
||||
|
||||
@ -0,0 +1,3 @@
|
||||
std_msgs/Header header
|
||||
uint8 type
|
||||
uint8[] data
|
||||
@ -0,0 +1,4 @@
|
||||
std_msgs/Header header
|
||||
uint8 is_difop
|
||||
uint8 is_frame_begin
|
||||
uint8[] data
|
||||
@ -0,0 +1,237 @@
|
||||
// Generated by gencpp from file rscamera_msg/RsCompressedImage.msg
|
||||
// DO NOT EDIT!
|
||||
|
||||
|
||||
#ifndef RSCAMERA_MESSAGE_RSCOMPRESSEDIMAGE_H
|
||||
#define RSCAMERA_MESSAGE_RSCOMPRESSEDIMAGE_H
|
||||
|
||||
|
||||
#include <string>
|
||||
#include <vector>
|
||||
#include <memory>
|
||||
|
||||
#include <ros/types.h>
|
||||
#include <ros/serialization.h>
|
||||
#include <ros/builtin_message_traits.h>
|
||||
#include <ros/message_operations.h>
|
||||
|
||||
#include <std_msgs/Header.h>
|
||||
|
||||
namespace rscamera_msg
|
||||
{
|
||||
template <class ContainerAllocator>
|
||||
struct RsCompressedImage_
|
||||
{
|
||||
typedef RsCompressedImage_<ContainerAllocator> Type;
|
||||
|
||||
RsCompressedImage_()
|
||||
: header()
|
||||
, type(0)
|
||||
, data() {
|
||||
}
|
||||
RsCompressedImage_(const ContainerAllocator& _alloc)
|
||||
: header(_alloc)
|
||||
, type(0)
|
||||
, data(_alloc) {
|
||||
(void)_alloc;
|
||||
}
|
||||
|
||||
|
||||
|
||||
typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
|
||||
_header_type header;
|
||||
|
||||
typedef uint8_t _type_type;
|
||||
_type_type type;
|
||||
|
||||
typedef std::vector<uint8_t, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<uint8_t>> _data_type;
|
||||
_data_type data;
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
typedef boost::shared_ptr< ::rscamera_msg::RsCompressedImage_<ContainerAllocator> > Ptr;
|
||||
typedef boost::shared_ptr< ::rscamera_msg::RsCompressedImage_<ContainerAllocator> const> ConstPtr;
|
||||
|
||||
}; // struct RsCompressedImage_
|
||||
|
||||
typedef ::rscamera_msg::RsCompressedImage_<std::allocator<void> > RsCompressedImage;
|
||||
|
||||
typedef boost::shared_ptr< ::rscamera_msg::RsCompressedImage > RsCompressedImagePtr;
|
||||
typedef boost::shared_ptr< ::rscamera_msg::RsCompressedImage const> RsCompressedImageConstPtr;
|
||||
|
||||
// constants requiring out of line definition
|
||||
|
||||
|
||||
|
||||
template<typename ContainerAllocator>
|
||||
std::ostream& operator<<(std::ostream& s, const ::rscamera_msg::RsCompressedImage_<ContainerAllocator> & v)
|
||||
{
|
||||
ros::message_operations::Printer< ::rscamera_msg::RsCompressedImage_<ContainerAllocator> >::stream(s, "", v);
|
||||
return s;
|
||||
}
|
||||
|
||||
|
||||
template<typename ContainerAllocator1, typename ContainerAllocator2>
|
||||
bool operator==(const ::rscamera_msg::RsCompressedImage_<ContainerAllocator1> & lhs, const ::rscamera_msg::RsCompressedImage_<ContainerAllocator2> & rhs)
|
||||
{
|
||||
return lhs.header == rhs.header &&
|
||||
lhs.type == rhs.type &&
|
||||
lhs.data == rhs.data;
|
||||
}
|
||||
|
||||
template<typename ContainerAllocator1, typename ContainerAllocator2>
|
||||
bool operator!=(const ::rscamera_msg::RsCompressedImage_<ContainerAllocator1> & lhs, const ::rscamera_msg::RsCompressedImage_<ContainerAllocator2> & rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
|
||||
} // namespace rscamera_msg
|
||||
|
||||
namespace ros
|
||||
{
|
||||
namespace message_traits
|
||||
{
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct IsMessage< ::rscamera_msg::RsCompressedImage_<ContainerAllocator> >
|
||||
: TrueType
|
||||
{ };
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct IsMessage< ::rscamera_msg::RsCompressedImage_<ContainerAllocator> const>
|
||||
: TrueType
|
||||
{ };
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct IsFixedSize< ::rscamera_msg::RsCompressedImage_<ContainerAllocator> >
|
||||
: FalseType
|
||||
{ };
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct IsFixedSize< ::rscamera_msg::RsCompressedImage_<ContainerAllocator> const>
|
||||
: FalseType
|
||||
{ };
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct HasHeader< ::rscamera_msg::RsCompressedImage_<ContainerAllocator> >
|
||||
: TrueType
|
||||
{ };
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct HasHeader< ::rscamera_msg::RsCompressedImage_<ContainerAllocator> const>
|
||||
: TrueType
|
||||
{ };
|
||||
|
||||
|
||||
template<class ContainerAllocator>
|
||||
struct MD5Sum< ::rscamera_msg::RsCompressedImage_<ContainerAllocator> >
|
||||
{
|
||||
static const char* value()
|
||||
{
|
||||
return "4044c7c7aa754eb9dc4031aaf0ca91a7";
|
||||
}
|
||||
|
||||
static const char* value(const ::rscamera_msg::RsCompressedImage_<ContainerAllocator>&) { return value(); }
|
||||
static const uint64_t static_value1 = 0x4044c7c7aa754eb9ULL;
|
||||
static const uint64_t static_value2 = 0xdc4031aaf0ca91a7ULL;
|
||||
};
|
||||
|
||||
template<class ContainerAllocator>
|
||||
struct DataType< ::rscamera_msg::RsCompressedImage_<ContainerAllocator> >
|
||||
{
|
||||
static const char* value()
|
||||
{
|
||||
return "rscamera_msg/RsCompressedImage";
|
||||
}
|
||||
|
||||
static const char* value(const ::rscamera_msg::RsCompressedImage_<ContainerAllocator>&) { return value(); }
|
||||
};
|
||||
|
||||
template<class ContainerAllocator>
|
||||
struct Definition< ::rscamera_msg::RsCompressedImage_<ContainerAllocator> >
|
||||
{
|
||||
static const char* value()
|
||||
{
|
||||
return "std_msgs/Header header\n"
|
||||
"uint8 type\n"
|
||||
"uint8[] data\n"
|
||||
"\n"
|
||||
"================================================================================\n"
|
||||
"MSG: std_msgs/Header\n"
|
||||
"# Standard metadata for higher-level stamped data types.\n"
|
||||
"# This is generally used to communicate timestamped data \n"
|
||||
"# in a particular coordinate frame.\n"
|
||||
"# \n"
|
||||
"# sequence ID: consecutively increasing ID \n"
|
||||
"uint32 seq\n"
|
||||
"#Two-integer timestamp that is expressed as:\n"
|
||||
"# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n"
|
||||
"# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n"
|
||||
"# time-handling sugar is provided by the client library\n"
|
||||
"time stamp\n"
|
||||
"#Frame this data is associated with\n"
|
||||
"string frame_id\n"
|
||||
;
|
||||
}
|
||||
|
||||
static const char* value(const ::rscamera_msg::RsCompressedImage_<ContainerAllocator>&) { return value(); }
|
||||
};
|
||||
|
||||
} // namespace message_traits
|
||||
} // namespace ros
|
||||
|
||||
namespace ros
|
||||
{
|
||||
namespace serialization
|
||||
{
|
||||
|
||||
template<class ContainerAllocator> struct Serializer< ::rscamera_msg::RsCompressedImage_<ContainerAllocator> >
|
||||
{
|
||||
template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
|
||||
{
|
||||
stream.next(m.header);
|
||||
stream.next(m.type);
|
||||
stream.next(m.data);
|
||||
}
|
||||
|
||||
ROS_DECLARE_ALLINONE_SERIALIZER
|
||||
}; // struct RsCompressedImage_
|
||||
|
||||
} // namespace serialization
|
||||
} // namespace ros
|
||||
|
||||
namespace ros
|
||||
{
|
||||
namespace message_operations
|
||||
{
|
||||
|
||||
template<class ContainerAllocator>
|
||||
struct Printer< ::rscamera_msg::RsCompressedImage_<ContainerAllocator> >
|
||||
{
|
||||
template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::rscamera_msg::RsCompressedImage_<ContainerAllocator>& v)
|
||||
{
|
||||
s << indent << "header: ";
|
||||
s << std::endl;
|
||||
Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
|
||||
s << indent << "type: ";
|
||||
Printer<uint8_t>::stream(s, indent + " ", v.type);
|
||||
s << indent << "data[]" << std::endl;
|
||||
for (size_t i = 0; i < v.data.size(); ++i)
|
||||
{
|
||||
s << indent << " data[" << i << "]: ";
|
||||
Printer<uint8_t>::stream(s, indent + " ", v.data[i]);
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace message_operations
|
||||
} // namespace ros
|
||||
|
||||
#endif // RSCAMERA_MESSAGE_RSCOMPRESSEDIMAGE_H
|
||||
247
src/airy/rslidar_sdk-main/src/msg/ros_msg/rslidar_packet.hpp
Normal file
@ -0,0 +1,247 @@
|
||||
// Generated by gencpp from file rslidar_msg/RslidarPacket.msg
|
||||
// DO NOT EDIT!
|
||||
|
||||
|
||||
#ifndef RSLIDAR_MSG_MESSAGE_RSLIDARPACKET_H
|
||||
#define RSLIDAR_MSG_MESSAGE_RSLIDARPACKET_H
|
||||
|
||||
|
||||
#include <string>
|
||||
#include <vector>
|
||||
#include <map>
|
||||
|
||||
#include <ros/types.h>
|
||||
#include <ros/serialization.h>
|
||||
#include <ros/builtin_message_traits.h>
|
||||
#include <ros/message_operations.h>
|
||||
|
||||
#include <std_msgs/Header.h>
|
||||
|
||||
namespace rslidar_msg
|
||||
{
|
||||
template <class ContainerAllocator>
|
||||
struct RslidarPacket_
|
||||
{
|
||||
typedef RslidarPacket_<ContainerAllocator> Type;
|
||||
|
||||
RslidarPacket_()
|
||||
: header()
|
||||
, is_difop(0)
|
||||
, is_frame_begin(0)
|
||||
, data() {
|
||||
}
|
||||
RslidarPacket_(const ContainerAllocator& _alloc)
|
||||
: header(_alloc)
|
||||
, is_difop(0)
|
||||
, is_frame_begin(0)
|
||||
, data(_alloc) {
|
||||
(void)_alloc;
|
||||
}
|
||||
|
||||
|
||||
|
||||
typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
|
||||
_header_type header;
|
||||
|
||||
typedef uint8_t _is_difop_type;
|
||||
_is_difop_type is_difop;
|
||||
|
||||
typedef uint8_t _is_frame_begin_type;
|
||||
_is_frame_begin_type is_frame_begin;
|
||||
|
||||
typedef std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > _data_type;
|
||||
_data_type data;
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
typedef boost::shared_ptr< ::rslidar_msg::RslidarPacket_<ContainerAllocator> > Ptr;
|
||||
typedef boost::shared_ptr< ::rslidar_msg::RslidarPacket_<ContainerAllocator> const> ConstPtr;
|
||||
|
||||
}; // struct RslidarPacket_
|
||||
|
||||
typedef ::rslidar_msg::RslidarPacket_<std::allocator<void> > RslidarPacket;
|
||||
|
||||
typedef boost::shared_ptr< ::rslidar_msg::RslidarPacket > RslidarPacketPtr;
|
||||
typedef boost::shared_ptr< ::rslidar_msg::RslidarPacket const> RslidarPacketConstPtr;
|
||||
|
||||
// constants requiring out of line definition
|
||||
|
||||
|
||||
|
||||
template<typename ContainerAllocator>
|
||||
std::ostream& operator<<(std::ostream& s, const ::rslidar_msg::RslidarPacket_<ContainerAllocator> & v)
|
||||
{
|
||||
ros::message_operations::Printer< ::rslidar_msg::RslidarPacket_<ContainerAllocator> >::stream(s, "", v);
|
||||
return s;
|
||||
}
|
||||
|
||||
|
||||
template<typename ContainerAllocator1, typename ContainerAllocator2>
|
||||
bool operator==(const ::rslidar_msg::RslidarPacket_<ContainerAllocator1> & lhs, const ::rslidar_msg::RslidarPacket_<ContainerAllocator2> & rhs)
|
||||
{
|
||||
return lhs.header == rhs.header &&
|
||||
lhs.is_difop == rhs.is_difop &&
|
||||
lhs.is_frame_begin == rhs.is_frame_begin &&
|
||||
lhs.data == rhs.data;
|
||||
}
|
||||
|
||||
template<typename ContainerAllocator1, typename ContainerAllocator2>
|
||||
bool operator!=(const ::rslidar_msg::RslidarPacket_<ContainerAllocator1> & lhs, const ::rslidar_msg::RslidarPacket_<ContainerAllocator2> & rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
|
||||
} // namespace rslidar_msg
|
||||
|
||||
namespace ros
|
||||
{
|
||||
namespace message_traits
|
||||
{
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct IsMessage< ::rslidar_msg::RslidarPacket_<ContainerAllocator> >
|
||||
: TrueType
|
||||
{ };
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct IsMessage< ::rslidar_msg::RslidarPacket_<ContainerAllocator> const>
|
||||
: TrueType
|
||||
{ };
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct IsFixedSize< ::rslidar_msg::RslidarPacket_<ContainerAllocator> >
|
||||
: FalseType
|
||||
{ };
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct IsFixedSize< ::rslidar_msg::RslidarPacket_<ContainerAllocator> const>
|
||||
: FalseType
|
||||
{ };
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct HasHeader< ::rslidar_msg::RslidarPacket_<ContainerAllocator> >
|
||||
: TrueType
|
||||
{ };
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct HasHeader< ::rslidar_msg::RslidarPacket_<ContainerAllocator> const>
|
||||
: TrueType
|
||||
{ };
|
||||
|
||||
|
||||
template<class ContainerAllocator>
|
||||
struct MD5Sum< ::rslidar_msg::RslidarPacket_<ContainerAllocator> >
|
||||
{
|
||||
static const char* value()
|
||||
{
|
||||
return "4b1cc155a9097c0cb935a7abf46d6eef";
|
||||
}
|
||||
|
||||
static const char* value(const ::rslidar_msg::RslidarPacket_<ContainerAllocator>&) { return value(); }
|
||||
static const uint64_t static_value1 = 0x4b1cc155a9097c0cULL;
|
||||
static const uint64_t static_value2 = 0xb935a7abf46d6eefULL;
|
||||
};
|
||||
|
||||
template<class ContainerAllocator>
|
||||
struct DataType< ::rslidar_msg::RslidarPacket_<ContainerAllocator> >
|
||||
{
|
||||
static const char* value()
|
||||
{
|
||||
return "rslidar_msg/RslidarPacket";
|
||||
}
|
||||
|
||||
static const char* value(const ::rslidar_msg::RslidarPacket_<ContainerAllocator>&) { return value(); }
|
||||
};
|
||||
|
||||
template<class ContainerAllocator>
|
||||
struct Definition< ::rslidar_msg::RslidarPacket_<ContainerAllocator> >
|
||||
{
|
||||
static const char* value()
|
||||
{
|
||||
return "std_msgs/Header header\n"
|
||||
"uint8 is_difop\n"
|
||||
"uint8 is_frame_begin\n"
|
||||
"uint8[] data\n"
|
||||
"\n"
|
||||
"================================================================================\n"
|
||||
"MSG: std_msgs/Header\n"
|
||||
"# Standard metadata for higher-level stamped data types.\n"
|
||||
"# This is generally used to communicate timestamped data \n"
|
||||
"# in a particular coordinate frame.\n"
|
||||
"# \n"
|
||||
"# sequence ID: consecutively increasing ID \n"
|
||||
"uint32 seq\n"
|
||||
"#Two-integer timestamp that is expressed as:\n"
|
||||
"# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n"
|
||||
"# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n"
|
||||
"# time-handling sugar is provided by the client library\n"
|
||||
"time stamp\n"
|
||||
"#Frame this data is associated with\n"
|
||||
"string frame_id\n"
|
||||
;
|
||||
}
|
||||
|
||||
static const char* value(const ::rslidar_msg::RslidarPacket_<ContainerAllocator>&) { return value(); }
|
||||
};
|
||||
|
||||
} // namespace message_traits
|
||||
} // namespace ros
|
||||
|
||||
namespace ros
|
||||
{
|
||||
namespace serialization
|
||||
{
|
||||
|
||||
template<class ContainerAllocator> struct Serializer< ::rslidar_msg::RslidarPacket_<ContainerAllocator> >
|
||||
{
|
||||
template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
|
||||
{
|
||||
stream.next(m.header);
|
||||
stream.next(m.is_difop);
|
||||
stream.next(m.is_frame_begin);
|
||||
stream.next(m.data);
|
||||
}
|
||||
|
||||
ROS_DECLARE_ALLINONE_SERIALIZER
|
||||
}; // struct RslidarPacket_
|
||||
|
||||
} // namespace serialization
|
||||
} // namespace ros
|
||||
|
||||
namespace ros
|
||||
{
|
||||
namespace message_operations
|
||||
{
|
||||
|
||||
template<class ContainerAllocator>
|
||||
struct Printer< ::rslidar_msg::RslidarPacket_<ContainerAllocator> >
|
||||
{
|
||||
template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::rslidar_msg::RslidarPacket_<ContainerAllocator>& v)
|
||||
{
|
||||
s << indent << "header: ";
|
||||
s << std::endl;
|
||||
Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
|
||||
s << indent << "is_difop: ";
|
||||
Printer<uint8_t>::stream(s, indent + " ", v.is_difop);
|
||||
s << indent << "is_frame_begin: ";
|
||||
Printer<uint8_t>::stream(s, indent + " ", v.is_frame_begin);
|
||||
s << indent << "data[]" << std::endl;
|
||||
for (size_t i = 0; i < v.data.size(); ++i)
|
||||
{
|
||||
s << indent << " data[" << i << "]: ";
|
||||
Printer<uint8_t>::stream(s, indent + " ", v.data[i]);
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace message_operations
|
||||
} // namespace ros
|
||||
|
||||
#endif // RSLIDAR_MSG_MESSAGE_RSLIDARPACKET_H
|
||||
@ -0,0 +1,196 @@
|
||||
// Generated by gencpp from file rslidar_msgs/rslidarPacket.msg
|
||||
// DO NOT EDIT!
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <string>
|
||||
#include <vector>
|
||||
#include <map>
|
||||
|
||||
#include <ros/types.h>
|
||||
#include <ros/serialization.h>
|
||||
#include <ros/builtin_message_traits.h>
|
||||
#include <ros/message_operations.h>
|
||||
|
||||
namespace rslidar_msgs
|
||||
{
|
||||
template <class ContainerAllocator>
|
||||
struct rslidarPacket_
|
||||
{
|
||||
typedef rslidarPacket_<ContainerAllocator> Type;
|
||||
|
||||
rslidarPacket_() : stamp(), data()
|
||||
{
|
||||
data.assign(0);
|
||||
}
|
||||
rslidarPacket_(const ContainerAllocator& _alloc) : stamp(), data()
|
||||
{
|
||||
(void)_alloc;
|
||||
data.assign(0);
|
||||
}
|
||||
|
||||
typedef ros::Time _stamp_type;
|
||||
_stamp_type stamp;
|
||||
|
||||
typedef boost::array<uint8_t, 1248> _data_type;
|
||||
_data_type data;
|
||||
|
||||
typedef boost::shared_ptr< ::rslidar_msgs::rslidarPacket_<ContainerAllocator> > Ptr;
|
||||
typedef boost::shared_ptr< ::rslidar_msgs::rslidarPacket_<ContainerAllocator> const> ConstPtr;
|
||||
|
||||
}; // struct rslidarPacket_
|
||||
|
||||
typedef ::rslidar_msgs::rslidarPacket_<std::allocator<void> > rslidarPacket;
|
||||
|
||||
typedef boost::shared_ptr< ::rslidar_msgs::rslidarPacket> rslidarPacketPtr;
|
||||
typedef boost::shared_ptr< ::rslidar_msgs::rslidarPacket const> rslidarPacketConstPtr;
|
||||
|
||||
// constants requiring out of line definition
|
||||
|
||||
template <typename ContainerAllocator>
|
||||
std::ostream& operator<<(std::ostream& s, const ::rslidar_msgs::rslidarPacket_<ContainerAllocator>& v)
|
||||
{
|
||||
ros::message_operations::Printer< ::rslidar_msgs::rslidarPacket_<ContainerAllocator> >::stream(s, "", v);
|
||||
return s;
|
||||
}
|
||||
|
||||
} // namespace rslidar_msgs
|
||||
|
||||
namespace ros
|
||||
{
|
||||
namespace message_traits
|
||||
{
|
||||
// BOOLTRAITS {'IsFixedSize': true, 'IsMessage': true, 'HasHeader': false}
|
||||
// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'rslidar_msgs':
|
||||
// ['/home/xzd/catkin_ws/src/rs_driver/rslidar_msgs/msg']}
|
||||
|
||||
// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__',
|
||||
// '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__',
|
||||
// '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name',
|
||||
// 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types']
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct IsFixedSize< ::rslidar_msgs::rslidarPacket_<ContainerAllocator> > : TrueType
|
||||
{
|
||||
};
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct IsFixedSize< ::rslidar_msgs::rslidarPacket_<ContainerAllocator> const> : TrueType
|
||||
{
|
||||
};
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct IsMessage< ::rslidar_msgs::rslidarPacket_<ContainerAllocator> > : TrueType
|
||||
{
|
||||
};
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct IsMessage< ::rslidar_msgs::rslidarPacket_<ContainerAllocator> const> : TrueType
|
||||
{
|
||||
};
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct HasHeader< ::rslidar_msgs::rslidarPacket_<ContainerAllocator> > : FalseType
|
||||
{
|
||||
};
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct HasHeader< ::rslidar_msgs::rslidarPacket_<ContainerAllocator> const> : FalseType
|
||||
{
|
||||
};
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct MD5Sum< ::rslidar_msgs::rslidarPacket_<ContainerAllocator> >
|
||||
{
|
||||
static const char* value()
|
||||
{
|
||||
return "1e4288e00b9222ea477b73350bf24f51";
|
||||
}
|
||||
|
||||
static const char* value(const ::rslidar_msgs::rslidarPacket_<ContainerAllocator>&)
|
||||
{
|
||||
return value();
|
||||
}
|
||||
static const uint64_t static_value1 = 0x1e4288e00b9222eaULL;
|
||||
static const uint64_t static_value2 = 0x477b73350bf24f51ULL;
|
||||
};
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct DataType< ::rslidar_msgs::rslidarPacket_<ContainerAllocator> >
|
||||
{
|
||||
static const char* value()
|
||||
{
|
||||
return "rslidar_msgs/rslidarPacket";
|
||||
}
|
||||
|
||||
static const char* value(const ::rslidar_msgs::rslidarPacket_<ContainerAllocator>&)
|
||||
{
|
||||
return value();
|
||||
}
|
||||
};
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct Definition< ::rslidar_msgs::rslidarPacket_<ContainerAllocator> >
|
||||
{
|
||||
static const char* value()
|
||||
{
|
||||
return "# Raw LIDAR packet.\n\
|
||||
\n\
|
||||
timestamp # packet timestamp\n\
|
||||
uint8[1248] data # packet contents\n\
|
||||
\n\
|
||||
";
|
||||
}
|
||||
|
||||
static const char* value(const ::rslidar_msgs::rslidarPacket_<ContainerAllocator>&)
|
||||
{
|
||||
return value();
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace message_traits
|
||||
} // namespace ros
|
||||
|
||||
namespace ros
|
||||
{
|
||||
namespace serialization
|
||||
{
|
||||
template <class ContainerAllocator>
|
||||
struct Serializer< ::rslidar_msgs::rslidarPacket_<ContainerAllocator> >
|
||||
{
|
||||
template <typename Stream, typename T>
|
||||
inline static void allInOne(Stream& stream, T m)
|
||||
{
|
||||
stream.next(m.stamp);
|
||||
stream.next(m.data);
|
||||
}
|
||||
|
||||
ROS_DECLARE_ALLINONE_SERIALIZER
|
||||
}; // struct rslidarPacket_
|
||||
|
||||
} // namespace serialization
|
||||
} // namespace ros
|
||||
|
||||
namespace ros
|
||||
{
|
||||
namespace message_operations
|
||||
{
|
||||
template <class ContainerAllocator>
|
||||
struct Printer< ::rslidar_msgs::rslidarPacket_<ContainerAllocator> >
|
||||
{
|
||||
template <typename Stream>
|
||||
static void stream(Stream& s, const std::string& indent, const ::rslidar_msgs::rslidarPacket_<ContainerAllocator>& v)
|
||||
{
|
||||
s << indent << "stamp: ";
|
||||
Printer<ros::Time>::stream(s, indent + " ", v.stamp);
|
||||
s << indent << "data[]" << std::endl;
|
||||
for (size_t i = 0; i < v.data.size(); ++i)
|
||||
{
|
||||
s << indent << " data[" << i << "]: ";
|
||||
Printer<uint8_t>::stream(s, indent + " ", v.data[i]);
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace message_operations
|
||||
} // namespace ros
|
||||
@ -0,0 +1,228 @@
|
||||
// Generated by gencpp from file rslidar_msgs/rslidarScan.msg
|
||||
// DO NOT EDIT!
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <string>
|
||||
#include <vector>
|
||||
#include <map>
|
||||
|
||||
#include <ros/types.h>
|
||||
#include <ros/serialization.h>
|
||||
#include <ros/builtin_message_traits.h>
|
||||
#include <ros/message_operations.h>
|
||||
|
||||
#include <std_msgs/Header.h>
|
||||
#include "msg/ros_msg/rslidar_packet_legacy.hpp"
|
||||
|
||||
namespace rslidar_msgs
|
||||
{
|
||||
template <class ContainerAllocator>
|
||||
struct rslidarScan_
|
||||
{
|
||||
typedef rslidarScan_<ContainerAllocator> Type;
|
||||
|
||||
rslidarScan_() : header(), packets()
|
||||
{
|
||||
}
|
||||
rslidarScan_(const ContainerAllocator& _alloc) : header(_alloc), packets(_alloc)
|
||||
{
|
||||
(void)_alloc;
|
||||
}
|
||||
|
||||
typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
|
||||
_header_type header;
|
||||
|
||||
typedef std::vector<
|
||||
::rslidar_msgs::rslidarPacket_<ContainerAllocator>,
|
||||
typename ContainerAllocator::template rebind<::rslidar_msgs::rslidarPacket_<ContainerAllocator>>::other>
|
||||
_packets_type;
|
||||
_packets_type packets;
|
||||
|
||||
typedef boost::shared_ptr<::rslidar_msgs::rslidarScan_<ContainerAllocator>> Ptr;
|
||||
typedef boost::shared_ptr<::rslidar_msgs::rslidarScan_<ContainerAllocator> const> ConstPtr;
|
||||
|
||||
}; // struct rslidarScan_
|
||||
|
||||
typedef ::rslidar_msgs::rslidarScan_<std::allocator<void>> rslidarScan;
|
||||
|
||||
typedef boost::shared_ptr<::rslidar_msgs::rslidarScan> rslidarScanPtr;
|
||||
typedef boost::shared_ptr<::rslidar_msgs::rslidarScan const> rslidarScanConstPtr;
|
||||
|
||||
// constants requiring out of line definition
|
||||
|
||||
template <typename ContainerAllocator>
|
||||
std::ostream& operator<<(std::ostream& s, const ::rslidar_msgs::rslidarScan_<ContainerAllocator>& v)
|
||||
{
|
||||
ros::message_operations::Printer<::rslidar_msgs::rslidarScan_<ContainerAllocator>>::stream(s, "", v);
|
||||
return s;
|
||||
}
|
||||
|
||||
} // namespace rslidar_msgs
|
||||
|
||||
namespace ros
|
||||
{
|
||||
namespace message_traits
|
||||
{
|
||||
// BOOLTRAITS {'IsFixedSize': false, 'IsMessage': true, 'HasHeader': true}
|
||||
// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'rslidar_msgs':
|
||||
// ['/home/xzd/catkin_ws/src/rs_driver/rslidar_msgs/msg']}
|
||||
|
||||
// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__',
|
||||
// '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__',
|
||||
// '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name',
|
||||
// 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types']
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct IsFixedSize<::rslidar_msgs::rslidarScan_<ContainerAllocator>> : FalseType
|
||||
{
|
||||
};
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct IsFixedSize<::rslidar_msgs::rslidarScan_<ContainerAllocator> const> : FalseType
|
||||
{
|
||||
};
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct IsMessage<::rslidar_msgs::rslidarScan_<ContainerAllocator>> : TrueType
|
||||
{
|
||||
};
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct IsMessage<::rslidar_msgs::rslidarScan_<ContainerAllocator> const> : TrueType
|
||||
{
|
||||
};
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct HasHeader<::rslidar_msgs::rslidarScan_<ContainerAllocator>> : TrueType
|
||||
{
|
||||
};
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct HasHeader<::rslidar_msgs::rslidarScan_<ContainerAllocator> const> : TrueType
|
||||
{
|
||||
};
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct MD5Sum<::rslidar_msgs::rslidarScan_<ContainerAllocator>>
|
||||
{
|
||||
static const char* value()
|
||||
{
|
||||
return "ff6baa58985b528481871cbaf1bb342f";
|
||||
}
|
||||
|
||||
static const char* value(const ::rslidar_msgs::rslidarScan_<ContainerAllocator>&)
|
||||
{
|
||||
return value();
|
||||
}
|
||||
static const uint64_t static_value1 = 0xff6baa58985b5284ULL;
|
||||
static const uint64_t static_value2 = 0x81871cbaf1bb342fULL;
|
||||
};
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct DataType<::rslidar_msgs::rslidarScan_<ContainerAllocator>>
|
||||
{
|
||||
static const char* value()
|
||||
{
|
||||
return "rslidar_msgs/rslidarScan";
|
||||
}
|
||||
|
||||
static const char* value(const ::rslidar_msgs::rslidarScan_<ContainerAllocator>&)
|
||||
{
|
||||
return value();
|
||||
}
|
||||
};
|
||||
|
||||
template <class ContainerAllocator>
|
||||
struct Definition<::rslidar_msgs::rslidarScan_<ContainerAllocator>>
|
||||
{
|
||||
static const char* value()
|
||||
{
|
||||
return "# LIDAR scan packets.\n\
|
||||
\n\
|
||||
Header header # standard ROS message header\n\
|
||||
rslidarPacket[] packets # vector of raw packets\n\
|
||||
\n\
|
||||
================================================================================\n\
|
||||
MSG: std_msgs/Header\n\
|
||||
# Standard metadata for higher-level stamped data types.\n\
|
||||
# This is generally used to communicate timestamped data \n\
|
||||
# in a particular coordinate frame.\n\
|
||||
# \n\
|
||||
# sequence ID: consecutively increasing ID \n\
|
||||
uint32 seq\n\
|
||||
#Two-integer timestamp that is expressed as:\n\
|
||||
# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
|
||||
# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
|
||||
# time-handling sugar is provided by the client library\n\
|
||||
timestamp\n\
|
||||
#Frame this data is associated with\n\
|
||||
# 0: no frame\n\
|
||||
# 1: global frame\n\
|
||||
string frame_id\n\
|
||||
\n\
|
||||
================================================================================\n\
|
||||
MSG: rslidar_msgs/rslidarPacket\n\
|
||||
# Raw LIDAR packet.\n\
|
||||
\n\
|
||||
timestamp # packet timestamp\n\
|
||||
uint8[1248] data # packet contents\n\
|
||||
\n\
|
||||
";
|
||||
}
|
||||
|
||||
static const char* value(const ::rslidar_msgs::rslidarScan_<ContainerAllocator>&)
|
||||
{
|
||||
return value();
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace message_traits
|
||||
} // namespace ros
|
||||
|
||||
namespace ros
|
||||
{
|
||||
namespace serialization
|
||||
{
|
||||
template <class ContainerAllocator>
|
||||
struct Serializer<::rslidar_msgs::rslidarScan_<ContainerAllocator>>
|
||||
{
|
||||
template <typename Stream, typename T>
|
||||
inline static void allInOne(Stream& stream, T m)
|
||||
{
|
||||
stream.next(m.header);
|
||||
stream.next(m.packets);
|
||||
}
|
||||
|
||||
ROS_DECLARE_ALLINONE_SERIALIZER
|
||||
}; // struct rslidarScan_
|
||||
|
||||
} // namespace serialization
|
||||
} // namespace ros
|
||||
|
||||
namespace ros
|
||||
{
|
||||
namespace message_operations
|
||||
{
|
||||
template <class ContainerAllocator>
|
||||
struct Printer<::rslidar_msgs::rslidarScan_<ContainerAllocator>>
|
||||
{
|
||||
template <typename Stream>
|
||||
static void stream(Stream& s, const std::string& indent, const ::rslidar_msgs::rslidarScan_<ContainerAllocator>& v)
|
||||
{
|
||||
s << indent << "header: ";
|
||||
s << std::endl;
|
||||
Printer<::std_msgs::Header_<ContainerAllocator>>::stream(s, indent + " ", v.header);
|
||||
s << indent << "packets[]" << std::endl;
|
||||
for (size_t i = 0; i < v.packets.size(); ++i)
|
||||
{
|
||||
s << indent << " packets[" << i << "]: ";
|
||||
s << std::endl;
|
||||
s << indent;
|
||||
Printer<::rslidar_msgs::rslidarPacket_<ContainerAllocator>>::stream(s, indent + " ", v.packets[i]);
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace message_operations
|
||||
} // namespace ros
|
||||
@ -0,0 +1,50 @@
|
||||
/*********************************************************************************************************************
|
||||
Copyright (c) 2020 RoboSense
|
||||
All rights reserved
|
||||
|
||||
By downloading, copying, installing or using the software you agree to this license. If you do not agree to this
|
||||
license, do not download, install, copy or use the software.
|
||||
|
||||
License Agreement
|
||||
For RoboSense LiDAR SDK Library
|
||||
(3-clause BSD License)
|
||||
|
||||
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the
|
||||
following conditions are met:
|
||||
|
||||
1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following
|
||||
disclaimer.
|
||||
|
||||
2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following
|
||||
disclaimer in the documentation and/or other materials provided with the distribution.
|
||||
|
||||
3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used
|
||||
to endorse or promote products derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
|
||||
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
|
||||
WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
|
||||
THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*********************************************************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "rs_driver/msg/point_cloud_msg.hpp"
|
||||
|
||||
#ifdef POINT_TYPE_XYZI
|
||||
typedef PointCloudT<PointXYZI> LidarPointCloudMsg;
|
||||
#elif defined(POINT_TYPE_XYZIF)
|
||||
typedef PointCloudT<PointXYZIF> LidarPointCloudMsg;
|
||||
#elif defined(POINT_TYPE_XYZIRT)
|
||||
typedef PointCloudT<PointXYZIRT> LidarPointCloudMsg;
|
||||
#elif defined(POINT_TYPE_XYZIRTF)
|
||||
typedef PointCloudT<PointXYZIRTF> LidarPointCloudMsg;
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef ENABLE_IMU_DATA_PARSE
|
||||
#include "rs_driver/msg/imu_data_msg.hpp"
|
||||
#endif
|
||||
BIN
src/airy/rslidar_sdk-main/src/rs_driver.zip
Normal file
66
src/airy/rslidar_sdk-main/src/rs_driver/.clang-format
Normal file
@ -0,0 +1,66 @@
|
||||
---
|
||||
BasedOnStyle: Google
|
||||
AccessModifierOffset: -2
|
||||
ConstructorInitializerIndentWidth: 2
|
||||
AlignEscapedNewlinesLeft: false
|
||||
AlignTrailingComments: true
|
||||
AllowAllParametersOfDeclarationOnNextLine: false
|
||||
AllowShortIfStatementsOnASingleLine: false
|
||||
AllowShortLoopsOnASingleLine: false
|
||||
AllowShortFunctionsOnASingleLine: None
|
||||
AllowShortLoopsOnASingleLine: false
|
||||
AlwaysBreakTemplateDeclarations: true
|
||||
AlwaysBreakBeforeMultilineStrings: false
|
||||
BreakBeforeBinaryOperators: false
|
||||
BreakBeforeTernaryOperators: false
|
||||
BreakConstructorInitializersBeforeComma: true
|
||||
BinPackParameters: true
|
||||
ColumnLimit: 125
|
||||
ConstructorInitializerAllOnOneLineOrOnePerLine: true
|
||||
DerivePointerBinding: false
|
||||
PointerBindsToType: true
|
||||
ExperimentalAutoDetectBinPacking: false
|
||||
IndentCaseLabels: true
|
||||
MaxEmptyLinesToKeep: 1
|
||||
NamespaceIndentation: None
|
||||
ObjCSpaceBeforeProtocolList: true
|
||||
PenaltyBreakBeforeFirstCallParameter: 19
|
||||
PenaltyBreakComment: 60
|
||||
PenaltyBreakString: 1
|
||||
PenaltyBreakFirstLessLess: 1000
|
||||
PenaltyExcessCharacter: 1000
|
||||
PenaltyReturnTypeOnItsOwnLine: 90
|
||||
SpacesBeforeTrailingComments: 2
|
||||
Cpp11BracedListStyle: false
|
||||
Standard: Auto
|
||||
IndentWidth: 2
|
||||
TabWidth: 2
|
||||
UseTab: Never
|
||||
IndentFunctionDeclarationAfterType: false
|
||||
SpacesInParentheses: false
|
||||
SpacesInAngles: false
|
||||
SpaceInEmptyParentheses: false
|
||||
SpacesInCStyleCastParentheses: false
|
||||
SpaceAfterControlStatementKeyword: true
|
||||
SpaceBeforeAssignmentOperators: true
|
||||
ContinuationIndentWidth: 4
|
||||
SortIncludes: false
|
||||
SpaceAfterCStyleCast: false
|
||||
|
||||
# Configure each individual brace in BraceWrapping
|
||||
BreakBeforeBraces: Custom
|
||||
|
||||
# Control of individual brace wrapping cases
|
||||
BraceWrapping: {
|
||||
AfterClass: 'true'
|
||||
AfterControlStatement: 'true'
|
||||
AfterEnum : 'true'
|
||||
AfterFunction : 'true'
|
||||
AfterNamespace : 'true'
|
||||
AfterStruct : 'true'
|
||||
AfterUnion : 'true'
|
||||
BeforeCatch : 'true'
|
||||
BeforeElse : 'true'
|
||||
IndentBraces : 'false'
|
||||
}
|
||||
...
|
||||
376
src/airy/rslidar_sdk-main/src/rs_driver/CHANGELOG.md
Normal file
@ -0,0 +1,376 @@
|
||||
# CHANGLOG
|
||||
|
||||
# UnReleased
|
||||
|
||||
### Fix
|
||||
- Fix PCAP playback speed issue.
|
||||
- Fix the compilation issue of rs_driver_viewer on Ubuntu 22.04.
|
||||
|
||||
|
||||
## v1.5.17 2025-02-14
|
||||
|
||||
### Added
|
||||
- Support RSAIRY.
|
||||
- Support parsing IMU data for RSAIRY and RSE1.
|
||||
- Support parsing IMU extrinsics parameters frome difop for RSAIRY.
|
||||
|
||||
### Changed
|
||||
- Add feature attribute to point type.
|
||||
- Update help document.
|
||||
- Update block_time_offset as us for RSE1
|
||||
|
||||
### Fix
|
||||
- Fix compilation bug in win/input_socket_select.
|
||||
|
||||
|
||||
## v1.5.16 2024-08-27
|
||||
|
||||
### Added
|
||||
- Support sn parsing of RSMX.
|
||||
### Fixed
|
||||
- Update msop protocol of RSMX.
|
||||
- Fix compilation bug in epoll socket.
|
||||
- Fix compilation warning for unit tests.
|
||||
|
||||
|
||||
## v1.5.15 2024-08-07
|
||||
|
||||
### Added
|
||||
- Support RSM3.
|
||||
|
||||
|
||||
## v1.5.14 2024-07-15
|
||||
|
||||
### Added
|
||||
- Support multiple lidars with different multicast addresses and the same port.
|
||||
### Fixed
|
||||
- Fix the bug that only one lidar was parsed correctly when multiple bp4.0 were used.
|
||||
|
||||
## v1.5.13 2024-05-10
|
||||
|
||||
### Added
|
||||
- Support RSMX.
|
||||
### Fixed
|
||||
- Update timestamp parsing unit and the number of packets per frame in decoder_RSE1.
|
||||
- Update firing_tss of Helios/Helios16P/RubyPlus.
|
||||
- Fix compilation bug of unit test.
|
||||
|
||||
|
||||
## v1.5.12 2023-12-28
|
||||
|
||||
### Fixed
|
||||
- Fix bug in getting device info and status.
|
||||
- Fix bug in getting device temperature.
|
||||
|
||||
|
||||
## v1.5.11 2023-12-18
|
||||
|
||||
### Added
|
||||
- Split frame at the end of frame.
|
||||
|
||||
### Changed
|
||||
- Enable modify socket buffer size.
|
||||
|
||||
### Fixed
|
||||
- Fix the bug of rs_drvier_viewer.cpp abnormal crash.
|
||||
- Fix fir_tss of RSBPV4.
|
||||
- Fix rotation direction of RSBPV4 when reversal.
|
||||
|
||||
|
||||
## v1.5.10 2023-04-11
|
||||
|
||||
### Added
|
||||
- Merge RSBPV4 into RSBP
|
||||
|
||||
|
||||
## v1.5.9 2023-02-17
|
||||
|
||||
### Added
|
||||
- Support CRC32 check on MSOP/DIFOP packets.
|
||||
- Support parsing DIFOP packets to get config/status data.
|
||||
|
||||
### Changed
|
||||
- Filter MOSP/DIFOP messages with two bytes instead of one byte.
|
||||
- clear current cloud point when stop the instance of rs_driver.
|
||||
- Recover frame_id field for C user.
|
||||
|
||||
### Fixed
|
||||
- Fix pcl point cloud message. Adapt it to the format of the output file of rslidar_sdk.
|
||||
- Fix timestamp value of XYZIRT for RS128
|
||||
|
||||
|
||||
|
||||
## v1.5.8 2022-12-09
|
||||
|
||||
### Added
|
||||
- Add User's guide document
|
||||
|
||||
### Changed
|
||||
- Rename RSEOS as RSE1
|
||||
- Let user's distance values cover LiDAR's
|
||||
|
||||
### Fixed
|
||||
- Revert "Report error ERRCODE_MSOP_TIMEOUT if only DIFOP packet is received", to avoid incorrect error report.
|
||||
- Fix error distance of RSM2. Change it to 250m.
|
||||
|
||||
|
||||
|
||||
## v1.5.7 2022-10-09
|
||||
|
||||
### Added
|
||||
- Add tool to save as PCD file
|
||||
- Seperate RSBPV4 from RSBP
|
||||
- Add demo app demo_online_multi_lidars
|
||||
|
||||
### Changed
|
||||
- Disable error report in case of wrong block id for RS128/RS80 temporarily
|
||||
|
||||
### Fixed
|
||||
- Fix distance range of helios series. Also update distance ranges of other lidars
|
||||
- Report error ERRCODE_MSOP_TIMEOUT if only DIFOP packet is received
|
||||
|
||||
|
||||
|
||||
## v1.5.6 2022-09-01
|
||||
|
||||
### Added
|
||||
- Add option ENABLE_DOUBLE_RCVBUF to solve the packet-loss problem
|
||||
- Add option ENABLE_WAIT_IF_QUEUE_EMPTY to reduce CPU usage.
|
||||
- Add option ENABLE_STAMP_WITH_LOCAL to convert point cloud's timestamp to local time
|
||||
|
||||
### Changed
|
||||
- Make ERRCODEs different for MSOP/DIFOP Packet
|
||||
- Rename error code CLOUDOVERFLOW
|
||||
- For RSM2, recover its coordinate to ROS-compatible
|
||||
- For RSM2, adapt to increased MSOP packet len
|
||||
- Update `demo_pcap` and `rs_driver_viewer` with cloud queue
|
||||
- Accept angle.csv with vert angle only
|
||||
- Update help documents
|
||||
|
||||
### Fixed
|
||||
- For Ruby and Ruby Plus, fix the problem of parsing point cloud' timestamp.
|
||||
- Fix ERRCODE_MSOPTIMEOUT problem of input_sock_epoll
|
||||
|
||||
### Removed
|
||||
- Remove option ENABLE_RCVMMSG
|
||||
|
||||
|
||||
|
||||
## v1.5.5 2022-08-01
|
||||
|
||||
### Added
|
||||
- Compiled rs_driver_viewer on Windows, and add help doc
|
||||
- Add option to double RECVBUF of UDP sockets
|
||||
|
||||
### Changed
|
||||
- Update demo_online to exit orderly.
|
||||
|
||||
### Fixed
|
||||
- Fix runtime error of Eigen in case of ENABLE_TRANSFORM
|
||||
- Fix Compiling error on QNX
|
||||
- Fix pcap_rate
|
||||
- Fix the problem with repeated stop and start of driver
|
||||
|
||||
### Removed
|
||||
- Remove option of high priority thread
|
||||
|
||||
|
||||
|
||||
## v1.5.4 2022-07-01
|
||||
|
||||
### Added
|
||||
- Support Ruby_3.0_48
|
||||
- Add option to stamp point cloud with first point
|
||||
|
||||
### Updated
|
||||
- Distinguish 80/80v with lidar model
|
||||
- Use ROS coordinate for EOS
|
||||
- Enable PCAP file parsing in default mode
|
||||
- Parse DIFOP packet in case of jumbo pcap file
|
||||
- Update demo_online example to use ponit cloud queue
|
||||
- Update help documents
|
||||
|
||||
### Fixed
|
||||
- Fix lidar temperature
|
||||
|
||||
|
||||
|
||||
## v1.5.3 2022-06-01
|
||||
|
||||
### Added
|
||||
- Add option to receive packet with epoll()
|
||||
- Support Jumbo Mode
|
||||
|
||||
### Fixed
|
||||
- Check overflow of point cloud
|
||||
- Fix compiling error of multiple definition
|
||||
|
||||
|
||||
|
||||
## v1.5.2 2022-05-20
|
||||
|
||||
### Added
|
||||
- Support RSP128/RSP80/RSP48 lidars
|
||||
- Support EOS lidar
|
||||
- Add option to usleep() when no packets to be handled
|
||||
|
||||
### Changed
|
||||
- Limit error information when error happens
|
||||
- Use raw buffer for packet callback
|
||||
- Split frame by seq 1 (for MEMS lidars)
|
||||
- Remove difop handle thread
|
||||
|
||||
|
||||
|
||||
## v1.5.1 - 2022-04-28
|
||||
|
||||
### Changed
|
||||
- When replay MSOP/DIFOP file, use the timestamp when it is recording.
|
||||
For Mechanical LiDARs,
|
||||
- Split frame by block instead of by packet
|
||||
- Let every point has its own timestamp, instead of using the block's one.
|
||||
-
|
||||
|
||||
|
||||
|
||||
## v1.5.0 - 2022-04-21
|
||||
|
||||
-- Refactory the coder part
|
||||
|
||||
|
||||
|
||||
## v1.4.6 - 2022-04-21
|
||||
|
||||
### Added
|
||||
- Check msop timeout
|
||||
- Support M2
|
||||
- add cmake option ENABLE_RECVMMSG
|
||||
|
||||
### Changed
|
||||
- Optimize point cloud transform
|
||||
|
||||
|
||||
|
||||
## v1.4.5 - 2022-03-09
|
||||
|
||||
### Added
|
||||
- Support dense attribute
|
||||
- Support to bind to a specifed ip
|
||||
- Limit max size of packet queue
|
||||
- Apply SO_REUSEADDR option to the receiving socket
|
||||
- Support user layer and tail layer
|
||||
- add macro option to disable the PCAP function.
|
||||
|
||||
### Changed
|
||||
- Join multicast group with code instead of shell script
|
||||
|
||||
### Fixed
|
||||
- Fix memory leaks problem
|
||||
- Fix temperature calculation (for M1 only)
|
||||
|
||||
|
||||
|
||||
## v1.4.0 - 2021-11-01
|
||||
|
||||
### Changed
|
||||
Optimazation to decrease CPU uage, includes:
|
||||
- Replace point with point cloud as template parameter
|
||||
- Instead of alloc/free packet, use packet pool
|
||||
- Instead of alloc/free point cloud, always keep point cloud memory
|
||||
- By default, use conditional macro to disable scan_msg/camera_trigger related code
|
||||
|
||||
|
||||
|
||||
## V1.3.1
|
||||
|
||||
### Added
|
||||
- Add vlan support
|
||||
- Add somip support
|
||||
- Add split frame when pkt_cnt < last_pkt_cnt in mems
|
||||
- Add temperature in mems
|
||||
- Add ROCK support
|
||||
|
||||
### Fixed
|
||||
- Fix don't get time when PointType doesn't have timestamp member
|
||||
- Fix ROCK light center compensation algorithm
|
||||
|
||||
### Removed
|
||||
- Remove redundance condition code in vec.emplace_back(std::move(point)) in mech lidars
|
||||
|
||||
|
||||
|
||||
## v1.3.0 - 2020-11-10
|
||||
|
||||
### Added
|
||||
|
||||
- Add RSHELIOS support
|
||||
- Add RSM1 (B3) support
|
||||
- Add Windows support
|
||||
- Add rs_driver_viewer, a small tool to show point cloud
|
||||
- Add save_by_rows argument
|
||||
- Add multi-cast support
|
||||
- Add points transformation function
|
||||
|
||||
### Changed
|
||||
|
||||
- Update some decoding part for LiDARs
|
||||
- Change the definition of packet message
|
||||
- Update documents
|
||||
|
||||
|
||||
|
||||
## v1.2.1 - 2020-09-04
|
||||
|
||||
### Fixed
|
||||
|
||||
- Fix the timestamp calculation for RS16,RS32 & RSBP. Now the output lidar timestamp will be UTC time and will not be affected by system time zone.
|
||||
|
||||
|
||||
|
||||
## v1.2.0 - 2020-09-01
|
||||
|
||||
### Added
|
||||
|
||||
- Add interface in driver core to get lidar temperature
|
||||
- Add support for point type XYZIRT (R - ring id)(T - timestamp)
|
||||
- Add RS80 support
|
||||
- Add interface in driver core to get camera trigger info
|
||||
|
||||
### Changed
|
||||
|
||||
- Update the decoding part for ruby in echo-dual mode
|
||||
- Update the compiler version from C++11 to C++14
|
||||
|
||||
|
||||
|
||||
## v1.1.0 - 2020-07-01
|
||||
|
||||
### Added
|
||||
|
||||
- Add the limit of the length of the msop queue
|
||||
- Add the exception capture when loading .csv file
|
||||
|
||||
### Fixed
|
||||
- Fix the bug in calculating the timestamp of 128
|
||||
- Fix the bug in calculating RPM
|
||||
|
||||
### Changed
|
||||
- Update some functions' names
|
||||
- Update the program structure
|
||||
|
||||
### Removed
|
||||
- Remove unused variables in point cloud message
|
||||
|
||||
|
||||
|
||||
## v1.0.0 - 2020-06-01
|
||||
|
||||
### Added
|
||||
|
||||
- New program structure
|
||||
|
||||
- Easy to do advanced development
|
||||
|
||||
- Remove the redundant code in old driver.
|
||||
|
||||
|
||||
246
src/airy/rslidar_sdk-main/src/rs_driver/CMakeLists.txt
Normal file
@ -0,0 +1,246 @@
|
||||
cmake_minimum_required(VERSION 3.5)
|
||||
|
||||
cmake_policy(SET CMP0048 NEW) # CMake 3.6 required
|
||||
|
||||
if(WIN32)
|
||||
cmake_policy(SET CMP0074 NEW) # CMake 3.12 required
|
||||
endif(WIN32)
|
||||
|
||||
project(rs_driver VERSION 1.5.17)
|
||||
|
||||
#========================
|
||||
# Project setup
|
||||
#========================
|
||||
if (CMAKE_BUILD_TYPE STREQUAL "")
|
||||
set(CMAKE_BUILD_TYPE Release)
|
||||
endif()
|
||||
|
||||
#=============================
|
||||
# Compile Features
|
||||
#=============================
|
||||
option(DISABLE_PCAP_PARSE "Disable PCAP file parse" OFF)
|
||||
option(ENABLE_TRANSFORM "Enable transform functions" OFF)
|
||||
|
||||
option(ENABLE_MODIFY_RECVBUF "Enable modify size of RCVBUF" OFF)
|
||||
option(ENABLE_WAIT_IF_QUEUE_EMPTY "Enable waiting for a while in handle thread if the queue is empty" OFF)
|
||||
option(ENABLE_EPOLL_RECEIVE "Receive packets with epoll() instead of select()" OFF)
|
||||
|
||||
option(ENABLE_STAMP_WITH_LOCAL "Enable stamp point cloud with local time" OFF)
|
||||
option(ENABLE_PCL_POINTCLOUD "Enable PCL Point Cloud" OFF)
|
||||
option(ENABLE_CRC32_CHECK "Enable CRC32 Check on MSOP Packet" OFF)
|
||||
option(ENABLE_DIFOP_PARSE "Enable parsing DIFOP Packet" OFF)
|
||||
|
||||
#=============================
|
||||
# Compile Demos, Tools, Tests
|
||||
#=============================
|
||||
option(COMPILE_DEMOS "Build rs_driver demos" OFF)
|
||||
option(COMPILE_TOOLS "Build rs_driver tools" OFF)
|
||||
option(COMPILE_TOOL_VIEWER "Build point cloud visualization tool" OFF)
|
||||
option(COMPILE_TOOL_PCDSAVER "Build point cloud pcd saver tool" OFF)
|
||||
option(COMPILE_TESTS "Build rs_driver unit tests" OFF)
|
||||
|
||||
#========================
|
||||
# Platform cross setup
|
||||
#========================
|
||||
if(MSVC)
|
||||
|
||||
set(COMPILER "MSVC Compiler")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /Wall")
|
||||
set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} /Od /Zi")
|
||||
set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} /O2")
|
||||
set(CompilerFlags
|
||||
CMAKE_CXX_FLAGS CMAKE_C_FLAGS
|
||||
CMAKE_CXX_FLAGS_DEBUG CMAKE_C_FLAGS_DEBUG
|
||||
CMAKE_CXX_FLAGS_RELEASE CMAKE_C_FLAGS_RELEASE
|
||||
CMAKE_CXX_FLAGS_MINSIZEREL CMAKE_C_FLAGS_MINSIZEREL
|
||||
CMAKE_CXX_FLAGS_RELWITHDEBINFO CMAKE_C_FLAGS_RELWITHDEBINFO)
|
||||
|
||||
foreach(CompilerFlag ${CompilerFlags})
|
||||
string(REPLACE "/MT" "/MD" ${CompilerFlag} "${${CompilerFlag}}")
|
||||
endforeach()
|
||||
|
||||
add_compile_definitions(_DISABLE_EXTENDED_ALIGNED_STORAGE) # to disable a msvc error
|
||||
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} /STACK:100000000")
|
||||
|
||||
elseif(CMAKE_CXX_COMPILER_ID STREQUAL "GNU")
|
||||
|
||||
if(UNIX)
|
||||
set(COMPILER "UNIX GNU Compiler")
|
||||
elseif(MINGW)
|
||||
set(COMPILER "MINGW Compiler")
|
||||
else()
|
||||
message(FATAL_ERROR "Unsupported compiler.")
|
||||
endif()
|
||||
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -Wall -Wno-unused-parameter")
|
||||
set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} -g")
|
||||
set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -O3")
|
||||
endif()
|
||||
|
||||
message(=============================================================)
|
||||
message("-- CMake run for ${COMPILER}")
|
||||
message(=============================================================)
|
||||
|
||||
#========================
|
||||
# Path Setup
|
||||
#========================
|
||||
set(CMAKE_INSTALL_PREFIX /usr/local)
|
||||
set(INSTALL_DRIVER_DIR ${CMAKE_INSTALL_PREFIX}/${CMAKE_PROJECT_NAME}/include)
|
||||
set(INSTALL_CMAKE_DIR ${CMAKE_INSTALL_PREFIX}/lib/cmake)
|
||||
set(DRIVER_INCLUDE_DIRS ${CMAKE_CURRENT_LIST_DIR}/src)
|
||||
set(DRIVER_CMAKE_ROOT ${CMAKE_CURRENT_LIST_DIR}/cmake)
|
||||
|
||||
if(WIN32)
|
||||
list(APPEND EXTERNAL_LIBS ws2_32)
|
||||
else()
|
||||
if (CMAKE_SYSTEM_NAME STREQUAL "QNX")
|
||||
list(APPEND EXTERNAL_LIBS socket)
|
||||
else()
|
||||
list(APPEND EXTERNAL_LIBS pthread)
|
||||
endif()
|
||||
endif(WIN32)
|
||||
|
||||
#========================
|
||||
# Build Features
|
||||
#========================
|
||||
|
||||
if(${ENABLE_EPOLL_RECEIVE})
|
||||
|
||||
message(=============================================================)
|
||||
message("-- Enable Epoll Receive")
|
||||
message(=============================================================)
|
||||
|
||||
add_definitions("-DENABLE_EPOLL_RECEIVE")
|
||||
endif(${ENABLE_EPOLL_RECEIVE})
|
||||
|
||||
if(${DISABLE_PCAP_PARSE})
|
||||
|
||||
message(=============================================================)
|
||||
message("-- Disable PCAP parse")
|
||||
message(=============================================================)
|
||||
|
||||
add_definitions("-DDISABLE_PCAP_PARSE")
|
||||
|
||||
else()
|
||||
|
||||
if(WIN32)
|
||||
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}/cmake)
|
||||
find_package(PCAP REQUIRED)
|
||||
include_directories(${PCAP_INCLUDE_DIR})
|
||||
list(APPEND EXTERNAL_LIBS ${PCAP_LIBRARY})
|
||||
else()
|
||||
list(APPEND EXTERNAL_LIBS pcap)
|
||||
endif(WIN32)
|
||||
|
||||
endif(${DISABLE_PCAP_PARSE})
|
||||
|
||||
if(${ENABLE_TRANSFORM})
|
||||
|
||||
message(=============================================================)
|
||||
message("-- Enable Transform Fucntions")
|
||||
message(=============================================================)
|
||||
|
||||
add_definitions("-DENABLE_TRANSFORM")
|
||||
|
||||
# Eigen
|
||||
find_package(Eigen3 REQUIRED)
|
||||
include_directories(${EIGEN3_INCLUDE_DIR})
|
||||
|
||||
endif(${ENABLE_TRANSFORM})
|
||||
|
||||
|
||||
|
||||
#============================
|
||||
# Build Demos, Tools, Tests
|
||||
#============================
|
||||
|
||||
if(${ENABLE_MODIFY_RECVBUF})
|
||||
add_definitions("-DENABLE_MODIFY_RECVBUF")
|
||||
endif(${ENABLE_MODIFY_RECVBUF})
|
||||
|
||||
if(${ENABLE_WAIT_IF_QUEUE_EMPTY})
|
||||
add_definitions("-DENABLE_WAIT_IF_QUEUE_EMPTY")
|
||||
endif(${ENABLE_WAIT_IF_QUEUE_EMPTY})
|
||||
|
||||
if(${ENABLE_STAMP_WITH_LOCAL})
|
||||
add_definitions("-DENABLE_STAMP_WITH_LOCAL")
|
||||
endif(${ENABLE_STAMP_WITH_LOCAL})
|
||||
|
||||
if(${ENABLE_PCL_POINTCLOUD})
|
||||
add_definitions("-DENABLE_PCL_POINTCLOUD")
|
||||
endif(${ENABLE_PCL_POINTCLOUD})
|
||||
|
||||
if(${ENABLE_CRC32_CHECK})
|
||||
add_definitions("-DENABLE_CRC32_CHECK")
|
||||
endif(${ENABLE_CRC32_CHECK})
|
||||
|
||||
if(${ENABLE_DIFOP_PARSE})
|
||||
add_definitions("-DENABLE_DIFOP_PARSE")
|
||||
endif(${ENABLE_DIFOP_PARSE})
|
||||
|
||||
if(${COMPILE_DEMOS})
|
||||
add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/demo)
|
||||
endif(${COMPILE_DEMOS})
|
||||
|
||||
if (${COMPILE_TOOLS})
|
||||
set(COMPILE_TOOL_VIEWER ON)
|
||||
set(COMPILE_TOOL_PCDSAVER ON)
|
||||
endif (${COMPILE_TOOLS})
|
||||
|
||||
if(${COMPILE_TOOL_VIEWER} OR ${COMPILE_TOOL_PCDSAVER})
|
||||
add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/tool)
|
||||
endif(${COMPILE_TOOL_VIEWER} OR ${COMPILE_TOOL_PCDSAVER})
|
||||
|
||||
if(${COMPILE_TESTS})
|
||||
add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/test)
|
||||
endif(${COMPILE_TESTS})
|
||||
|
||||
#========================
|
||||
# Cmake
|
||||
#========================
|
||||
configure_file(
|
||||
${DRIVER_CMAKE_ROOT}/rs_driverConfig.cmake.in
|
||||
${DRIVER_CMAKE_ROOT}/rs_driverConfig.cmake
|
||||
@ONLY)
|
||||
|
||||
configure_file(
|
||||
${DRIVER_CMAKE_ROOT}/rs_driverConfigVersion.cmake.in
|
||||
${DRIVER_CMAKE_ROOT}/rs_driverConfigVersion.cmake
|
||||
@ONLY)
|
||||
|
||||
configure_file (
|
||||
${CMAKE_CURRENT_LIST_DIR}/src/rs_driver/macro/version.hpp.in
|
||||
${CMAKE_CURRENT_LIST_DIR}/src/rs_driver/macro/version.hpp
|
||||
@ONLY)
|
||||
|
||||
if(NOT ${CMAKE_SOURCE_DIR} STREQUAL ${CMAKE_CURRENT_SOURCE_DIR})
|
||||
set(rs_driver_DIR ${DRIVER_CMAKE_ROOT} PARENT_SCOPE)
|
||||
endif()
|
||||
|
||||
#========================
|
||||
# Install & Uninstall
|
||||
#========================
|
||||
if(UNIX AND ${CMAKE_SOURCE_DIR} STREQUAL ${CMAKE_CURRENT_SOURCE_DIR})
|
||||
|
||||
install(FILES ${DRIVER_CMAKE_ROOT}/rs_driverConfig.cmake
|
||||
${DRIVER_CMAKE_ROOT}/rs_driverConfigVersion.cmake
|
||||
DESTINATION ${INSTALL_CMAKE_DIR}/${CMAKE_PROJECT_NAME})
|
||||
|
||||
install(DIRECTORY src/
|
||||
DESTINATION ${INSTALL_DRIVER_DIR}
|
||||
FILES_MATCHING PATTERN "*.h")
|
||||
|
||||
install(DIRECTORY src/
|
||||
DESTINATION ${INSTALL_DRIVER_DIR}
|
||||
FILES_MATCHING PATTERN "*.hpp")
|
||||
|
||||
if(NOT TARGET uninstall)
|
||||
configure_file(
|
||||
${CMAKE_CURRENT_LIST_DIR}/cmake/cmake_uninstall.cmake.in
|
||||
${PROJECT_BINARY_DIR}/cmake_uninstall.cmake @ONLY)
|
||||
add_custom_target(uninstall
|
||||
COMMAND ${CMAKE_COMMAND} -P ${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake)
|
||||
endif(NOT TARGET uninstall)
|
||||
|
||||
endif(UNIX AND ${CMAKE_SOURCE_DIR} STREQUAL ${CMAKE_CURRENT_SOURCE_DIR})
|
||||
|
||||
19
src/airy/rslidar_sdk-main/src/rs_driver/LICENSE
Normal file
@ -0,0 +1,19 @@
|
||||
Copyright (c) 2020 RoboSense
|
||||
All rights reserved
|
||||
|
||||
By downloading, copying, installing or using the software you agree to this license. If you do not agree to this license, do not download, install, copy or use the software.
|
||||
|
||||
License Agreement
|
||||
For RoboSense LiDAR SDK Library
|
||||
(3-clause BSD License)
|
||||
|
||||
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
|
||||
|
||||
1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
|
||||
|
||||
2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
|
||||
|
||||
3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used to endorse or promote products derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
|
||||
260
src/airy/rslidar_sdk-main/src/rs_driver/README.md
Normal file
@ -0,0 +1,260 @@
|
||||
# 1 **rs_driver**
|
||||
|
||||
[中文介绍](README_CN.md)
|
||||
|
||||
|
||||
|
||||
## 1.1 Introduction
|
||||
|
||||
**rs_driver** is the driver kernel for the RoboSense LiDARs.
|
||||
|
||||
Please download the official release from [github](https://github.com/RoboSense-LiDAR/rs_driver/releases), or get the latest version with the git client tool.
|
||||
|
||||
````shell
|
||||
git clone https://github.com/RoboSense-LiDAR/rs_driver.git
|
||||
````
|
||||
|
||||
|
||||
|
||||
## 1.2 Supported LiDARs
|
||||
|
||||
Below are the supported LiDARS.
|
||||
|
||||
- RS-LiDAR-16
|
||||
- RS-LiDAR-32
|
||||
- RS-Bpearl
|
||||
- RS-Helios
|
||||
- RS-Helios-16P
|
||||
- RS-Ruby-128
|
||||
- RS-Ruby-80
|
||||
- RS-Ruby-48
|
||||
- RS-Ruby-Plus-128
|
||||
- RS-Ruby-Plus-80
|
||||
- RS-Ruby-Plus-48
|
||||
- RS-LiDAR-M1
|
||||
- RS-LiDAR-M2
|
||||
- RS-LiDAR-M3
|
||||
- RS-LiDAR-E1
|
||||
- RS-LiDAR-MX
|
||||
- RS-LiDAR-AIRY
|
||||
|
||||
|
||||
## 1.3 Supported Platforms
|
||||
|
||||
**rs_driver** is supported on the following platforms and compilers. Note the compiler should support `C++14`.
|
||||
|
||||
- Ubuntu (16.04, 18.04)
|
||||
- gcc (4.8+)
|
||||
|
||||
- Windows
|
||||
- MSVC ( tested with Win10 / VS2019)
|
||||
|
||||
|
||||
|
||||
## 1.4 Dependency Libraries
|
||||
|
||||
**rs_driver** depends on the following third-party libraries.
|
||||
|
||||
- libpcap (optional, needed to parse PCAP file)
|
||||
- Eigen3 (optional, needed to use the internal transformation function)
|
||||
- PCL (optional, needed to build the visualization tool)
|
||||
- Boost (optional, needed to build the visualization tool)
|
||||
|
||||
|
||||
|
||||
## 1.5 Compile On Ubuntu
|
||||
|
||||
### 1.5.1 Dependency Libraries
|
||||
|
||||
```sh
|
||||
sudo apt-get install libpcap-dev libeigen3-dev libboost-dev libpcl-dev
|
||||
```
|
||||
|
||||
### 1.5.2 Compilation
|
||||
|
||||
```bash
|
||||
cd rs_driver
|
||||
mkdir build && cd build
|
||||
cmake .. && make -j4
|
||||
```
|
||||
|
||||
### 1.5.3 Installation
|
||||
|
||||
```bash
|
||||
sudo make install
|
||||
```
|
||||
|
||||
### 1.5.4 Use `rs_driver` as a third party library
|
||||
|
||||
In your ```CMakeLists.txt```, find the **rs_driver** package and link to it .
|
||||
|
||||
```cmake
|
||||
find_package(rs_driver REQUIRED)
|
||||
include_directories(${rs_driver_INCLUDE_DIRS})
|
||||
target_link_libraries(your_project ${rs_driver_LIBRARIES})
|
||||
```
|
||||
|
||||
### 1.5.5 Use `rs_driver` as a submodule
|
||||
|
||||
Add **rs_driver** into your project as a submodule.
|
||||
|
||||
In your ```CMakeLists.txt```, find the **rs_driver** package and link to it .
|
||||
|
||||
```cmake
|
||||
add_subdirectory(${PROJECT_SOURCE_DIR}/rs_driver)
|
||||
find_package(rs_driver REQUIRED)
|
||||
include_directories(${rs_driver_INCLUDE_DIRS})
|
||||
target_link_libraries(your_project ${rs_driver_LIBRARIES})
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 1.6 Compile On Windows
|
||||
|
||||
### 1.6.1 Dependency Libraries
|
||||
|
||||
#### 1.6.1.1 libpcap
|
||||
|
||||
Install [libpcap runtime library](https://www.winpcap.org/install/bin/WinPcap_4_1_3.exe).
|
||||
|
||||
Unzip [libpcap's developer's pack](https://www.winpcap.org/install/bin/WpdPack_4_1_2.zip) to your favorite location, and add the path to the folder ```WpdPack_4_1_2/WpdPack``` to the environment variable ```PATH``` .
|
||||
|
||||
#### 1.6.1.2 PCL
|
||||
|
||||
To compile with VS2019, please use the official installation package [PCL All-in-one installer](https://github.com/PointCloudLibrary/pcl/releases).
|
||||
|
||||
Select the "Add PCL to the system PATH for xxx" option during the installation.
|
||||

|
||||
|
||||
### 1.6.2 Installation
|
||||
|
||||
Installation is not supported on Windows.
|
||||
|
||||
|
||||
|
||||
## 1.7 Quick Start
|
||||
|
||||
**rs_driver** offers two demo programs in ```rs_driver/demo```.
|
||||
|
||||
- demo_online.cpp
|
||||
|
||||
`demo_online` connects to online lidar, and output point cloud.
|
||||
|
||||
- demo_pcap.cpp
|
||||
|
||||
`demo_pcap` parses pcap file, and output point cloud. It is based on libpcap.
|
||||
|
||||
|
||||
|
||||
To build `demo_online` and `demo_pcap`, enable the CMake option `COMPILE_DEMOS`.
|
||||
|
||||
```bash
|
||||
cmake -DCOMPILE_DEMOS=ON ..
|
||||
```
|
||||
|
||||
For more info about `demo_online`, Please refer to [Decode online LiDAR](doc/howto/07_how_to_decode_online_lidar.md)
|
||||
|
||||
For more info about `demo_pcap`, Please refer to [Decode pcap file](doc/howto/09_how_to_decode_pcap_file.md)
|
||||
|
||||
|
||||
|
||||
## 1.8 Visualization of Point Cloud
|
||||
|
||||
**rs_driver** offers a visualization tool `rs_driver_viwer` in ```rs_driver/tool``` , which is based on PCL.
|
||||
|
||||
To build it, enable the CMake option CMOPILE_TOOLS.
|
||||
|
||||
```bash
|
||||
cmake -DCOMPILE_TOOLS=ON ..
|
||||
```
|
||||
|
||||
For more info about `rs_driver_viewer`, please refer to [Visualization tool guide](doc/howto/13_how_to_use_rs_driver_viewer.md)
|
||||
|
||||
|
||||
|
||||
## 1.9 API files
|
||||
|
||||
For more info about the `rs_driver` API, Please refer to:
|
||||
- **Point Cloud message definition**: ```rs_driver/src/rs_driver/msg/point_cloud_msg.hpp```, ```rs_driver/src/rs_driver/msg/pcl_point_cloud_msg.hpp```
|
||||
- **API definition**: ```rs_driver/src/rs_driver/api/lidar_driver.hpp```
|
||||
- **Parameters definition**: ```rs_driver/src/rs_driver/driver/driver_param.hpp```,
|
||||
- **Error code definition**: ```rs_driver/src/rs_driver/common/error_code.hpp```
|
||||
|
||||
|
||||
|
||||
## 1.10 More Topics
|
||||
|
||||
For more topics, Please refer to:
|
||||
|
||||
+ What is available in the **rs_driver** project? Include examples, tools, documents.
|
||||
|
||||
Please see [Directories and Files](doc/intro/02_directories_and_files.md)
|
||||
|
||||
+ There are two versions of **rs_driver**: `v1.3.x` and `v1.5.x`. Which is suggested? Is it suggested to upgrade to `v1.5.x` ? How to upgrade?
|
||||
|
||||
Please see [How to port from v1.3.x to v1.5.x](doc/howto/07_how_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md)
|
||||
|
||||
+ How to compile **rs_driver** on Windows ?
|
||||
|
||||
Please see [How to compile `rs_driver` on Windows](./doc/howto/16_how_to_compile_on_windows.md)
|
||||
|
||||
+ What is the interface of **rs_driver** like ? How to integrate it into my system?
|
||||
|
||||
Please see [Thread Model and Interface](./doc/intro/03_thread_model.md)
|
||||
|
||||
+ Is there any examples about how to integrate **rs_driver** ? And if mulitple LiDARs?
|
||||
|
||||
Please see [How to connect to online LiDAR](doc/howto/08_how_to_decode_online_lidar.md),[How to decode PCAP file](doc/howto/10_how_to_decode_pcap_file.md)。
|
||||
|
||||
+ How to configure **rs_driver**'s network options in unicast/multicast/broadcast mode? And if mulitple Lidars? With VLAN layer? May I add extra layers before/after MSOP/DIFOP packet? All configurations are OK, and Wireshark/tcpdump can capture the packets, but **rs_driver** still fails to get them. Why ?
|
||||
|
||||
Please see [Online LiDAR - Advanced Topics](doc/howto/09_online_lidar_advanced_topics.md)
|
||||
|
||||
+ To decode a PCAP file with only one LiDAR data, how to configure `rs_driver`? And if multiple LiDARs? With VLAN layer? With extra layers before/after MSOP/DIFOP packet?
|
||||
|
||||
Please see [PCAP File - Advanced Topics](doc/howto/11_pcap_file_advanced_topics.md)
|
||||
|
||||
+ Can I determine how to configure `rs_driver` by a PCAP file? For both online LiDAR and PCAP file?
|
||||
|
||||
Please see [How to configure rs_driver by PCAP file](doc/howto/12_how_to_configure_by_pcap_file.md)
|
||||
|
||||
+ What format of PCAP file is supported by `rs_driver`? How to capture such a file?
|
||||
|
||||
Please see [How to capture a PCAP file for rs_driver](doc/howto/13_how_to_capture_pcap_file.md)
|
||||
|
||||
+ How to compile demo apps/tools? How to avoid packet loss? How much is CPU usage? Point cloud is UTC time. How to convert it to loca time? How to disable PCAP file decoding on embedded Linux? How to enable point transformation?
|
||||
|
||||
Please see [rs_driver CMake Macros](./doc/intro/05_cmake_macros_intro.md)
|
||||
|
||||
+ How to specify Lidar type? How to specify data source (online LiDAR, PCAP file, user's data) ? How to timestamp point cloud with LiDAR clock or Host clock? How to discard NAN points in point cloud? Where does point cloud get its timestamp? from its first point, or last point? How to configure point transform? How to change the splitting angle of mechanical LiDAR?
|
||||
|
||||
Please see [rs_driver configuration parameters](./doc/intro/04_parameter_intro.md)
|
||||
|
||||
+ **rs_driver** reports an error `ERRCODE_MSOPTIMEOUT`/`ERRCODE_WRONGMSOPID`/`ERRCODE_PKTBUFOVERFLOW` ...... What does it mean?
|
||||
|
||||
Please see [rs_driver Error Code](./doc/intro/06_error_code_intro.md)
|
||||
|
||||
+ How to transform point cloud to another position?
|
||||
|
||||
Please see [How to transform point cloud](doc/howto/15_how_to_transform_pointcloud.md)
|
||||
|
||||
+ How much is data flow of RoboSense LiDARs ? When may it loss packets? How to avoid this?
|
||||
|
||||
Please see [How to avoid packet Loss](doc/howto/17_how_to_avoid_packet_loss.md)
|
||||
|
||||
+ How much CPU and memory does **rs_driver** need?
|
||||
|
||||
Please see [CPU Usage and Memory Usage of `rs_driver`](doc/howto/20_about_usage_of_cpu_and_memory.md)
|
||||
|
||||
+ What is point layout like? What's the coordinate system of **rs_driver**? What is `ring` of point? Where is point timestamp from?
|
||||
|
||||
Please see [Point Layout in point cloud](doc/howto/18_about_point_layout.md)
|
||||
|
||||
+ How does RoboSense split frames? It uses the UDP protocol. What if packet loss or out of order?
|
||||
|
||||
Please see [Splitting frames](doc/howto/19_about_splitting_frame.md)
|
||||
|
||||
+ Want to know more implementation details about `rs_driver`?
|
||||
|
||||
Please see [Analysis of rs_driver's source code](doc/src_intro/rs_driver_intro_CN.md)
|
||||
|
||||
268
src/airy/rslidar_sdk-main/src/rs_driver/README_CN.md
Normal file
@ -0,0 +1,268 @@
|
||||
# 1 **rs_driver预览**
|
||||
|
||||
[English Version](README.md)
|
||||
|
||||
|
||||
|
||||
## 1.1 概述
|
||||
|
||||
**rs_driver**是RoboSense雷达的驱动库。
|
||||
|
||||
可以从[github](https://github.com/RoboSense-LiDAR/rs_driver/releases)下载正式版本。也可以使用git工具得到最新版本。
|
||||
|
||||
```
|
||||
git clone https://github.com/RoboSense-LiDAR/rs_driver.git
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 1.2 支持的雷达型号
|
||||
|
||||
**rs_driver**支持的雷达型号如下。
|
||||
|
||||
+ RS-LiDAR-16
|
||||
+ RS-LiDAR-32
|
||||
+ RS-Bpearl
|
||||
+ RS-Helios
|
||||
+ RS-Helios-16P
|
||||
+ RS-Ruby-128
|
||||
+ RS-Ruby-80
|
||||
+ RS-Ruby-48
|
||||
+ RS-Ruby-Plus-128
|
||||
+ RS-Ruby-Plus-80
|
||||
+ RS-Ruby-Plus-48
|
||||
+ RS-LiDAR-M1
|
||||
+ RS-LiDAR-M2
|
||||
+ RS-LiDAR-M3
|
||||
+ RS-LiDAR-E1
|
||||
+ RS-LiDAR-MX
|
||||
+ RS-LiDAR-AIRY
|
||||
|
||||
|
||||
|
||||
## 1.3 支持的操作系统
|
||||
|
||||
**rs_driver**支持的操作系统及编译器如下。注意编译器需支持`C++14`标准。
|
||||
|
||||
- Ubuntu (16.04, 18.04, 20.04)
|
||||
- gcc (4.8+)
|
||||
|
||||
- Windows
|
||||
- MSVC (Win10 / VS2019 已测试)
|
||||
|
||||
|
||||
|
||||
## 1.4 依赖的第三方库
|
||||
|
||||
**rs_driver**依赖的第三方库如下。
|
||||
|
||||
- `libpcap` (可选。如不需要解析PCAP文件,可忽略)
|
||||
- `eigen3` (可选。如不需要内置坐标变换,可忽略)
|
||||
- `PCL` (可选。如不需要可视化工具,可忽略)
|
||||
- `Boost` (可选。如不需要可视化工具,可忽略)
|
||||
|
||||
|
||||
|
||||
## 1.5 Ubuntu下的编译及安装
|
||||
|
||||
### 1.5.1 安装第三方库
|
||||
|
||||
```bash
|
||||
sudo apt-get install libpcap-dev libeigen3-dev libboost-dev libpcl-dev
|
||||
```
|
||||
### 1.5.2 编译
|
||||
|
||||
```bash
|
||||
cd rs_driver
|
||||
mkdir build && cd build
|
||||
cmake .. && make -j4
|
||||
```
|
||||
|
||||
### 1.5.3 安装
|
||||
|
||||
```bash
|
||||
sudo make install
|
||||
```
|
||||
|
||||
### 1.5.4 作为第三方库使用
|
||||
|
||||
配置您的```CMakeLists.txt```文件,使用find_package()指令找到**rs_driver**库,并链接。
|
||||
|
||||
```cmake
|
||||
find_package(rs_driver REQUIRED)
|
||||
include_directories(${rs_driver_INCLUDE_DIRS})
|
||||
target_link_libraries(your_project ${rs_driver_LIBRARIES})
|
||||
```
|
||||
|
||||
### 1.5.5 作为子模块使用
|
||||
|
||||
将**rs_driver**作为子模块添加到您的工程,相应配置您的```CMakeLists.txt```文件。
|
||||
|
||||
使用find_package()指令找到**rs_driver**库,并链接。
|
||||
|
||||
```cmake
|
||||
add_subdirectory(${PROJECT_SOURCE_DIR}/rs_driver)
|
||||
find_package(rs_driver REQUIRED)
|
||||
include_directories(${rs_driver_INCLUDE_DIRS})
|
||||
target_link_libraries(project ${rs_driver_LIBRARIES})
|
||||
```
|
||||
|
||||
|
||||
|
||||
## 1.6 Windows下的编译及安装
|
||||
|
||||
### 1.6.1 安装第三方库
|
||||
|
||||
#### 1.6.1.1 libpcap
|
||||
|
||||
安装[libpcap运行库](https://www.winpcap.org/install/bin/WinPcap_4_1_3.exe)。
|
||||
|
||||
解压[libpcap开发者包](https://www.winpcap.org/install/bin/WpdPack_4_1_2.zip)到任意位置,并将```WpdPack_4_1_2/WpdPack``` 的路径添加到环境变量```PATH```。
|
||||
|
||||
#### 1.6.1.2 PCL
|
||||
|
||||
如果使用MSVC编译器,可使用PCL官方提供的[PCL安装包](https://github.com/PointCloudLibrary/pcl/releases)安装。
|
||||
|
||||
安装过程中选择 `Add PCL to the system PATH for xxx`。
|
||||

|
||||
|
||||
### 1.6.2 安装
|
||||
|
||||
Windows下,**rs_driver** 暂不支持安装。
|
||||
|
||||
### 1.6.3 VS工程文件
|
||||
|
||||
工程目录`rs_driver/win`下,有编译实例程序和工具的MSVS工程文件。
|
||||
|
||||
关于Windows下编译和使用**rs_driver**的更多说明,可以参考[如何在Windows下编译rs_driver](doc/howto/16_how_to_compile_on_windows_CN.md)
|
||||
|
||||
|
||||
|
||||
## 1.7 示例程序
|
||||
|
||||
**rs_driver**在目录```rs_driver/demo``` 下,提供了两个示例程序。
|
||||
|
||||
- `demo_online.cpp`
|
||||
|
||||
`demo_online`解析在线雷达的数据,输出点云。
|
||||
|
||||
|
||||
- `demo_pcap.cpp`
|
||||
|
||||
`demo_pcap`解析PCAP文件,输出点云。编译`demo_pcap`需要安装`libpcap`库。
|
||||
|
||||
|
||||
|
||||
要编译这两个程序,需使能`COMPILE_DEMOS`选项。
|
||||
|
||||
```bash
|
||||
cmake -DCOMPILE_DEMOS=ON ..
|
||||
```
|
||||
|
||||
关于`demo_online`的更多说明,可以参考[如何连接在线雷达](doc/howto/08_how_to_decode_online_lidar_CN.md)
|
||||
|
||||
关于`demo_pcap`的更多说明,可以参考[如何解码PCAP文件](doc/howto/10_how_to_decode_pcap_file_CN.md)
|
||||
|
||||
|
||||
|
||||
## 1.8 点云可视化工具
|
||||
|
||||
**rs_driver**在目录```rs_driver/tool``` 下,提供了一个点云可视化工具`rs_driver_viewer`。
|
||||
|
||||
要编译这个工具,需使能`COMPILE_TOOS`选项。编译它需要安装PCL库和Boost库。
|
||||
|
||||
```bash
|
||||
cmake -DCOMPILE_TOOLS=ON ..
|
||||
```
|
||||
|
||||
关于`rs_driver_viewer`的使用方法,请参考[如何使用可视化工具rs_driver_viewer](doc/howto/14_how_to_use_rs_driver_viewer_CN.md)
|
||||
|
||||
|
||||
|
||||
## 1.9 接口文件
|
||||
|
||||
**rs_driver**的主要接口文件如下。
|
||||
|
||||
- 点云消息定义: ```rs_driver/src/rs_driver/msg/point_cloud_msg.hpp```, ```rs_driver/src/rs_driver/msg/pcl_point_cloud_msg.hpp```
|
||||
- 接口定义: ```rs_driver/src/rs_driver/api/lidar_driver.hpp```
|
||||
- 参数定义: ```rs_driver/src/rs_driver/driver/driver_param.hpp```
|
||||
- 错误码定义: ```rs_driver/src/rs_driver/common/error_code.hpp```
|
||||
|
||||
|
||||
|
||||
## 1.10 更多主题
|
||||
|
||||
关于**rs_driver**的其他主题,请参考如下链接。
|
||||
|
||||
+ **rs_driver**工程中包括哪些例子、工具、和文档?
|
||||
|
||||
请参考[rs_driver的目录结构](doc/intro/02_directories_and_files_CN.md)
|
||||
|
||||
+ **rs_driver**有`v1.3.x`和`v1.5.x`两个版本?该选哪一个?现在正在使用`v1.3.x`,需要升级到`v1.5.x`吗?如何升级?
|
||||
|
||||
请参考[如何从v1.3.x升级到v1.5.x](doc/howto/07_how_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x_CN.md)
|
||||
|
||||
+ Windows上如何编译**rs_driver**?
|
||||
|
||||
请参考[如何在Windows上编译rs_driver](./doc/howto/16_how_to_compile_on_windows_CN.md)
|
||||
|
||||
+ **rs_driver**的接口如何设计的?如何将**rs_driver**集成到我的系统中,有什么注意事项吗?
|
||||
|
||||
请参考[rs_driver的线程模型与接口设计](./doc/intro/03_thread_model_CN.md)
|
||||
|
||||
+ **rs_driver**如何集成到我自己的系统中?有参考的例子吗?有多雷达的例子吗?
|
||||
|
||||
请参考[如何连接在线雷达](doc/howto/08_how_to_decode_online_lidar_CN.md),[如何解析PCAP文件](doc/howto/10_how_to_decode_pcap_file_CN.md)。
|
||||
|
||||
+ 在单播、组播、广播的情况下,应该如何配置**rs_driver**的网络选项?在多雷达的情况下如何配置?在VLAN的情况下如何配置?可以在MSOP/DIFOP数据的前后加入自己的层吗?这些网络配置都确认无误,用抓包软件也能抓到MSOP/DIFOP包,为什么还是接收不到点云?
|
||||
|
||||
请参考[在线雷达 - 高级主题](doc/howto/09_online_lidar_advanced_topics_CN.md)
|
||||
|
||||
+ 一般情况下,PCAP文件中只有一个雷达的数据,如何配置网络选项? 如果文件中有多个雷达的数据,如何配置? 在VLAN的情况下如何配置?可以在MSOP/DIFOP数据的前后加入自己的层吗?
|
||||
|
||||
请参考[PCAP文件 - 高级主题](doc/howto/11_pcap_file_advanced_topics_CN.md)
|
||||
|
||||
+ 手上只有一个PCAP文件,可以根据它确定**rs_driver**的网络配置选项吗?包括连接在线雷达和解析PCAP文件。
|
||||
|
||||
请参考[根据PCAP文件确定网络配置选项](doc/howto/12_how_to_configure_by_pcap_file_CN.md)
|
||||
|
||||
+ **rs_driver**支持什么格式的PCAP文件?如何录制这样的文件?
|
||||
|
||||
请参考[如何为rs_driver录制PCAP文件](doc/howto/13_how_to_capture_pcap_file_CN.md)
|
||||
|
||||
+ 想编译示例程序/小工具,怎么指定编译选项? **rs_driver**丢包了,如何解决?**rs_driver**的CPU占用率?点云的时间戳是UTC时间,能改成本地时间吗?嵌入式平台不需要解析PCAP文件,可以不编译这个特性吗?如何启用点云坐标转换功能?
|
||||
|
||||
请参考[rs_driver CMake编译宏](./doc/intro/05_cmake_macros_intro_CN.md)
|
||||
|
||||
+ **rs_driver**如何指定雷达类型?如何指定数据源为在线雷达、PCAP文件或用户数据? 想先试用一下,但是对雷达作PTP时间同步很麻烦,可以先用电脑的系统时间给点云打时间戳吗?想节省一点内存空间,可以丢弃点云中的无效点吗?点云的时间戳来自它的第一个点,还是最后一个点?可以配置吗?点云坐标转换的位移、旋转参数如何设置?机械式雷达的分帧角度可以设置吗?
|
||||
|
||||
请参考[rs_driver配置选项](./doc/intro/04_parameter_intro_CN.md)
|
||||
|
||||
+ **rs_driver**报告了一个错误`ERRCODE_MSOPTIMEOUT`/`ERRCODE_WRONGMSOPID`/`ERRCODE_PKTBUFOVERFLOW` ...... 这个错误码是什么意思?
|
||||
|
||||
请参考[rs_driver错误码](./doc/intro/06_error_code_intro_CN.md)
|
||||
|
||||
+ 如何将点云变换到另一个位置和角度上去?
|
||||
|
||||
请参考[点云坐标变换](doc/howto/15_how_to_transform_pointcloud_CN.md)
|
||||
|
||||
+ RoboSense雷达的数据量有多大?在什么情况下可能丢包?怎么避免?
|
||||
|
||||
请参考[丢包问题以及如何解决](doc/howto/17_how_to_avoid_packet_loss_CN.md)
|
||||
|
||||
+ **rs_driver**要占用多少CPU和内存?
|
||||
|
||||
请参考[rs_driver的CPU和内存占用](doc/howto/20_about_usage_of_cpu_and_memory_CN.md)
|
||||
|
||||
+ 点在点云中是怎样布局的?点坐标的参考系是什么?点的通道 号指什么?点的时间戳来自哪里?
|
||||
|
||||
请参考[点云中点的布局](doc/howto/18_about_point_layout_CN.md)
|
||||
|
||||
+ RoboSense雷达怎么分帧?RoboSense使用UDP协议,万一丢包或乱序,会影响**rs_driver**的分帧处理吗?
|
||||
|
||||
请参考[RoboSense雷达如何分帧](doc/howto/19_about_splitting_frame_CN.md)
|
||||
|
||||
+ 希望进一步深入了解**rs_driver**的设计细节?
|
||||
|
||||
请参考[rs_driver源代码解析](doc/src_intro/rs_driver_intro_CN.md)
|
||||
|
||||
86
src/airy/rslidar_sdk-main/src/rs_driver/cmake/FindPCAP.cmake
Normal file
@ -0,0 +1,86 @@
|
||||
# - Try to find libpcap include dirs and libraries
|
||||
#
|
||||
# Usage of this module as follows:
|
||||
#
|
||||
# find_package(PCAP)
|
||||
#
|
||||
# Variables used by this module, they can change the default behaviour and need
|
||||
# to be set before calling find_package:
|
||||
#
|
||||
# PCAP_ROOT_DIR Set this variable to the root installation of
|
||||
# libpcap if the module has problems finding the
|
||||
# proper installation path.
|
||||
#
|
||||
# Variables defined by this module:
|
||||
#
|
||||
# PCAP_FOUND System has libpcap, include and library dirs found
|
||||
# PCAP_INCLUDE_DIR The libpcap include directories.
|
||||
# PCAP_LIBRARY The libpcap library (possibly includes a thread
|
||||
# library e.g. required by pf_ring's libpcap)
|
||||
# HAVE_PF_RING If a found version of libpcap supports PF_RING
|
||||
# HAVE_PCAP_IMMEDIATE_MODE If the version of libpcap found supports immediate mode
|
||||
|
||||
find_path(PCAP_ROOT_DIR
|
||||
NAMES include/pcap.h
|
||||
)
|
||||
|
||||
find_path(PCAP_INCLUDE_DIR
|
||||
NAMES pcap.h
|
||||
HINTS ${PCAP_ROOT_DIR}/include
|
||||
)
|
||||
|
||||
set (HINT_DIR ${PCAP_ROOT_DIR}/Lib)
|
||||
|
||||
# On x64 windows, we should look also for the .lib at /lib/x64/
|
||||
# as this is the default path for the WinPcap developer's pack
|
||||
if (${CMAKE_SIZEOF_VOID_P} EQUAL 8 AND WIN32)
|
||||
set (HINT_DIR ${PCAP_ROOT_DIR}/Lib/x64 ${HINT_DIR})
|
||||
endif ()
|
||||
|
||||
find_library(PCAP_LIBRARY
|
||||
NAMES pcap wpcap
|
||||
HINTS ${HINT_DIR}
|
||||
NO_DEFAULT_PATH
|
||||
)
|
||||
|
||||
include(FindPackageHandleStandardArgs)
|
||||
find_package_handle_standard_args(PCAP DEFAULT_MSG
|
||||
PCAP_LIBRARY
|
||||
PCAP_INCLUDE_DIR
|
||||
)
|
||||
|
||||
include(CheckCXXSourceCompiles)
|
||||
set(CMAKE_REQUIRED_LIBRARIES ${PCAP_LIBRARY})
|
||||
check_cxx_source_compiles("int main() { return 0; }" PCAP_LINKS_SOLO)
|
||||
set(CMAKE_REQUIRED_LIBRARIES)
|
||||
|
||||
# check if linking against libpcap also needs to link against a thread library
|
||||
if (NOT PCAP_LINKS_SOLO)
|
||||
find_package(Threads)
|
||||
if (THREADS_FOUND)
|
||||
set(CMAKE_REQUIRED_LIBRARIES ${PCAP_LIBRARY} ${CMAKE_THREAD_LIBS_INIT})
|
||||
check_cxx_source_compiles("int main() { return 0; }" PCAP_NEEDS_THREADS)
|
||||
set(CMAKE_REQUIRED_LIBRARIES)
|
||||
endif (THREADS_FOUND)
|
||||
if (THREADS_FOUND AND PCAP_NEEDS_THREADS)
|
||||
set(_tmp ${PCAP_LIBRARY} ${CMAKE_THREAD_LIBS_INIT})
|
||||
list(REMOVE_DUPLICATES _tmp)
|
||||
set(PCAP_LIBRARY ${_tmp}
|
||||
CACHE STRING "Libraries needed to link against libpcap" FORCE)
|
||||
else (THREADS_FOUND AND PCAP_NEEDS_THREADS)
|
||||
message(FATAL_ERROR "Couldn't determine how to link against libpcap")
|
||||
endif (THREADS_FOUND AND PCAP_NEEDS_THREADS)
|
||||
endif (NOT PCAP_LINKS_SOLO)
|
||||
|
||||
include(CheckFunctionExists)
|
||||
set(CMAKE_REQUIRED_LIBRARIES ${PCAP_LIBRARY})
|
||||
check_function_exists(pcap_get_pfring_id HAVE_PF_RING)
|
||||
check_function_exists(pcap_set_immediate_mode HAVE_PCAP_IMMEDIATE_MODE)
|
||||
check_function_exists(pcap_set_tstamp_precision HAVE_PCAP_TIMESTAMP_PRECISION)
|
||||
set(CMAKE_REQUIRED_LIBRARIES)
|
||||
|
||||
mark_as_advanced(
|
||||
PCAP_ROOT_DIR
|
||||
PCAP_INCLUDE_DIR
|
||||
PCAP_LIBRARY
|
||||
)
|
||||
@ -0,0 +1,23 @@
|
||||
if(NOT EXISTS "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt")
|
||||
message(FATAL_ERROR "Cannot find install manifest: @CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt")
|
||||
endif(NOT EXISTS "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt")
|
||||
|
||||
file(READ "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt" files)
|
||||
string(REGEX REPLACE "\n" ";" files "${files}")
|
||||
foreach(file ${files})
|
||||
message(STATUS "Uninstalling $ENV{DESTDIR}${file}")
|
||||
if(IS_SYMLINK "$ENV{DESTDIR}${file}" OR EXISTS "$ENV{DESTDIR}${file}")
|
||||
exec_program(
|
||||
"@CMAKE_COMMAND@" ARGS "-E remove \"$ENV{DESTDIR}${file}\""
|
||||
OUTPUT_VARIABLE rm_out
|
||||
RETURN_VALUE rm_retval
|
||||
)
|
||||
if(NOT "${rm_retval}" STREQUAL 0)
|
||||
message(FATAL_ERROR "Problem when removing $ENV{DESTDIR}${file}")
|
||||
endif(NOT "${rm_retval}" STREQUAL 0)
|
||||
else(IS_SYMLINK "$ENV{DESTDIR}${file}" OR EXISTS "$ENV{DESTDIR}${file}")
|
||||
message(STATUS "File $ENV{DESTDIR}${file} does not exist.")
|
||||
endif(IS_SYMLINK "$ENV{DESTDIR}${file}" OR EXISTS "$ENV{DESTDIR}${file}")
|
||||
endforeach(file)
|
||||
|
||||
|
||||
@ -0,0 +1,29 @@
|
||||
# - Config file for the package
|
||||
# It defines the following variables
|
||||
# rs_driver_INCLUDE_DIRS - include directories for
|
||||
# rs_driver_LIBRARIES - libraries to link against
|
||||
# rs_driver_FOUND - found flag
|
||||
|
||||
if(WIN32)
|
||||
if(CMAKE_SIZEOF_VOID_P EQUAL 8) # 64-bit
|
||||
set(Boost_ARCHITECTURE "-x64")
|
||||
elseif(CMAKE_SIZEOF_VOID_P EQUAL 4) # 32-bit
|
||||
set(Boost_ARCHITECTURE "-x32")
|
||||
endif()
|
||||
set(Boost_USE_STATIC_LIBS ON)
|
||||
set(Boost_USE_MULTITHREADED ON)
|
||||
set(Boost_USE_STATIC_RUNTIME OFF)
|
||||
endif(WIN32)
|
||||
|
||||
if(${ENABLE_TRANSFORM})
|
||||
add_definitions("-DENABLE_TRANSFORM")
|
||||
endif(${ENABLE_TRANSFORM})
|
||||
|
||||
set(rs_driver_INCLUDE_DIRS "/home/nvidia/Downloads/sweeper_whu/src/airy/rslidar_sdk-main/src/rs_driver/src;/usr/local/rslidar_sdk/include")
|
||||
set(RS_DRIVER_INCLUDE_DIRS "/home/nvidia/Downloads/sweeper_whu/src/airy/rslidar_sdk-main/src/rs_driver/src;/usr/local/rslidar_sdk/include")
|
||||
|
||||
set(rs_driver_LIBRARIES "pthread;pcap")
|
||||
set(RS_DRIVER_LIBRARIES "pthread;pcap")
|
||||
|
||||
set(rs_driver_FOUND true)
|
||||
set(RS_DRIVER_FOUND true)
|
||||
@ -0,0 +1,29 @@
|
||||
# - Config file for the @PROJECT_NAME_LOWER@ package
|
||||
# It defines the following variables
|
||||
# rs_driver_INCLUDE_DIRS - include directories for @PROJECT_NAME_LOWER@
|
||||
# rs_driver_LIBRARIES - libraries to link against
|
||||
# rs_driver_FOUND - found flag
|
||||
|
||||
if(WIN32)
|
||||
if(CMAKE_SIZEOF_VOID_P EQUAL 8) # 64-bit
|
||||
set(Boost_ARCHITECTURE "-x64")
|
||||
elseif(CMAKE_SIZEOF_VOID_P EQUAL 4) # 32-bit
|
||||
set(Boost_ARCHITECTURE "-x32")
|
||||
endif()
|
||||
set(Boost_USE_STATIC_LIBS ON)
|
||||
set(Boost_USE_MULTITHREADED ON)
|
||||
set(Boost_USE_STATIC_RUNTIME OFF)
|
||||
endif(WIN32)
|
||||
|
||||
if(${ENABLE_TRANSFORM})
|
||||
add_definitions("-DENABLE_TRANSFORM")
|
||||
endif(${ENABLE_TRANSFORM})
|
||||
|
||||
set(rs_driver_INCLUDE_DIRS "@DRIVER_INCLUDE_DIRS@;@INSTALL_DRIVER_DIR@")
|
||||
set(RS_DRIVER_INCLUDE_DIRS "@DRIVER_INCLUDE_DIRS@;@INSTALL_DRIVER_DIR@")
|
||||
|
||||
set(rs_driver_LIBRARIES "@EXTERNAL_LIBS@")
|
||||
set(RS_DRIVER_LIBRARIES "@EXTERNAL_LIBS@")
|
||||
|
||||
set(rs_driver_FOUND true)
|
||||
set(RS_DRIVER_FOUND true)
|
||||
@ -0,0 +1,14 @@
|
||||
set (PACKAGE_VERSION "1.5.17")
|
||||
message(=============================================================)
|
||||
message("-- rs_driver Version : v${PACKAGE_VERSION}")
|
||||
message(=============================================================)
|
||||
|
||||
# Check whether the requested PACKAGE_FIND_VERSION is compatible
|
||||
if ("${PACKAGE_VERSION}" VERSION_LESS "${PACKAGE_FIND_VERSION}")
|
||||
set (PACKAGE_VERSION_COMPATIBLE FALSE)
|
||||
else ()
|
||||
set (PACKAGE_VERSION_COMPATIBLE TRUE)
|
||||
if ("${PACKAGE_VERSION}" VERSION_EQUAL "${PACKAGE_FIND_VERSION}")
|
||||
set (PACKAGE_VERSION_EXACT TRUE)
|
||||
endif ()
|
||||
endif ()
|
||||
@ -0,0 +1,14 @@
|
||||
set (PACKAGE_VERSION "@rs_driver_VERSION@")
|
||||
message(=============================================================)
|
||||
message("-- rs_driver Version : v${PACKAGE_VERSION}")
|
||||
message(=============================================================)
|
||||
|
||||
# Check whether the requested PACKAGE_FIND_VERSION is compatible
|
||||
if ("${PACKAGE_VERSION}" VERSION_LESS "${PACKAGE_FIND_VERSION}")
|
||||
set (PACKAGE_VERSION_COMPATIBLE FALSE)
|
||||
else ()
|
||||
set (PACKAGE_VERSION_COMPATIBLE TRUE)
|
||||
if ("${PACKAGE_VERSION}" VERSION_EQUAL "${PACKAGE_FIND_VERSION}")
|
||||
set (PACKAGE_VERSION_EXACT TRUE)
|
||||
endif ()
|
||||
endif ()
|
||||