Compare commits

...

2 Commits

Author SHA1 Message Date
lyq
466a615378 更新gitignore 2026-01-21 13:29:42 +08:00
lyq
0c429ac416 优化日志文件结构 2026-01-21 13:29:22 +08:00
18 changed files with 36 additions and 22 deletions

3
.gitignore vendored
View File

@ -2,4 +2,5 @@ build
install
log
.vscode
deb_build
deb_build
nodes_log

View File

@ -750,6 +750,8 @@ class fu_node : public rclcpp::Node
reliability = msg->reliability;
located = msg->enter_range;
is_start = msg->is_start;
LOG_INFO("目标点位置: x -- %.2f , y -- %.2f", x, y);
}
void msg_callback_DetectLine(const sweeper_interfaces::msg::DetectLine::SharedPtr msg)
@ -1638,7 +1640,7 @@ class fu_node : public rclcpp::Node
int main(int argc, char** argv)
{
// 初始化日志系统
logger::Logger::Init("fu", "./log");
logger::Logger::Init("fu", "./nodes_log");
rclcpp::init(argc, argv);
auto node = std::make_shared<fu_node>("fu_node");

View File

@ -13,6 +13,7 @@
<depend>std_msgs</depend>
<depend>sweeper_interfaces</depend>
<depend>mc</depend>
<depend>logger</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

View File

@ -218,11 +218,6 @@ void PL_ProcThread()
des_pos = Road_Planning_Find_Aim_Point(road_pos, 3); // 找到当前点后第 3 个点,作为目标点
direction_pos = Road_Planning_Find_Aim_Point(road_pos, 6); // 找到当前点后第 6 个点,判断直行/转弯
// printf("当前位置: %d\n", road_pos);
// printf("目标位置: %d\n", des_pos);
// printf("direction_pos: %d\n", direction_pos);
// printf("\n");
drive_mode = straight_or_turn(g_rtk.direction, GPSPointQueue[direction_pos].Heading, 12);
// 新增距离判断逻辑
@ -233,6 +228,12 @@ void PL_ProcThread()
double target_lat = GPSPointQueue[des_pos].LatitudeInfo;
double target_head = GPSPointQueue[des_pos].Heading;
LOG_INFO_THROTTLE(1000, "当前位置: %d 经度: %.6f 纬度: %.6f 朝向: %.1f", road_pos, current_lon, current_lat,
current_head);
LOG_INFO_THROTTLE(1000, "目标位置: %d 经度: %.6f 纬度: %.6f 朝向: %.1f", des_pos, target_lon, target_lat,
target_head);
LOG_INFO_THROTTLE(1000, "############################################################");
// 计算当前定位点与目标点距离
double distance = ntzx_GPS_length(current_lon, current_lat, target_lon, target_lat);
int nl_within_head = (abs(target_head - current_head) < 30) ? 1 : 0;

View File

@ -229,7 +229,7 @@ int main(int argc, char** argv)
initConfig();
rclcpp::init(argc, argv);
// 初始化日志系统
logger::Logger::Init("pl", "./log");
logger::Logger::Init("pl", "./nodes_log");
/*创建对应节点的共享指针对象*/
auto node = std::make_shared<pl_node>("pl_node");
/* 运行节点,并检测退出信号*/

View File

@ -253,7 +253,7 @@ int main(int argc, char** argv)
init_main();
rclcpp::init(argc, argv);
/*初始化日志系统*/
logger::Logger::Init("route", "./log");
logger::Logger::Init("route", "./nodes_log");
/*创建对应节点的共享指针对象*/
auto node = std::make_shared<route_node>("route_node");
/* 运行节点,并检测退出信号*/

View File

@ -44,7 +44,7 @@ int main(int argc, char** argv)
{
rclcpp::init(argc, argv);
/*初始化日志系统*/
logger::Logger::Init("mc", "./log");
logger::Logger::Init("mc", "./nodes_log");
auto node = rclcpp::Node::make_shared("can_driver_node");
LOG_INFO("Starting mc package...");

View File

@ -109,7 +109,7 @@ int main(int argc, char** argv)
{
rclcpp::init(argc, argv);
/*初始化日志系统*/
logger::Logger::Init("vehicle_params", "./log");
logger::Logger::Init("vehicle_params", "./nodes_log");
rclcpp::spin(std::make_shared<VehicleParamsNode>());
rclcpp::shutdown();

View File

@ -51,7 +51,7 @@ ament_target_dependencies(your_target
```cpp
// 初始化日志系统
logger::Logger::Init("node_name", "./log");
logger::Logger::Init("node_name", "./nodes_log");
// 业务逻辑...

View File

@ -106,8 +106,16 @@ void Logger::InitLogFile()
struct tm tm_info;
localtime_r(&now_c, &tm_info);
// 按节点名称和日期创建子目录
char sub_dir[256];
snprintf(sub_dir, sizeof(sub_dir), "%s/%s/%04d%02d%02d", log_dir_.c_str(), name_.c_str(),
tm_info.tm_year + 1900, tm_info.tm_mon + 1, tm_info.tm_mday);
// 创建子目录
std::filesystem::create_directories(sub_dir);
char filename[256];
snprintf(filename, sizeof(filename), "%s/%s_%04d%02d%02d_%02d%02d%02d.log", log_dir_.c_str(), name_.c_str(),
snprintf(filename, sizeof(filename), "%s/%s_%04d%02d%02d_%02d%02d%02d.log", sub_dir, name_.c_str(),
tm_info.tm_year + 1900, tm_info.tm_mon + 1, tm_info.tm_mday, tm_info.tm_hour, tm_info.tm_min,
tm_info.tm_sec);

View File

@ -170,7 +170,7 @@ int main(int argc, char** argv)
rclcpp::init(argc, argv);
/*初始化日志系统*/
logger::Logger::Init("mqtt_report", "./log");
logger::Logger::Init("mqtt_report", "./nodes_log");
Config config;

View File

@ -81,7 +81,7 @@ int main(int argc, char** argv)
// 4) ROS2 spin
rclcpp::init(argc, argv);
/*初始化日志系统*/
logger::Logger::Init("sub", "./log");
logger::Logger::Init("sub", "./nodes_log");
LOG_INFO("MQTT address: %s", cfg.address.c_str());
LOG_INFO("MQTT topic template: %s", cfg.remote_topic_template.c_str());

View File

@ -478,7 +478,7 @@ int main(int argc, char** argv)
signal(SIGINT, signalHandler);
// 初始化日志系统
logger::Logger::Init("task_manager", "./log");
logger::Logger::Init("task_manager", "./nodes_log");
// 默认配置路径
std::string config_path = "config.json";

View File

@ -11,11 +11,12 @@
<depend>sweeper_interfaces</depend>
<depend>rclcpp</depend>
<depend>logger</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>
</package>

View File

@ -108,7 +108,7 @@ class ArbitrationNode : public rclcpp::Node
int main(int argc, char* argv[])
{
// 初始化日志系统
logger::Logger::Init("ctrl_arbiter", "./log");
logger::Logger::Init("ctrl_arbiter", "./nodes_log");
rclcpp::init(argc, argv);
auto node = std::make_shared<ArbitrationNode>();

View File

@ -206,7 +206,7 @@ class SBUSNode : public rclcpp::Node
int main(int argc, char* argv[])
{
// 初始化日志系统
logger::Logger::Init("radio_ctrl", "./log");
logger::Logger::Init("radio_ctrl", "./nodes_log");
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<SBUSNode>()); // 启动节点

View File

@ -392,7 +392,7 @@ class RemoteCtrlNode : public rclcpp::Node
int main(int argc, char* argv[])
{
// 初始化日志系统
logger::Logger::Init("remote_ctrl", "./log");
logger::Logger::Init("remote_ctrl", "./nodes_log");
// ===============================
// 1. 默认配置路径 + 手动解析 --config

View File

@ -195,7 +195,7 @@ class rtk_node : public rclcpp::Node
int main(int argc, char** argv)
{
// 初始化日志系统
logger::Logger::Init("rtk", "./log");
logger::Logger::Init("rtk", "./nodes_log");
// unsigned int a = -1;
// LOG_DEBUG("%u\n", a);