Compare commits

..

2 Commits

Author SHA1 Message Date
lyq
ff342c1f05 重新分配cpu 2026-04-20 09:44:09 +08:00
lyq
946ad6bfc5 [pl]避免忙等待,避免忙等待 2026-04-20 09:43:05 +08:00
2 changed files with 17 additions and 8 deletions

View File

@ -206,9 +206,12 @@ void PL_ProcThread()
int road_pos = 0; int road_pos = 0;
int des_pos = 3; int des_pos = 3;
int direction_pos = 20; int direction_pos = 20;
auto next_time = std::chrono::steady_clock::now();
while (1) while (1)
{ {
next_time += std::chrono::milliseconds(50);
g_NavInfo.Latitude_degree = g_rtk.lat; g_NavInfo.Latitude_degree = g_rtk.lat;
g_NavInfo.Longitude_degree = g_rtk.lon; g_NavInfo.Longitude_degree = g_rtk.lon;
g_NavInfo.Yaw_rad = g_rtk.direction; g_NavInfo.Yaw_rad = g_rtk.direction;
@ -274,6 +277,12 @@ void PL_ProcThread()
} }
// printf("x_cm:%lf y_cm:%lf speed:%d\n", x, y, pl_speed); // printf("x_cm:%lf y_cm:%lf speed:%d\n", x, y, pl_speed);
// 避免忙等待,增加延迟让 CPU 能够处理其他任务
auto now = std::chrono::steady_clock::now();
if (now > next_time)
next_time = now;
std::this_thread::sleep_until(next_time);
} }
return; return;

View File

@ -47,7 +47,7 @@ def generate_launch_description():
package="mc", package="mc",
executable="mc_node", executable="mc_node",
output="screen", output="screen",
prefix="taskset -c 1", prefix="taskset -c 2",
) )
] ]
) )
@ -71,7 +71,7 @@ def generate_launch_description():
package="pl", package="pl",
executable="pl_node", executable="pl_node",
output="screen", output="screen",
prefix="taskset -c 2", prefix="taskset -c 3",
) )
] ]
) )
@ -83,7 +83,7 @@ def generate_launch_description():
package="mqtt_report", package="mqtt_report",
executable="mqtt_report_node", executable="mqtt_report_node",
output="screen", output="screen",
prefix="taskset -c 6", prefix="taskset -c 7",
) )
] ]
) )
@ -94,7 +94,7 @@ def generate_launch_description():
ExecuteProcess( ExecuteProcess(
cmd=["ros2", "launch", "rslidar_sdk", "start_double.launch.py"], cmd=["ros2", "launch", "rslidar_sdk", "start_double.launch.py"],
output="screen", output="screen",
prefix="taskset -c 3,4", prefix="taskset -c 4,5",
) )
] ]
) )
@ -105,7 +105,7 @@ def generate_launch_description():
ExecuteProcess( ExecuteProcess(
cmd=["ros2", "launch", "rslidar_pointcloud_merger", "merge_two_lidars.launch.py"], cmd=["ros2", "launch", "rslidar_pointcloud_merger", "merge_two_lidars.launch.py"],
output="screen", output="screen",
prefix="taskset -c 5", prefix="taskset -c 6",
) )
] ]
) )
@ -117,7 +117,7 @@ def generate_launch_description():
package="rtk", package="rtk",
executable="rtk_node", executable="rtk_node",
output="screen", output="screen",
prefix="taskset -c 6", prefix="taskset -c 7",
) )
] ]
) )
@ -129,7 +129,7 @@ def generate_launch_description():
package="route", package="route",
executable="route_node", executable="route_node",
output="screen", output="screen",
prefix="taskset -c 6", prefix="taskset -c 7",
) )
] ]
) )
@ -141,7 +141,7 @@ def generate_launch_description():
package="sub", package="sub",
executable="sub_node", executable="sub_node",
output="screen", output="screen",
prefix="taskset -c 6", prefix="taskset -c 7",
) )
] ]
) )