From 381b92bee24df04fb7dfbfb82bfb67c2506c4b08 Mon Sep 17 00:00:00 2001 From: Yuxiao Hua <1628280289@qq.com> Date: Thu, 7 Mar 2024 10:23:07 +0800 Subject: [PATCH] Update `map_input`, convert `int` to `bool` type. --- include/global_planner.h | 2 +- package.xml | 2 +- src/global_planner.cpp | 56 +++++++++++++++++++--------------------- 3 files changed, 28 insertions(+), 32 deletions(-) diff --git a/include/global_planner.h b/include/global_planner.h index 65b9543..48bc743 100644 --- a/include/global_planner.h +++ b/include/global_planner.h @@ -39,7 +39,7 @@ class Global_Planner{ ros::NodeHandle nodehandle; // 参数 - int map_input; + bool map_input; bool sim_mode; bool map_groundtruth; diff --git a/package.xml b/package.xml index 55848ef..304188b 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ octomapping - 0.0.4 + 0.1.2 A ROS package targeted for building 3D octomap on Premetheus P450 (Nano) Eason Hua diff --git a/src/global_planner.cpp b/src/global_planner.cpp index e0b0f60..a2ebb85 100644 --- a/src/global_planner.cpp +++ b/src/global_planner.cpp @@ -1,14 +1,14 @@ #include "global_planner.h" + namespace Global_Planning{ // 初始化函数 void Global_Planner::init(ros::NodeHandle& nodehandle){ - // 选择地图更新方式: 0代表全局点云,1代表局部点云,2代表激光雷达scan数据 - nodehandle.param("global_planner/map_input", map_input, 0); + // 选择地图更新方式: true代表全局点云,false代表激光雷达scan数据 + nodehandle.param("global_planner/map_input", map_input, true); // 是否为仿真模式 - nodehandle.param("global_planner/sim_mode", sim_mode, false); - + nodehandle.param("global_planner/sim_mode", sim_mode, false); nodehandle.param("global_planner/map_groundtruth", map_groundtruth, false); @@ -16,19 +16,17 @@ void Global_Planner::init(ros::NodeHandle& nodehandle){ drone_state_sub = nodehandle.subscribe("/prometheus/drone_state", 10, &Global_Planner::drone_state_cb, this); // 根据map_input选择地图更新方式 - if(map_input == 0) - { + if(map_input){ Gpointcloud_sub = nodehandle.subscribe("/prometheus/global_planning/global_pcl", 1, &Global_Planner::Gpointcloud_cb, this); - }else if(map_input == 1) - { - Lpointcloud_sub = nodehandle.subscribe("/prometheus/global_planning/local_pcl", 1, &Global_Planner::Lpointcloud_cb, this); - }else if(map_input == 2) - { + }else{ laserscan_sub = nodehandle.subscribe("/prometheus/global_planning/laser_scan", 1, &Global_Planner::laser_cb, this); } + // 发布提示消息 message_pub = nodehandle.advertise("/prometheus/message/global_planner", 10); + + // 定时器 规划器算法执行周期 mainloop_timer = nodehandle.createTimer(ros::Duration(1.5), &Global_Planner::mainloop_cb, this); // 路径追踪循环,快速移动场景应当适当提高执行频率 @@ -81,40 +79,36 @@ void Global_Planner::drone_state_cb(const prometheus_msgs::DroneStateConstPtr& m Drone_odom.twist.twist.linear.z = _DroneState.velocity[2]; } + + // 根据全局点云更新地图 // 情况:已知全局点云的场景、由SLAM实时获取的全局点云 -void Global_Planner::Gpointcloud_cb(const sensor_msgs::PointCloud2ConstPtr &msg) -{ +void Global_Planner::Gpointcloud_cb(const sensor_msgs::PointCloud2ConstPtr &msg){ /* need odom_ for center radius sensing */ - if (!odom_ready) - { + if (!odom_ready){ return; } - + sensor_ready = true; - if(!map_groundtruth) - { + if(!map_groundtruth){ // 对Astar中的地图进行更新 Astar_ptr->Occupy_map_ptr->map_update_gpcl(msg); // 并对地图进行膨胀 - Astar_ptr->Occupy_map_ptr->inflate_point_cloud(); - }else - { + Astar_ptr->Occupy_map_ptr->inflate_point_cloud(); + }else{ static int update_num=0; update_num++; // 此处改为根据循环时间计算的数值 - if(update_num == 10) - { + if(update_num == 10){ // 对Astar中的地图进行更新 Astar_ptr->Occupy_map_ptr->map_update_gpcl(msg); // 并对地图进行膨胀 - Astar_ptr->Occupy_map_ptr->inflate_point_cloud(); + Astar_ptr->Occupy_map_ptr->inflate_point_cloud(); update_num = 0; - } + } } - } @@ -123,19 +117,20 @@ void Global_Planner::Gpointcloud_cb(const sensor_msgs::PointCloud2ConstPtr &msg) void Global_Planner::laser_cb(const sensor_msgs::LaserScanConstPtr &msg) { /* need odom_ for center radius sensing */ - if (!odom_ready) + if (!odom_ready) { return; } - + sensor_ready = true; // 对Astar中的地图进行更新(laser+odom) Astar_ptr->Occupy_map_ptr->map_update_laser(msg, Drone_odom); // 并对地图进行膨胀 - Astar_ptr->Occupy_map_ptr->inflate_point_cloud(); + Astar_ptr->Occupy_map_ptr->inflate_point_cloud(); } + void Global_Planner::track_path_cb(const ros::TimerEvent& e) { if(!path_ok) @@ -150,7 +145,8 @@ void Global_Planner::track_path_cb(const ros::TimerEvent& e) int i = cur_id; } - + + // 主循环 void Global_Planner::mainloop_cb(const ros::TimerEvent& e) {