HKUST-Aerial-Robotics / Fast-Planner

A Robust and Efficient Trajectory Planner for Quadrotors
GNU General Public License v3.0
2.38k stars 661 forks source link

[Topo] Unable to plan through wall object #19

Closed SwiftGust closed 4 years ago

SwiftGust commented 4 years ago

First of all, Fast planner's kino & topo both algorithms are works exceptionally.

However, I found topo planner cannot plan through the flat wall-shaped object, I think the planner wouldn't have much problem finding a bypass path through wall. I don't know problem maybe a simple issue behind or limitation of local map strategy.

  1. Problem in sdf map couldn't update depth properly as picture below,

Screenshot from 2020-04-22 15-32-25

  1. Another problem is path twists then vehicle moves like uncontrolled then program crashes as follows

Peek Program Dies

crash log

[ INFO] [1587540352.802406181]: iter num: 82
plan heading: 0.00013925
[FSM]: from REPLAN_TRAJ to EXEC_TRAJ
[FSM]: from EXEC_TRAJ to REPLAN_TRAJ
[ERROR] [1587540353.298135604]: max vel: 18.056680, max acc: 134.117603.
ratio: 11.5809
[ INFO] [1587540353.298351864]: cost func: smooth | dist  | feasi |
[ INFO] [1587540353.303459633]: iter num: 118
[ WARN] [1587540353.303508063]: [Refine]: cost 0.00540908 seconds, time change is: 49.9948
[ INFO] [1587540353.303544483]: plan yaw
[ INFO] [1587540353.303825133]: cost func: smooth | waypt |
[ INFO] [1587540353.304844822]: iter num: 96
plan heading: 0.00134053
[FSM]: from REPLAN_TRAJ to EXEC_TRAJ
state: EXEC_TRAJ
[ WARN] [1587540353.411409102]: current traj 2.786250 m to collision
[SAFETY]: from EXEC_TRAJ to REPLAN_TRAJ
[ INFO] [1587540353.419981248]: [Topo]: ---------
[Topo]: sample num: 384, raw path num: 1, 1, pruned path num: 1, select path num: 1, pruned path num: 1
[Topo]: total time: 0.00546091, graph: 0.00504886, search: 4.75e-06, short: 0.00019535, prune: 1.1e-06, select: 0.00021085
[ INFO] [1587540353.425513227]: [Optimize]: ---------
[ INFO] [1587540353.425726917]: cost func: smooth | guide |
[ INFO] [1587540353.425825637]: cost func: smooth | dist  | feasi |
[ INFO] [1587540353.430891275]: iter num: 155
[ INFO] [1587540353.430929115]: optimization 0 cost 0.000125, 0.000126, 0.005095 seconds.
[planner]: optimization time: 0.00544329
ratio: 0.82771
[ INFO] [1587540353.431084045]: cost func: smooth | dist  | feasi |
[ WARN] [1587540353.433768794]: [Optimization]: nlopt exception
nlopt failure
[ INFO] [1587540353.433793784]: iter num: 196
[ WARN] [1587540353.433808124]: [Refine]: cost 0.0028037 seconds, time change is: -7.62869
[ INFO] [1587540353.433830364]: plan yaw
[ INFO] [1587540353.433959994]: cost func: smooth | waypt |
[ INFO] [1587540353.434395264]: iter num: 90
plan heading: 0.00057517
[FSM]: from REPLAN_TRAJ to EXEC_TRAJ
[ WARN] [1587540353.461693427]: current traj 4.518979 m to collision
[SAFETY]: from EXEC_TRAJ to REPLAN_TRAJ
[ INFO] [1587540353.464955076]: [Topo]: ---------
[Topo]: sample num: 377, raw path num: 4, 4, pruned path num: 1, select path num: 1, pruned path num: 1
[Topo]: total time: 0.00562946, graph: 0.00506682, search: 8.01e-06, short: 0.00024741, prune: 6.357e-05, select: 0.00024365
[ INFO] [1587540353.470637283]: [Optimize]: ---------
[ INFO] [1587540353.470903393]: cost func: smooth | guide |
[ INFO] [1587540353.471002653]: cost func: smooth | dist  | feasi |
[ INFO] [1587540353.475683792]: iter num: 230
[ INFO] [1587540353.475716072]: optimization 0 cost 0.000167, 0.000127, 0.004708 seconds.
[planner]: optimization time: 0.00510211
ratio: 1.24659
[ INFO] [1587540353.475899912]: cost func: smooth | dist  | feasi |
[ INFO] [1587540353.476831152]: iter num: 65
[ WARN] [1587540353.476859862]: [Refine]: cost 0.00108291 seconds, time change is: 1.33538
[ INFO] [1587540353.476894742]: plan yaw
[ INFO] [1587540353.476950172]: cost func: smooth | waypt |
[ INFO] [1587540353.477057692]: iter num: 70
plan heading: 0.00016601
[FSM]: from REPLAN_TRAJ to EXEC_TRAJ
[ WARN] [1587540353.511636152]: current traj 5.667316 m to collision
[SAFETY]: from EXEC_TRAJ to REPLAN_TRAJ
[ INFO] [1587540353.514968071]: [Topo]: ---------
[Topo]: sample num: 402, raw path num: 2, 2, pruned path num: 1, select path num: 1, pruned path num: 1
[Topo]: total time: 0.00539363, graph: 0.00505092, search: 5.5e-06, short: 0.00018369, prune: 1.691e-05, select: 0.00013661
[ INFO] [1587540353.520402800]: [Optimize]: ---------
[ INFO] [1587540353.520609510]: cost func: smooth | guide |
[ INFO] [1587540353.520718130]: cost func: smooth | dist  | feasi |
[ INFO] [1587540353.523657598]: iter num: 184
[ INFO] [1587540353.523692988]: optimization 0 cost 0.000151, 0.000116, 0.002974 seconds.
[planner]: optimization time: 0.00331785
ratio: 1.19515
[ INFO] [1587540353.523854558]: cost func: smooth | dist  | feasi |
[ INFO] [1587540353.526090387]: iter num: 190
[ WARN] [1587540353.526111657]: [Refine]: cost 0.00236315 seconds, time change is: 1.24586
[ INFO] [1587540353.526134047]: plan yaw
[ INFO] [1587540353.526183077]: cost func: smooth | waypt |
[ INFO] [1587540353.526313267]: iter num: 82
plan heading: 0.00018699
[FSM]: from REPLAN_TRAJ to EXEC_TRAJ
[ WARN] [1587540353.563552466]: current traj 5.646009 m to collision
[SAFETY]: from EXEC_TRAJ to REPLAN_TRAJ
terminate called after throwing an instance of 'std::bad_alloc'
  what():  std::bad_alloc
Stack trace (most recent call last):
#21   Object "[0xffffffffffffffff]", at 0xffffffffffffffff, in
#20   Object "/home/sjo/ws_fast/devel/lib/plan_manage/fast_planner_node", at 0x565555570d19, in _start
#19   Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7efbfc7f7b96, in __libc_start_main
#18   Object "/home/sjo/ws_fast/devel/lib/plan_manage/fast_planner_node", at 0x56555556e3f0, in main
#17   Object "/opt/ros/melodic/lib/libroscpp.so", at 0x7efbfe72187a, in ros::spin()
#16   Object "/opt/ros/melodic/lib/libroscpp.so", at 0x7efbfe738fe8, in ros::SingleThreadedSpinner::spin(ros::CallbackQueue*)
#15   Object "/opt/ros/melodic/lib/libroscpp.so", at 0x7efbfe6e0f7a, in ros::CallbackQueue::callAvailable(ros::WallDuration)
#14   Object "/opt/ros/melodic/lib/libroscpp.so", at 0x7efbfe6dfb8b, in ros::CallbackQueue::callOneCB(ros::CallbackQueue::TLS*)
#13   Object "/opt/ros/melodic/lib/libroscpp.so", at 0x7efbfe6baa86, in ros::TimerManager<ros::Time, ros::Duration, ros::TimerEvent>::TimerQueueCallback::call()
#12   Object "/home/sjo/ws_fast/devel/lib/plan_manage/fast_planner_node", at 0x565555588955, in fast_planner::TopoReplanFSM::execFSMCallback(ros::TimerEvent const&)
#11   Object "/home/sjo/ws_fast/devel/lib/plan_manage/fast_planner_node", at 0x565555587ab4, in fast_planner::TopoReplanFSM::callTopologicalTraj(int)
#10   Object "/home/sjo/ws_fast/devel/lib/plan_manage/fast_planner_node", at 0x5655555931f7, in fast_planner::FastPlannerManager::topoReplan(bool)
#9    Object "/home/sjo/ws_fast/devel/lib/plan_manage/fast_planner_node", at 0x565555591342, in fast_planner::FastPlannerManager::reparamLocalTraj(double, double&, double&)
#8    Object "/home/sjo/ws_fast/devel/lib/libbspline.so", at 0x7efbfee6ee48, in fast_planner::NonUniformBspline::parameterizeToBspline(double const&, std::vector<Eigen::Matrix<double, 3, 1, 0, 3, 1>, std::allocator<Eigen::Matrix<double, 3, 1, 0, 3, 1> > > const&, std::vector<Eigen::Matrix<double, 3, 1, 0, 3, 1>, std::allocator<Eigen::Matrix<double, 3, 1, 0, 3, 1> > > const&, Eigen::Matrix<double, -1, -1, 0, -1, -1>&)
#7    Object "/home/sjo/ws_fast/devel/lib/plan_manage/fast_planner_node", at 0x565555597c0f, in Eigen::PlainObjectBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> >::resize(long, long)
#6    Object "/home/sjo/ws_fast/devel/lib/plan_manage/fast_planner_node", at 0x56555559459d, in Eigen::internal::throw_std_bad_alloc()
#5    Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7efbfd20fd53, in __cxa_throw
#4    Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7efbfd20fb20, in std::terminate()
#3    Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7efbfd20fae5, in
#2    Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7efbfd209956, in
#1    Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7efbfc816800, in abort
#0    Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7efbfc814e97, in gsignal
Aborted (Signal sent by tkill() 23295 1000)
[fast_planner_node-2] process has died [pid 23295, exit code -6, cmd /home/sjo/ws_fast/devel/lib/plan_manage/fast_planner_node /odom_world:=/state_ukf/odom /sdf_map/odom:=/state_ukf/odom /sdf_map/cloud:=/map_generator/global_cloud_no_use /sdf_map/pose:=/pcl_render_node/camera_pose /sdf_map/depth:=/pcl_render_node/depth __name:=fast_planner_node __log:=/home/sjo/.ros/log/735868d2-846a-11ea-99e5-00d8617c19f3/fast_planner_node-2.log].
log file: /home/sjo/.ros/log/735868d2-846a-11ea-99e5-00d8617c19f3/fast_planner_node-2*.log

To Reproduce

I made wall object with tiny modification on polar object generation code in map_generator package as follow

original

https://github.com/HKUST-Aerial-Robotics/Fast-Planner/blob/d1dd6e7ee856819d8993c7a9f8d78fcdadb2dfe7/uav_simulator/map_generator/src/random_forest_sensing.cpp#L96

modifed for wall object

    for (int r = -5; r < 5; r++)

For reproduction, use launch files attached. topo-wall.zip

ZbyLGsc commented 4 years ago

The reason is, we restrict the y axis of the local map to be within the range of [-10, 10]. Your wall seems to be outside the range so obstacle will not be mapped in the local map. So you can try setting the range of y. I do think the Planner can avoid it if the map is correct, although the reference path is so poor.

ZbyLGsc commented 4 years ago

Also, I think I need to clarify that Topo Planner is not designed to be used in such a way. If you read the related paper, a global reference path is required and the task of the Topo Planner is to plan locally to avoid obstacles around the reference path. If the reference path is too ridiculous (as is the one you give, which differs so much from the real feasible path), the planner may fail to replan.

In other word, Topo Planner is designed to follow a predefined reference path safely. For example, in some inspection tasks like in a big warehouse, it may require the drone to go along a reference path predefined by the warehouse manager, and the drone monitors/inspects somethings. The Topo Planner gets the global path as INPUT and plans trajectories avoiding unexpected obstacles (such as AGV and human in warehouse). The 'click-and-go' demo, wherein the reference path is simply a straight line, may be misleading somehow. I will refine the document and explain it more clearly later.

SwiftGust commented 4 years ago

@ZbyLGsc Hi, thank you for quick response. To summarize your response, the problem is giving a single global waypoint for reference path generation. To vehicle to avoid large-scale object, Topo planner needs some waypoints to it to avoid obstacle.

For instance having two global waypoints to avoid thin wall then Topo Planner would be able to avoid obstacle like picture below

image

If so, It would be good to have some logic for automatic generation of mid-waypoint but for me, it seems difficult without human intervention.

For the mapping issue, I missed local map size of y is +- 10 m, then the first problem is solved. However, path twist and program crash still persist. I think the program crash issue may need to be addressed.

Thank you for clarification.

ZbyLGsc commented 4 years ago

@SwiftGust Yes, given the KNOWN global map, it will be better to find a more informative global path, such as using A / RRT. However, I would emphasize again that this is not the task of Topo Planner.

For the path twisting, I have found it before but the bug seems very difficult to identify. I would fix it once I know the reason.