HKUST-Aerial-Robotics / Fast-Planner

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

Problem occurs when trying to limit the velocity(setting the max_vel parameter) #64

Closed BlueeHole closed 3 years ago

BlueeHole commented 3 years ago

Hello, sorry to bother, but I encountered with a disgusting problem.

The original max_vel parameter is 3.0, everything is ok. But when I set the max_vel parameter to 0.5, kino_replan will report: kino search fail( open set empty, no path! ), while topo_replan will crash, reporting a Segmentation fault. The output is below:

[SAFETY]: from EXEC_TRAJ to REPLAN_TRAJ                                                                                                                                                                            
Stack trace (most recent call last):                                                                                                                                                                               
#12   Object "[0xffffffffffffffff]", at 0xffffffffffffffff, in                                                                                                                                                     
#11   Object "/home/mofei/3_ROS/fast_planner/devel/lib/plan_manage/fast_planner_node", at 0x55bddeeb5be9, in _start                                                                                                
#10   Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fde03f7fb96, in __libc_start_main                                                                                                                            
#9    Object "/home/mofei/3_ROS/fast_planner/devel/lib/plan_manage/fast_planner_node", at 0x55bddeeb32d0, in main                                                                                                  
#8    Object "/opt/ros/melodic/lib/libroscpp.so", at 0x7fde05ea542a, in ros::spin()                                                                                                                                
#7    Object "/opt/ros/melodic/lib/libroscpp.so", at 0x7fde05ebcb48, in ros::SingleThreadedSpinner::spin(ros::CallbackQueue*)                                                                                      
#6    Object "/opt/ros/melodic/lib/libroscpp.so", at 0x7fde05e6561a, in ros::CallbackQueue::callAvailable(ros::WallDuration)
#5    Object "/opt/ros/melodic/lib/libroscpp.so", at 0x7fde05e638a8, in ros::CallbackQueue::callOneCB(ros::CallbackQueue::TLS*)
#4    Object "/opt/ros/melodic/lib/libroscpp.so", at 0x7fde05e3e846, in ros::TimerManager<ros::Time, ros::Duration, ros::TimerEvent>::TimerQueueCallback::call()
#3    Object "/home/mofei/3_ROS/fast_planner/devel/lib/plan_manage/fast_planner_node", at 0x55bddeecd9b5, in fast_planner::TopoReplanFSM::execFSMCallback(ros::TimerEvent const&)
#2    Object "/home/mofei/3_ROS/fast_planner/devel/lib/plan_manage/fast_planner_node", at 0x55bddeeccb14, in fast_planner::TopoReplanFSM::callTopologicalTraj(int)
#1    Object "/home/mofei/3_ROS/fast_planner/devel/lib/plan_manage/fast_planner_node", at 0x55bddeed833c, in fast_planner::FastPlannerManager::topoReplan(bool)
#0    Object "/home/mofei/3_ROS/fast_planner/devel/lib/plan_manage/fast_planner_node", at 0x55bddeed5775, in fast_planner::FastPlannerManager::findCollisionRange(std::vector<Eigen::Matrix<double, 3, 1, 0, 3, 1>, std::allocator<Eigen::Matrix<double, 3, 1, 0, 3, 1> > >&, std::vector<Eigen::Matrix<double, 3, 1, 0, 3, 1>, std::allocator<Eigen::Matrix<double, 3, 1, 0, 3, 1> > >&, std::vector<Eigen::Matrix<double, 3, 1, 0, $, 1>, std::allocator<Eigen::Matrix<double, 3, 1, 0, 3, 1> > >&, std::vector<Eigen::Matrix<double, 3, 1, 0, 3, 1>, std::allocator<Eigen::Matrix<double, 3, 1, 0, 3, 1> > >&)
Segmentation fault (Address not mapped to object [0x1530])
[fast_planner_node-2] process has died [pid 4709, exit code -11, cmd /home/mofei/3_ROS/fast_planner/devel/lib/plan_manage/fast_planner_node /odom_world:=/state_ukf/odom /sdf_map/odom:=/state_ukf/odom /sdf_map/cloud:=/pcl_render_node/cloud /sdf_map/pose:=/pcl_render_node/camera_pose /sdf_map/depth:=/pcl_render_node/depth __name:=fast_planner_node __log:=/home/mofei/.ros/log/4c58bd3c-1bef-11eb-88b1-04d3b0a0e0c9/fast_planner_node-2.log].
log file: /home/mofei/.ros/log/4c58bd3c-1bef-11eb-88b1-04d3b0a0e0c9/fast_planner_node-2*.log

(This is the origin version: only on simulation using rviz, no mavros and no other things)

Any solutions will be appreciated.Thanks a lot !

ZbyLGsc commented 3 years ago

If you reduce the velocity limit to a small value, remember also to reduce the acceleration, otherwise there may not be feasible states.

BlueeHole commented 3 years ago

If you reduce the velocity limit to a small value, remember also to reduce the acceleration, otherwise there may not be feasible states.

Thank you very much! I've retried and it sometimes works. However it's a little hard to adjust the velocity and acceleration by a proper degree at the same time.…

ZbyLGsc commented 3 years ago

May be you also need to change the search/resolution to a smaller value, to ensure that the motion primitives do not end up in the same voxel.

BlueeHole commented 3 years ago

May be you also need to change the search/resolution to a smaller value, to ensure that the motion primitives do not end up in the same voxel.

Thank you very much ! I will take consideration of it.