Poaos / LAEA

LAEA: A 2D LiDAR-Assisted UAV Exploration Algorithm for Unknown Environments
GNU Affero General Public License v3.0
15 stars 0 forks source link

[ WARN] [1720103255.728859210, 14937.430000000]: TF_REPEATED_DATA ignoring data with redundant timestamp for frame world (parent map) at time 14937.460000 according to authority unknown_publisher #2

Closed Yangye0526 closed 2 months ago

Yangye0526 commented 3 months ago

[ WARN] [1720103255.728859210, 14937.430000000]: TF_REPEATED_DATA ignoring data with redundant timestamp for frame world (parent map) at time 14937.460000 according to authority unknown_publisher 一启动explore_test.launch就会报这个错,建图看着好像没啥问题 2fad2e74-709b-4a13-8215-4e33d6dba181 402c614e-29c9-4d78-b52b-2c4d2a4db9d8 一直不动,请问是什么问题呢

Poaos commented 3 months ago

TF_REPEATED_DATA的问题可以rosrun rqt_tf_tree rqt_tf_tree查看一下系统里面的tf树是不是没有正常连接上(检查启动的系列程序是否存在tf关系发布的报错),这个报错有时候可以忽略。 这套算法需要使用mavros_controller接收探索算法的轨迹并解算无人机的控制量,走的mavros通信,所以需要手动切入offboard并解锁。该操作可以在qgc里面操作,也可以使用命令行指令。

[ WARN] [1720103255.728859210, 14937.430000000]: TF_REPEATED_DATA ignoring data with redundant timestamp for frame world (parent map) at time 14937.460000 according to authority unknown_publisher 一启动explore_test.launch就会报这个错,建图看着好像没啥问题 2fad2e74-709b-4a13-8215-4e33d6dba181 402c614e-29c9-4d78-b52b-2c4d2a4db9d8 一直不动,请问是什么问题呢

TF_REPEATED_DATA的问题可以rosrun rqt_tf_tree rqt_tf_tree查看一下系统里面的tf树是不是没有正常连接上(检查启动的系列程序是否存在tf关系发布的报错),这个报错有时候可以忽略(pkill -f roscore* , roscore&,然后重新启动相关程序可能就好了)。 这套算法需要使用mavros_controller接收探索算法的轨迹并解算无人机的控制量,走的mavros通信,所以需要手动切入offboard并解锁。该操作可以在qgc里面操作,也可以使用命令行指令。

# 查看 tf 树发布情况,是否连接正常
rosrun rqt_tf_tree rqt_tf_tree

# 杀掉所有roscore程序,把环境弄干净点
# pkill -f roscore*
# 后台启动roscore,保障程序之间的正常通信
# roscore&

# In another terminal  手动切入offboard并解
rosrun mavros mavsys mode -c OFFBOARD
rosrun mavros mavsafety arm
Yangye0526 commented 3 months ago

我发现我在运行的过程中经常出现#1 Object "/home/yy/exploration_demo/laea_ws/devel/lib/libactive_perception.so", at 0x7f15298f7802, in fast_planner::FrontierFinder::count_Lidar_VisibleCells(Eigen::Matrix<double, 3, 1, 0, 3, 1> const&, double const&, std::vector<Eigen::Matrix<double, 3, 1, 0, 3, 1>, std::allocator<Eigen::Matrix<double, 3, 1, 0, 3, 1> > > const&, int&, Eigen::Matrix<double, 3, 1, 0, 3, 1>&)

0 Object "/home/yy/exploration_demo/laea_ws/devel/lib/libactive_perception.so", at 0x7f152991709e, in Lidar_gain::Get_Multi_Raycast(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, 3, 1>, std::allocator<Eigen::Matrix<double, 3, 1, 0, 3, 1> > >&)

Segmentation fault (Address not mapped to object [(nil)]) [exploration_node-2] process has died [pid 1888891, exit code -11, cmd /home/yy/exploration_demo/laea_ws/devel/lib/exploration_manager/exploration_node /odom_world:=/mavros/local_position/odom /map_ros/pose:=/camera_pose /map_ros/depth:=/camera/depth/image_raw /map_ros/cloud:=/pcl_render_node/cloud /planning/pos_cmd:=position_cmd /projected_map:=/sdf_map/hybrid_2d /planning/travel_traj:=/planning/travel_traj_ours __name:=exploration_node __log:=/home/yy/.ros/log/599e2598-3c22-11ef-ac25-f1155abdff5a/exploration_node-2.log]. log file: /home/yy/.ros/log/599e2598-3c22-11ef-ac25-f1155abdff5a/exploration_node-2*.log 这个报错,不知道问题在哪,运行成功一次但是一直在一个地方打转了 2321744DFC2B172B1E94105227A9A5ED 64A8D3FA1D55032A09E81CDC9BD10391

Poaos commented 3 months ago

我发现我在运行的过程中经常出现#1 Object "/home/yy/exploration_demo/laea_ws/devel/lib/libactive_perception.so", at 0x7f15298f7802, in fast_planner::FrontierFinder::count_Lidar_VisibleCells(Eigen::Matrix<double, 3, 1, 0, 3, 1> const&, double const&, std::vector<Eigen::Matrix<double, 3, 1, 0, 3, 1>, std::allocator<Eigen::Matrix<double, 3, 1, 0, 3, 1> > > const&, int&, Eigen::Matrix<double, 3, 1, 0, 3, 1>&) #0 Object "/home/yy/exploration_demo/laea_ws/devel/lib/libactive_perception.so", at 0x7f152991709e, in Lidar_gain::Get_Multi_Raycast(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, 3, 1>, std::allocator<Eigen::Matrix<double, 3, 1, 0, 3, 1> > >&) Segmentation fault (Address not mapped to object [(nil)]) [exploration_node-2] process has died [pid 1888891, exit code -11, cmd /home/yy/exploration_demo/laea_ws/devel/lib/exploration_manager/exploration_node /odom_world:=/mavros/local_position/odom /map_ros/pose:=/camera_pose /map_ros/depth:=/camera/depth/image_raw /map_ros/cloud:=/pcl_render_node/cloud /planning/pos_cmd:=position_cmd /projected_map:=/sdf_map/hybrid_2d /planning/travel_traj:=/planning/travel_traj_ours __name:=exploration_node __log:=/home/yy/.ros/log/599e2598-3c22-11ef-ac25-f1155abdff5a/exploration_node-2.log]. log file: /home/yy/.ros/log/599e2598-3c22-11ef-ac25-f1155abdff5a/exploration_node-2*.log 这个报错,不知道问题在哪,运行成功一次但是一直在一个地方打转了 2321744DFC2B172B1E94105227A9A5ED 64A8D3FA1D55032A09E81CDC9BD10391

这个报错应该和内存分配有关系,可能是内存不够炸了。目前这套算法是基于FAEP->FUEL的框架修改的,程序本身存在一定的bug,我之前在自己的笔记本上面运行偶尔也会出现类似问题,不过主要是在调用getFullCostMatrix()函数的时候。你这里在调用Get_Multi_Raycast的时候报错我还真没怎么遇到过,我在Ubuntu18和20下基本上是正常运行的,笔记本i5-12500h, 16g内存

hosonhere commented 2 months ago

我也有遇到类似的问题. 我发现Lidar_gain::Get_Multi_Raycast中有呼叫到的Lidar_gain::getOccupancy(const Eigen::Vector3i& id)中, 执行时计算出的idex可能会有问题.

后来我再下面加上 if (idex < 0 || idex >= OccGrid.data.size()) return -1; 就正常了