0417 修改启动方式,加入cpu绑定
This commit is contained in:
parent
74da7950fe
commit
3897be02b1
@ -1,22 +1,66 @@
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#!/bin/bash
|
#!/bin/bash
|
||||||
set -e
|
set -e
|
||||||
|
|
||||||
# ===== 环境 =====
|
source install/setup.bash
|
||||||
source /opt/ros/humble/setup.bash
|
|
||||||
source /home/nvidia/Downloads/sweeper_200/install/setup.bash
|
|
||||||
|
|
||||||
# ===== 信号处理(这是核心)=====
|
# ==============================================
|
||||||
terminate() {
|
# 1. 车辆参数节点(你之前漏掉的!必须第一个启动)
|
||||||
echo "[start_ros2] Caught SIGTERM/SIGINT, shutting down ROS2..."
|
# ==============================================
|
||||||
kill -TERM "$ROS2_PID"
|
taskset -c 0 ros2 run vehicle_params vehicle_params_node &
|
||||||
wait "$ROS2_PID"
|
sleep 0.2
|
||||||
exit 0
|
|
||||||
}
|
|
||||||
|
|
||||||
trap terminate SIGINT SIGTERM
|
# ==============================================
|
||||||
|
# 2. 控制类节点(低负载,不影响雷达)
|
||||||
|
# ==============================================
|
||||||
|
taskset -c 0 ros2 run can_radio_ctrl can_radio_ctrl_node &
|
||||||
|
sleep 0.2
|
||||||
|
|
||||||
# ===== 启动 launch(前台语义)=====
|
taskset -c 2 ros2 run remote_ctrl remote_ctrl_node &
|
||||||
ros2 launch launch_system start_all.launch.py &
|
sleep 0.2
|
||||||
ROS2_PID=$!
|
|
||||||
|
|
||||||
wait "$ROS2_PID"
|
taskset -c 1 ros2 run mc mc_node &
|
||||||
|
sleep 0.2
|
||||||
|
|
||||||
|
taskset -c 1 ros2 run ctrl_arbiter ctrl_arbiter_node &
|
||||||
|
sleep 0.2
|
||||||
|
|
||||||
|
taskset -c 2 ros2 run pl pl_node &
|
||||||
|
sleep 0.2
|
||||||
|
|
||||||
|
taskset -c 6 ros2 run mqtt_report mqtt_report_node &
|
||||||
|
sleep 0.3
|
||||||
|
|
||||||
|
# ==============================================
|
||||||
|
# 3. 雷达驱动 —— 专用核心 3、4(绝不被抢占)
|
||||||
|
# ==============================================
|
||||||
|
taskset -c 3,4 ros2 launch rslidar_sdk start_double.launch.py &
|
||||||
|
sleep 1.5
|
||||||
|
|
||||||
|
# ==============================================
|
||||||
|
# 4. 点云融合 —— 专用核心 5(完全隔离)
|
||||||
|
# ==============================================
|
||||||
|
taskset -c 5 ros2 launch rslidar_pointcloud_merger merge_two_lidars.launch.py &
|
||||||
|
sleep 0.3
|
||||||
|
|
||||||
|
# ==============================================
|
||||||
|
# 5. 定位 & 业务节点(不干扰雷达)
|
||||||
|
# ==============================================
|
||||||
|
taskset -c 6 ros2 run rtk rtk_node &
|
||||||
|
sleep 0.3
|
||||||
|
|
||||||
|
taskset -c 6 ros2 run route route_node &
|
||||||
|
sleep 0.3
|
||||||
|
|
||||||
|
taskset -c 6 ros2 run sub sub_node &
|
||||||
|
sleep 0.3
|
||||||
|
|
||||||
|
taskset -c 7 ros2 run task_manager task_manager_node &
|
||||||
|
sleep 0.3
|
||||||
|
|
||||||
|
taskset -c 7 ros2 launch fu fu.launch.py &
|
||||||
|
|
||||||
|
wait
|
||||||
1124
gps_load_now.txt
1124
gps_load_now.txt
File diff suppressed because it is too large
Load Diff
1504
routes/gps_load_1772775503834.txt
Normal file
1504
routes/gps_load_1772775503834.txt
Normal file
File diff suppressed because it is too large
Load Diff
4
routes/gps_load_1776133105337.txt
Normal file
4
routes/gps_load_1776133105337.txt
Normal file
@ -0,0 +1,4 @@
|
|||||||
|
32.0306440200
|
||||||
|
120.91487580900
|
||||||
|
358.662994
|
||||||
|
0.000000
|
||||||
0
routes/gps_load_1776403621977.txt
Normal file
0
routes/gps_load_1776403621977.txt
Normal file
264
routes/gps_load_1776403666678.txt
Normal file
264
routes/gps_load_1776403666678.txt
Normal file
@ -0,0 +1,264 @@
|
|||||||
|
32.0309108070
|
||||||
|
120.91507417100
|
||||||
|
155.817001
|
||||||
|
0.000000
|
||||||
|
32.0309020700
|
||||||
|
120.91507871100
|
||||||
|
155.617004
|
||||||
|
0.000000
|
||||||
|
32.0308925710
|
||||||
|
120.91508315600
|
||||||
|
156.106003
|
||||||
|
0.000000
|
||||||
|
32.0308838810
|
||||||
|
120.91508811200
|
||||||
|
159.794998
|
||||||
|
0.000000
|
||||||
|
32.0308750760
|
||||||
|
120.91509269300
|
||||||
|
156.994003
|
||||||
|
0.000000
|
||||||
|
32.0308662720
|
||||||
|
120.91509687200
|
||||||
|
154.442001
|
||||||
|
0.000000
|
||||||
|
32.0308572580
|
||||||
|
120.91510140100
|
||||||
|
154.037003
|
||||||
|
0.000000
|
||||||
|
32.0308493400
|
||||||
|
120.91510792100
|
||||||
|
149.167007
|
||||||
|
0.000000
|
||||||
|
32.0308410420
|
||||||
|
120.91511352700
|
||||||
|
148.658005
|
||||||
|
0.000000
|
||||||
|
32.0308330410
|
||||||
|
120.91511914800
|
||||||
|
147.304001
|
||||||
|
0.000000
|
||||||
|
32.0308248540
|
||||||
|
120.91512524500
|
||||||
|
149.287994
|
||||||
|
0.000000
|
||||||
|
32.0308159770
|
||||||
|
120.91513145400
|
||||||
|
150.360001
|
||||||
|
0.000000
|
||||||
|
32.0308082140
|
||||||
|
120.91513700300
|
||||||
|
147.880005
|
||||||
|
0.000000
|
||||||
|
32.0308008210
|
||||||
|
120.91514308400
|
||||||
|
140.037994
|
||||||
|
0.000000
|
||||||
|
32.0307936440
|
||||||
|
120.91515072000
|
||||||
|
132.856003
|
||||||
|
0.000000
|
||||||
|
32.0307878360
|
||||||
|
120.91515897500
|
||||||
|
121.110001
|
||||||
|
0.000000
|
||||||
|
32.0307834830
|
||||||
|
120.91516829500
|
||||||
|
112.790001
|
||||||
|
0.000000
|
||||||
|
32.0307799510
|
||||||
|
120.91517868100
|
||||||
|
108.697998
|
||||||
|
0.000000
|
||||||
|
32.0307772600
|
||||||
|
120.91518915200
|
||||||
|
102.210999
|
||||||
|
0.000000
|
||||||
|
32.0307758630
|
||||||
|
120.91520013900
|
||||||
|
90.101997
|
||||||
|
0.000000
|
||||||
|
32.0307765330
|
||||||
|
120.91521115700
|
||||||
|
76.972000
|
||||||
|
0.000000
|
||||||
|
32.0307792340
|
||||||
|
120.91522159800
|
||||||
|
61.636002
|
||||||
|
0.000000
|
||||||
|
32.0307846230
|
||||||
|
120.91523071400
|
||||||
|
43.868000
|
||||||
|
0.000000
|
||||||
|
32.0307924840
|
||||||
|
120.91523764700
|
||||||
|
25.950001
|
||||||
|
0.000000
|
||||||
|
32.0308016330
|
||||||
|
120.91524212700
|
||||||
|
19.583000
|
||||||
|
0.000000
|
||||||
|
32.0308107830
|
||||||
|
120.91524524100
|
||||||
|
6.474000
|
||||||
|
0.000000
|
||||||
|
32.0308204550
|
||||||
|
120.91524576100
|
||||||
|
355.416992
|
||||||
|
0.000000
|
||||||
|
32.0308296190
|
||||||
|
120.91524483600
|
||||||
|
356.260010
|
||||||
|
0.000000
|
||||||
|
32.0308395780
|
||||||
|
120.91524464400
|
||||||
|
0.199000
|
||||||
|
0.000000
|
||||||
|
32.0308489180
|
||||||
|
120.91524451800
|
||||||
|
0.015000
|
||||||
|
0.000000
|
||||||
|
32.0308585990
|
||||||
|
120.91524434700
|
||||||
|
359.226990
|
||||||
|
0.000000
|
||||||
|
32.0308694160
|
||||||
|
120.91524423900
|
||||||
|
358.707001
|
||||||
|
0.000000
|
||||||
|
32.0308791190
|
||||||
|
120.91524398500
|
||||||
|
358.138000
|
||||||
|
0.000000
|
||||||
|
32.0308889120
|
||||||
|
120.91524350400
|
||||||
|
357.056000
|
||||||
|
0.000000
|
||||||
|
32.0308986090
|
||||||
|
120.91524281800
|
||||||
|
356.694000
|
||||||
|
0.000000
|
||||||
|
32.0309080990
|
||||||
|
120.91524194800
|
||||||
|
357.459991
|
||||||
|
0.000000
|
||||||
|
32.0309170830
|
||||||
|
120.91524129800
|
||||||
|
357.404999
|
||||||
|
0.000000
|
||||||
|
32.0309264030
|
||||||
|
120.91524072500
|
||||||
|
356.957001
|
||||||
|
0.000000
|
||||||
|
32.0309357950
|
||||||
|
120.91524006000
|
||||||
|
357.480011
|
||||||
|
0.000000
|
||||||
|
32.0309463390
|
||||||
|
120.91523904200
|
||||||
|
357.307007
|
||||||
|
0.000000
|
||||||
|
32.0309554710
|
||||||
|
120.91523855400
|
||||||
|
351.339996
|
||||||
|
0.000000
|
||||||
|
32.0309652710
|
||||||
|
120.91523615700
|
||||||
|
346.320007
|
||||||
|
0.000000
|
||||||
|
32.0309748560
|
||||||
|
120.91523298200
|
||||||
|
345.138000
|
||||||
|
0.000000
|
||||||
|
32.0309836220
|
||||||
|
120.91523009100
|
||||||
|
345.750000
|
||||||
|
0.000000
|
||||||
|
32.0309944360
|
||||||
|
120.91522686300
|
||||||
|
346.925995
|
||||||
|
0.000000
|
||||||
|
32.0310042540
|
||||||
|
120.91522422300
|
||||||
|
345.520996
|
||||||
|
0.000000
|
||||||
|
32.0310132960
|
||||||
|
120.91522074900
|
||||||
|
333.592987
|
||||||
|
0.000000
|
||||||
|
32.0310218240
|
||||||
|
120.91521520700
|
||||||
|
327.031006
|
||||||
|
0.000000
|
||||||
|
32.0310292350
|
||||||
|
120.91520841800
|
||||||
|
311.174988
|
||||||
|
0.000000
|
||||||
|
32.0310347830
|
||||||
|
120.91519920300
|
||||||
|
294.627014
|
||||||
|
0.000000
|
||||||
|
32.0310382010
|
||||||
|
120.91518880900
|
||||||
|
287.684998
|
||||||
|
0.000000
|
||||||
|
32.0310407910
|
||||||
|
120.91517767000
|
||||||
|
278.509003
|
||||||
|
0.000000
|
||||||
|
32.0310416520
|
||||||
|
120.91516486000
|
||||||
|
268.722992
|
||||||
|
0.000000
|
||||||
|
32.0310406100
|
||||||
|
120.91515351800
|
||||||
|
256.851013
|
||||||
|
0.000000
|
||||||
|
32.0310381420
|
||||||
|
120.91514246100
|
||||||
|
254.175995
|
||||||
|
0.000000
|
||||||
|
32.0310349300
|
||||||
|
120.91513156600
|
||||||
|
247.996994
|
||||||
|
0.000000
|
||||||
|
32.0310300470
|
||||||
|
120.91512051800
|
||||||
|
232.988998
|
||||||
|
0.000000
|
||||||
|
32.0310238220
|
||||||
|
120.91511187700
|
||||||
|
221.505997
|
||||||
|
0.000000
|
||||||
|
32.0310162570
|
||||||
|
120.91510478900
|
||||||
|
216.899002
|
||||||
|
0.000000
|
||||||
|
32.0310082200
|
||||||
|
120.91509815500
|
||||||
|
213.102005
|
||||||
|
0.000000
|
||||||
|
32.0310000010
|
||||||
|
120.91509229000
|
||||||
|
204.339005
|
||||||
|
0.000000
|
||||||
|
32.0309901480
|
||||||
|
120.91508807900
|
||||||
|
193.214005
|
||||||
|
0.000000
|
||||||
|
32.0309811650
|
||||||
|
120.91508645100
|
||||||
|
183.498993
|
||||||
|
0.000000
|
||||||
|
32.0309719130
|
||||||
|
120.91508578100
|
||||||
|
179.050003
|
||||||
|
0.000000
|
||||||
|
32.0309626190
|
||||||
|
120.91508615600
|
||||||
|
176.710999
|
||||||
|
0.000000
|
||||||
|
32.0309533890
|
||||||
|
120.91508666000
|
||||||
|
175.382996
|
||||||
|
0.000000
|
||||||
@ -16,7 +16,7 @@ struct can_BMS_query_0x100
|
|||||||
// 报文ID与控制标志定义
|
// 报文ID与控制标志定义
|
||||||
static constexpr uint32_t CMD_ID = 0x100; // 标准帧ID
|
static constexpr uint32_t CMD_ID = 0x100; // 标准帧ID
|
||||||
static constexpr bool EXT_FLAG = false; // 11位标准帧
|
static constexpr bool EXT_FLAG = false; // 11位标准帧
|
||||||
static constexpr bool RTR_FLAG = true; // 普通数据帧(非远程帧)
|
static constexpr bool RTR_FLAG = false; // 普通数据帧(非远程帧)
|
||||||
static constexpr uint8_t DLC = 8; // 数据长度为8字节
|
static constexpr uint8_t DLC = 8; // 数据长度为8字节
|
||||||
|
|
||||||
// 数据区(主机查询时通常发送全0)
|
// 数据区(主机查询时通常发送全0)
|
||||||
@ -43,7 +43,7 @@ struct can_BMS_query_0x101
|
|||||||
// 报文ID与控制标志定义
|
// 报文ID与控制标志定义
|
||||||
static constexpr uint32_t CMD_ID = 0x101; // 标准帧ID
|
static constexpr uint32_t CMD_ID = 0x101; // 标准帧ID
|
||||||
static constexpr bool EXT_FLAG = false; // 11位标准帧
|
static constexpr bool EXT_FLAG = false; // 11位标准帧
|
||||||
static constexpr bool RTR_FLAG = true; // 普通数据帧(非远程帧)
|
static constexpr bool RTR_FLAG = false; // 普通数据帧(非远程帧)
|
||||||
static constexpr uint8_t DLC = 8; // 数据长度为8字节
|
static constexpr uint8_t DLC = 8; // 数据长度为8字节
|
||||||
|
|
||||||
// 数据区(主机查询时通常发送全0)
|
// 数据区(主机查询时通常发送全0)
|
||||||
|
|||||||
@ -1,203 +1,187 @@
|
|||||||
from launch import LaunchDescription
|
from launch import LaunchDescription
|
||||||
from launch_ros.actions import Node
|
from launch_ros.actions import Node
|
||||||
from launch.actions import IncludeLaunchDescription, TimerAction
|
from launch.actions import TimerAction, ExecuteProcess
|
||||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
|
||||||
from ament_index_python.packages import get_package_share_directory
|
from ament_index_python.packages import get_package_share_directory
|
||||||
import os
|
import os
|
||||||
|
|
||||||
|
|
||||||
def generate_launch_description():
|
def generate_launch_description():
|
||||||
# 获取各包的路径
|
rslidar_sdk_dir = get_package_share_directory("rslidar_sdk")
|
||||||
rslidar_sdk_path = get_package_share_directory("rslidar_sdk")
|
pointcloud_merger_dir = get_package_share_directory("rslidar_pointcloud_merger")
|
||||||
fu_path = get_package_share_directory("fu")
|
fu_dir = get_package_share_directory("fu")
|
||||||
|
|
||||||
# ===================== 按顺序延时启动所有节点 =====================
|
vehicle_params = Node(
|
||||||
# 1. 车辆参数节点 (立即启动)
|
|
||||||
vehicle_params_node = Node(
|
|
||||||
package="vehicle_params",
|
package="vehicle_params",
|
||||||
executable="vehicle_params_node",
|
executable="vehicle_params_node",
|
||||||
name="vehicle_params_node",
|
|
||||||
output="screen",
|
output="screen",
|
||||||
respawn=True,
|
prefix="taskset -c 0",
|
||||||
respawn_delay=2,
|
|
||||||
)
|
)
|
||||||
|
|
||||||
# 2. CAN遥控节点 (延时0.2s)
|
can_radio_ctrl = TimerAction(
|
||||||
can_radio_ctrl_node = TimerAction(
|
|
||||||
period=0.2,
|
period=0.2,
|
||||||
actions=[Node(
|
actions=[
|
||||||
package="can_radio_ctrl",
|
Node(
|
||||||
executable="can_radio_ctrl_node",
|
package="can_radio_ctrl",
|
||||||
name="can_radio_ctrl_node",
|
executable="can_radio_ctrl_node",
|
||||||
output="screen",
|
output="screen",
|
||||||
respawn=True,
|
prefix="taskset -c 0",
|
||||||
respawn_delay=2,
|
|
||||||
)]
|
|
||||||
)
|
|
||||||
# Node(
|
|
||||||
# package="radio_ctrl",
|
|
||||||
# executable="radio_ctrl_node",
|
|
||||||
# name="radio_ctrl_node",
|
|
||||||
# output="screen",
|
|
||||||
# respawn=True,
|
|
||||||
# respawn_delay=2,
|
|
||||||
# ),
|
|
||||||
|
|
||||||
# 3. 远程控制节点 (延时0.4s)
|
|
||||||
remote_ctrl_node = TimerAction(
|
|
||||||
period=0.4,
|
|
||||||
actions=[Node(
|
|
||||||
package="remote_ctrl",
|
|
||||||
executable="remote_ctrl_node",
|
|
||||||
name="remote_ctrl_node",
|
|
||||||
output="screen",
|
|
||||||
respawn=True,
|
|
||||||
respawn_delay=2,
|
|
||||||
)]
|
|
||||||
)
|
|
||||||
|
|
||||||
# 4. MC电机控制节点 (延时0.6s)
|
|
||||||
mc_node = TimerAction(
|
|
||||||
period=0.6,
|
|
||||||
actions=[Node(
|
|
||||||
package="mc",
|
|
||||||
executable="mc_node",
|
|
||||||
name="mc_node",
|
|
||||||
output="screen",
|
|
||||||
respawn=True,
|
|
||||||
respawn_delay=2,
|
|
||||||
)]
|
|
||||||
)
|
|
||||||
|
|
||||||
# 5. 控制仲裁节点 (延时0.8s)
|
|
||||||
ctrl_arbiter_node = TimerAction(
|
|
||||||
period=0.8,
|
|
||||||
actions=[Node(
|
|
||||||
package="ctrl_arbiter",
|
|
||||||
executable="ctrl_arbiter_node",
|
|
||||||
name="ctrl_arbiter_node",
|
|
||||||
output="screen",
|
|
||||||
respawn=True,
|
|
||||||
respawn_delay=2,
|
|
||||||
)]
|
|
||||||
)
|
|
||||||
|
|
||||||
# 6. MQTT上报节点 (延时1.0s) —— 【关键:必须最后启动】
|
|
||||||
mqtt_report_node = TimerAction(
|
|
||||||
period=1.0,
|
|
||||||
actions=[Node(
|
|
||||||
package="mqtt_report",
|
|
||||||
executable="mqtt_report_node",
|
|
||||||
name="mqtt_report_node",
|
|
||||||
output="screen",
|
|
||||||
respawn=True,
|
|
||||||
respawn_delay=2,
|
|
||||||
)]
|
|
||||||
)
|
|
||||||
|
|
||||||
# 7. 雷达启动 (延时1.5s)
|
|
||||||
lidar_launch = TimerAction(
|
|
||||||
period=1.5,
|
|
||||||
actions=[IncludeLaunchDescription(
|
|
||||||
PythonLaunchDescriptionSource(
|
|
||||||
os.path.join(rslidar_sdk_path, "launch", "start_double.launch.py")
|
|
||||||
)
|
)
|
||||||
)]
|
|
||||||
)
|
|
||||||
|
|
||||||
# 8. RTK定位节点 (延时2.0s)
|
|
||||||
rtk_node = TimerAction(
|
|
||||||
period=2.0,
|
|
||||||
actions=[Node(
|
|
||||||
package="rtk",
|
|
||||||
executable="rtk_node",
|
|
||||||
name="rtk_node",
|
|
||||||
parameters=[
|
|
||||||
os.path.join(
|
|
||||||
get_package_share_directory("rtk"), "config", "rtk_params.yaml"
|
|
||||||
)
|
|
||||||
],
|
|
||||||
output="screen",
|
|
||||||
)]
|
|
||||||
)
|
|
||||||
|
|
||||||
# 9. 路径节点 (延时2.5s)
|
|
||||||
route_node = TimerAction(
|
|
||||||
period=2.5,
|
|
||||||
actions=[Node(
|
|
||||||
package="route",
|
|
||||||
executable="route_node",
|
|
||||||
name="route_node",
|
|
||||||
output="screen",
|
|
||||||
respawn=True,
|
|
||||||
respawn_delay=2,
|
|
||||||
)]
|
|
||||||
)
|
|
||||||
|
|
||||||
# 10. 订阅节点 (延时3.0s)
|
|
||||||
sub_node = TimerAction(
|
|
||||||
period=3.0,
|
|
||||||
actions=[Node(
|
|
||||||
package="sub",
|
|
||||||
executable="sub_node",
|
|
||||||
name="sub_node",
|
|
||||||
output="screen",
|
|
||||||
respawn=True,
|
|
||||||
respawn_delay=2,
|
|
||||||
)]
|
|
||||||
)
|
|
||||||
|
|
||||||
# 11. 任务管理节点 (延时3.5s)
|
|
||||||
task_manager_node = TimerAction(
|
|
||||||
period=3.5,
|
|
||||||
actions=[Node(
|
|
||||||
package="task_manager",
|
|
||||||
executable="task_manager_node",
|
|
||||||
name="task_manager_node",
|
|
||||||
output="screen",
|
|
||||||
respawn=True,
|
|
||||||
respawn_delay=2,
|
|
||||||
)]
|
|
||||||
)
|
|
||||||
|
|
||||||
# 12. 规划控制节点 (延时4.0s)
|
|
||||||
pl_node = TimerAction(
|
|
||||||
period=4.0,
|
|
||||||
actions=[Node(
|
|
||||||
package="pl",
|
|
||||||
executable="pl_node",
|
|
||||||
name="pl_node",
|
|
||||||
output="screen",
|
|
||||||
respawn=True,
|
|
||||||
respawn_delay=2,
|
|
||||||
)]
|
|
||||||
)
|
|
||||||
|
|
||||||
# 13. FU功能节点 (延时4.5s)
|
|
||||||
fu_launch = TimerAction(
|
|
||||||
period=4.5,
|
|
||||||
actions=[IncludeLaunchDescription(
|
|
||||||
PythonLaunchDescriptionSource(
|
|
||||||
os.path.join(fu_path, "launch", "fu.launch.py")
|
|
||||||
)
|
|
||||||
)]
|
|
||||||
)
|
|
||||||
|
|
||||||
# ===================== 组装启动列表 =====================
|
|
||||||
return LaunchDescription(
|
|
||||||
[
|
|
||||||
vehicle_params_node,
|
|
||||||
can_radio_ctrl_node,
|
|
||||||
remote_ctrl_node,
|
|
||||||
mc_node,
|
|
||||||
ctrl_arbiter_node,
|
|
||||||
mqtt_report_node,
|
|
||||||
lidar_launch,
|
|
||||||
rtk_node,
|
|
||||||
route_node,
|
|
||||||
sub_node,
|
|
||||||
task_manager_node,
|
|
||||||
pl_node,
|
|
||||||
fu_launch,
|
|
||||||
]
|
]
|
||||||
)
|
)
|
||||||
|
|
||||||
|
remote_ctrl = TimerAction(
|
||||||
|
period=0.4,
|
||||||
|
actions=[
|
||||||
|
Node(
|
||||||
|
package="remote_ctrl",
|
||||||
|
executable="remote_ctrl_node",
|
||||||
|
output="screen",
|
||||||
|
prefix="taskset -c 2",
|
||||||
|
)
|
||||||
|
]
|
||||||
|
)
|
||||||
|
|
||||||
|
mc = TimerAction(
|
||||||
|
period=0.6,
|
||||||
|
actions=[
|
||||||
|
Node(
|
||||||
|
package="mc",
|
||||||
|
executable="mc_node",
|
||||||
|
output="screen",
|
||||||
|
prefix="taskset -c 1",
|
||||||
|
)
|
||||||
|
]
|
||||||
|
)
|
||||||
|
|
||||||
|
ctrl_arbiter = TimerAction(
|
||||||
|
period=0.8,
|
||||||
|
actions=[
|
||||||
|
Node(
|
||||||
|
package="ctrl_arbiter",
|
||||||
|
executable="ctrl_arbiter_node",
|
||||||
|
output="screen",
|
||||||
|
prefix="taskset -c 1",
|
||||||
|
)
|
||||||
|
]
|
||||||
|
)
|
||||||
|
|
||||||
|
pl = TimerAction(
|
||||||
|
period=1.0,
|
||||||
|
actions=[
|
||||||
|
Node(
|
||||||
|
package="pl",
|
||||||
|
executable="pl_node",
|
||||||
|
output="screen",
|
||||||
|
prefix="taskset -c 2",
|
||||||
|
)
|
||||||
|
]
|
||||||
|
)
|
||||||
|
|
||||||
|
mqtt_report = TimerAction(
|
||||||
|
period=1.3,
|
||||||
|
actions=[
|
||||||
|
Node(
|
||||||
|
package="mqtt_report",
|
||||||
|
executable="mqtt_report_node",
|
||||||
|
output="screen",
|
||||||
|
prefix="taskset -c 6",
|
||||||
|
)
|
||||||
|
]
|
||||||
|
)
|
||||||
|
|
||||||
|
lidar_driver = TimerAction(
|
||||||
|
period=1.6,
|
||||||
|
actions=[
|
||||||
|
ExecuteProcess(
|
||||||
|
cmd=["ros2", "launch", "rslidar_sdk", "start_double.launch.py"],
|
||||||
|
output="screen",
|
||||||
|
prefix="taskset -c 3,4",
|
||||||
|
)
|
||||||
|
]
|
||||||
|
)
|
||||||
|
|
||||||
|
pointcloud_merger = TimerAction(
|
||||||
|
period=3.1,
|
||||||
|
actions=[
|
||||||
|
ExecuteProcess(
|
||||||
|
cmd=["ros2", "launch", "rslidar_pointcloud_merger", "merge_two_lidars.launch.py"],
|
||||||
|
output="screen",
|
||||||
|
prefix="taskset -c 5",
|
||||||
|
)
|
||||||
|
]
|
||||||
|
)
|
||||||
|
|
||||||
|
rtk = TimerAction(
|
||||||
|
period=3.4,
|
||||||
|
actions=[
|
||||||
|
Node(
|
||||||
|
package="rtk",
|
||||||
|
executable="rtk_node",
|
||||||
|
output="screen",
|
||||||
|
prefix="taskset -c 6",
|
||||||
|
)
|
||||||
|
]
|
||||||
|
)
|
||||||
|
|
||||||
|
route = TimerAction(
|
||||||
|
period=3.7,
|
||||||
|
actions=[
|
||||||
|
Node(
|
||||||
|
package="route",
|
||||||
|
executable="route_node",
|
||||||
|
output="screen",
|
||||||
|
prefix="taskset -c 6",
|
||||||
|
)
|
||||||
|
]
|
||||||
|
)
|
||||||
|
|
||||||
|
sub = TimerAction(
|
||||||
|
period=4.0,
|
||||||
|
actions=[
|
||||||
|
Node(
|
||||||
|
package="sub",
|
||||||
|
executable="sub_node",
|
||||||
|
output="screen",
|
||||||
|
prefix="taskset -c 6",
|
||||||
|
)
|
||||||
|
]
|
||||||
|
)
|
||||||
|
|
||||||
|
task_manager = TimerAction(
|
||||||
|
period=4.3,
|
||||||
|
actions=[
|
||||||
|
Node(
|
||||||
|
package="task_manager",
|
||||||
|
executable="task_manager_node",
|
||||||
|
output="screen",
|
||||||
|
prefix="taskset -c 7",
|
||||||
|
)
|
||||||
|
]
|
||||||
|
)
|
||||||
|
|
||||||
|
fu = TimerAction(
|
||||||
|
period=4.6,
|
||||||
|
actions=[
|
||||||
|
ExecuteProcess(
|
||||||
|
cmd=["ros2", "launch", "fu", "fu.launch.py"],
|
||||||
|
output="screen",
|
||||||
|
prefix="taskset -c 7",
|
||||||
|
)
|
||||||
|
]
|
||||||
|
)
|
||||||
|
|
||||||
|
return LaunchDescription([
|
||||||
|
vehicle_params,
|
||||||
|
can_radio_ctrl,
|
||||||
|
remote_ctrl,
|
||||||
|
mc,
|
||||||
|
ctrl_arbiter,
|
||||||
|
pl,
|
||||||
|
mqtt_report,
|
||||||
|
lidar_driver,
|
||||||
|
pointcloud_merger,
|
||||||
|
rtk,
|
||||||
|
route,
|
||||||
|
sub,
|
||||||
|
task_manager,
|
||||||
|
fu,
|
||||||
|
])
|
||||||
70
start_all.sh
70
start_all.sh
@ -1,62 +1,22 @@
|
|||||||
#!/bin/bash
|
#!/bin/bash
|
||||||
set -e
|
set -e
|
||||||
|
|
||||||
source install/setup.bash
|
# ===== 环境 =====
|
||||||
|
source /opt/ros/humble/setup.bash
|
||||||
|
source /home/nvidia/Downloads/sweeper_200/install/setup.bash
|
||||||
|
|
||||||
# ==============================================
|
# ===== 信号处理(这是核心)=====
|
||||||
# 1. 车辆参数节点(你之前漏掉的!必须第一个启动)
|
terminate() {
|
||||||
# ==============================================
|
echo "[start_ros2] Caught SIGTERM/SIGINT, shutting down ROS2..."
|
||||||
taskset -c 0 ros2 run vehicle_params vehicle_params_node &
|
kill -TERM "$ROS2_PID"
|
||||||
sleep 0.2
|
wait "$ROS2_PID"
|
||||||
|
exit 0
|
||||||
|
}
|
||||||
|
|
||||||
# ==============================================
|
trap terminate SIGINT SIGTERM
|
||||||
# 2. 控制类节点(低负载,不影响雷达)
|
|
||||||
# ==============================================
|
|
||||||
taskset -c 0 ros2 run can_radio_ctrl can_radio_ctrl_node &
|
|
||||||
sleep 0.2
|
|
||||||
|
|
||||||
taskset -c 2 ros2 run remote_ctrl remote_ctrl_node &
|
# ===== 启动 launch(前台语义)=====
|
||||||
sleep 0.2
|
ros2 launch launch_system start_all.launch.py &
|
||||||
|
ROS2_PID=$!
|
||||||
|
|
||||||
taskset -c 1 ros2 run mc mc_node &
|
wait "$ROS2_PID"
|
||||||
sleep 0.2
|
|
||||||
|
|
||||||
taskset -c 1 ros2 run ctrl_arbiter ctrl_arbiter_node &
|
|
||||||
sleep 0.2
|
|
||||||
|
|
||||||
taskset -c 2 ros2 run pl pl_node &
|
|
||||||
sleep 0.2
|
|
||||||
|
|
||||||
taskset -c 6 ros2 run mqtt_report mqtt_report_node &
|
|
||||||
sleep 0.3
|
|
||||||
|
|
||||||
# ==============================================
|
|
||||||
# 3. 雷达驱动 —— 专用核心 3、4(绝不被抢占)
|
|
||||||
# ==============================================
|
|
||||||
taskset -c 3,4 ros2 launch rslidar_sdk start_double.launch.py &
|
|
||||||
sleep 1.5
|
|
||||||
|
|
||||||
# ==============================================
|
|
||||||
# 4. 点云融合 —— 专用核心 5(完全隔离)
|
|
||||||
# ==============================================
|
|
||||||
taskset -c 5 ros2 launch rslidar_pointcloud_merger merge_two_lidars.launch.py &
|
|
||||||
sleep 0.3
|
|
||||||
|
|
||||||
# ==============================================
|
|
||||||
# 5. 定位 & 业务节点(不干扰雷达)
|
|
||||||
# ==============================================
|
|
||||||
taskset -c 6 ros2 run rtk rtk_node &
|
|
||||||
sleep 0.3
|
|
||||||
|
|
||||||
taskset -c 6 ros2 run route route_node &
|
|
||||||
sleep 0.3
|
|
||||||
|
|
||||||
taskset -c 6 ros2 run sub sub_node &
|
|
||||||
sleep 0.3
|
|
||||||
|
|
||||||
taskset -c 7 ros2 run task_manager task_manager_node &
|
|
||||||
sleep 0.3
|
|
||||||
|
|
||||||
taskset -c 7 ros2 launch fu fu.launch.py &
|
|
||||||
|
|
||||||
wait
|
|
||||||
Loading…
Reference in New Issue
Block a user