Skip to content

Commit

Permalink
Update global_planner.h
Browse files Browse the repository at this point in the history
  • Loading branch information
HuaYuXiao authored Mar 6, 2024
1 parent 4fe54eb commit 2913075
Showing 1 changed file with 2 additions and 21 deletions.
23 changes: 2 additions & 21 deletions include/global_planner.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,21 +43,11 @@ class Global_Planner

// 参数
int algorithm_mode;
bool is_2D;
double fly_height_2D;
double safe_distance;
double time_per_path;
int map_input;
double replan_time;
bool consider_neighbour;
bool sim_mode;
bool map_groundtruth;

// 本机位置
// 邻机位置
// 根据不同的输入(激光雷达输入、相机输入等)生成occupymap
// 调用路径规划算法 生成路径
// 调用轨迹优化算法 规划轨迹

// 订阅无人机状态、目标点、传感器数据(生成地图)
ros::Subscriber goal_sub;
Expand All @@ -70,21 +60,14 @@ class Global_Planner
//

// 发布控制指令
ros::Publisher command_pub,path_cmd_pub;
ros::Publisher command_pub;
ros::Timer mainloop_timer, track_path_timer, safety_timer;

// A星规划器
Astar::Ptr Astar_ptr;

prometheus_msgs::DroneState _DroneState;
nav_msgs::Odometry Drone_odom;

nav_msgs::Path path_cmd;
double distance_walked;
prometheus_msgs::ControlCommand Command_Now;

double distance_to_goal;

// 规划器状态
bool odom_ready;
bool drone_ready;
Expand All @@ -100,8 +83,6 @@ class Global_Planner
// 规划初始状态及终端状态
Eigen::Vector3d start_pos, start_vel, start_acc, goal_pos, goal_vel;

float desired_yaw;

ros::Time tra_start_time;
float tra_running_time;

Expand Down Expand Up @@ -145,4 +126,4 @@ class Global_Planner

}

#endif
#endif

0 comments on commit 2913075

Please sign in to comment.