Skip to content

Commit

Permalink
Update map_input, convert int to bool type.
Browse files Browse the repository at this point in the history
  • Loading branch information
HuaYuXiao committed Mar 7, 2024
1 parent 796e23a commit 381b92b
Show file tree
Hide file tree
Showing 3 changed files with 28 additions and 32 deletions.
2 changes: 1 addition & 1 deletion include/global_planner.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ class Global_Planner{
ros::NodeHandle nodehandle;

// 参数
int map_input;
bool map_input;
bool sim_mode;
bool map_groundtruth;

Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>octomapping</name>
<version>0.0.4</version>
<version>0.1.2</version>
<description>A ROS package targeted for building 3D octomap on Premetheus P450 (Nano)</description>

<maintainer email="hyx020222@gmail.com">Eason Hua</maintainer>
Expand Down
56 changes: 26 additions & 30 deletions src/global_planner.cpp
Original file line number Diff line number Diff line change
@@ -1,34 +1,32 @@
#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);


// 订阅 无人机状态
drone_state_sub = nodehandle.subscribe<prometheus_msgs::DroneState>("/prometheus/drone_state", 10, &Global_Planner::drone_state_cb, this);

// 根据map_input选择地图更新方式
if(map_input == 0)
{
if(map_input){
Gpointcloud_sub = nodehandle.subscribe<sensor_msgs::PointCloud2>("/prometheus/global_planning/global_pcl", 1, &Global_Planner::Gpointcloud_cb, this);
}else if(map_input == 1)
{
Lpointcloud_sub = nodehandle.subscribe<sensor_msgs::PointCloud2>("/prometheus/global_planning/local_pcl", 1, &Global_Planner::Lpointcloud_cb, this);
}else if(map_input == 2)
{
}else{
laserscan_sub = nodehandle.subscribe<sensor_msgs::LaserScan>("/prometheus/global_planning/laser_scan", 1, &Global_Planner::laser_cb, this);
}


// 发布提示消息
message_pub = nodehandle.advertise<prometheus_msgs::Message>("/prometheus/message/global_planner", 10);


// 定时器 规划器算法执行周期
mainloop_timer = nodehandle.createTimer(ros::Duration(1.5), &Global_Planner::mainloop_cb, this);
// 路径追踪循环,快速移动场景应当适当提高执行频率
Expand Down Expand Up @@ -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;
}
}
}

}


Expand All @@ -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)
Expand All @@ -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)
{
Expand Down

0 comments on commit 381b92b

Please sign in to comment.