Compare commits
No commits in common. "ff342c1f05339dfb164d1e6deff4b385a48a1440" and "3897be02b13b7da85c58e1f7a6632f4a1908ae11" have entirely different histories.
ff342c1f05
...
3897be02b1
@ -206,12 +206,9 @@ void PL_ProcThread()
|
||||
int road_pos = 0;
|
||||
int des_pos = 3;
|
||||
int direction_pos = 20;
|
||||
auto next_time = std::chrono::steady_clock::now();
|
||||
|
||||
while (1)
|
||||
{
|
||||
next_time += std::chrono::milliseconds(50);
|
||||
|
||||
g_NavInfo.Latitude_degree = g_rtk.lat;
|
||||
g_NavInfo.Longitude_degree = g_rtk.lon;
|
||||
g_NavInfo.Yaw_rad = g_rtk.direction;
|
||||
@ -277,12 +274,6 @@ void PL_ProcThread()
|
||||
}
|
||||
|
||||
// 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;
|
||||
|
||||
@ -47,7 +47,7 @@ def generate_launch_description():
|
||||
package="mc",
|
||||
executable="mc_node",
|
||||
output="screen",
|
||||
prefix="taskset -c 2",
|
||||
prefix="taskset -c 1",
|
||||
)
|
||||
]
|
||||
)
|
||||
@ -71,7 +71,7 @@ def generate_launch_description():
|
||||
package="pl",
|
||||
executable="pl_node",
|
||||
output="screen",
|
||||
prefix="taskset -c 3",
|
||||
prefix="taskset -c 2",
|
||||
)
|
||||
]
|
||||
)
|
||||
@ -83,7 +83,7 @@ def generate_launch_description():
|
||||
package="mqtt_report",
|
||||
executable="mqtt_report_node",
|
||||
output="screen",
|
||||
prefix="taskset -c 7",
|
||||
prefix="taskset -c 6",
|
||||
)
|
||||
]
|
||||
)
|
||||
@ -94,7 +94,7 @@ def generate_launch_description():
|
||||
ExecuteProcess(
|
||||
cmd=["ros2", "launch", "rslidar_sdk", "start_double.launch.py"],
|
||||
output="screen",
|
||||
prefix="taskset -c 4,5",
|
||||
prefix="taskset -c 3,4",
|
||||
)
|
||||
]
|
||||
)
|
||||
@ -105,7 +105,7 @@ def generate_launch_description():
|
||||
ExecuteProcess(
|
||||
cmd=["ros2", "launch", "rslidar_pointcloud_merger", "merge_two_lidars.launch.py"],
|
||||
output="screen",
|
||||
prefix="taskset -c 6",
|
||||
prefix="taskset -c 5",
|
||||
)
|
||||
]
|
||||
)
|
||||
@ -117,7 +117,7 @@ def generate_launch_description():
|
||||
package="rtk",
|
||||
executable="rtk_node",
|
||||
output="screen",
|
||||
prefix="taskset -c 7",
|
||||
prefix="taskset -c 6",
|
||||
)
|
||||
]
|
||||
)
|
||||
@ -129,7 +129,7 @@ def generate_launch_description():
|
||||
package="route",
|
||||
executable="route_node",
|
||||
output="screen",
|
||||
prefix="taskset -c 7",
|
||||
prefix="taskset -c 6",
|
||||
)
|
||||
]
|
||||
)
|
||||
@ -141,7 +141,7 @@ def generate_launch_description():
|
||||
package="sub",
|
||||
executable="sub_node",
|
||||
output="screen",
|
||||
prefix="taskset -c 7",
|
||||
prefix="taskset -c 6",
|
||||
)
|
||||
]
|
||||
)
|
||||
|
||||
Loading…
Reference in New Issue
Block a user