mrpt_navigation
mrpt_navigation copied to clipboard
rawlog_play: support for observation_only rawlog?
Hi, I'm trying to play multiple rawlog files with the rawlog_play node, but most of them crash (no error msgs, just the ros node exiting). After some research I believe it may be due to sensory_frame/observation_only rawlog types. Can you kindly confirm that the observation_only rawlog format is supported at the moment?
Aside from that problem, if the input is a rawlog containing only laser_scan observations, why is the rawlog_play publishing the TF: odom_link -> base_link? Is it trying to estimate the odometry from laser_scans?
Thanks
Hi @JGMonroy !
Can you kindly confirm that the observation_only rawlog format is supported at the moment?
As you know, this ROS node was developed by the contributions of different people over time, so I didn't actually know it and had to dig in the code to find out... that it DIDN'T support rawlogs in the obs-only format.
But it was easy to fix, and it should work now after https://github.com/mrpt-ros-pkg/mrpt_navigation/commit/f418d0e8899453237223634cd49d6bb62c3c4568
Please, give it a try. If it still crashes, please run the node with gdb ~/catkin_ws/devel/.../node_executable
, run
, then print the bt
when crashed to see what's wrong.
Aside from that problem, if the input is a rawlog containing only laser_scan observations, why is the rawlog_play publishing the TF: odom_link -> base_link? Is it trying to estimate the odometry from laser_scans?
Didn't checked this one yet but, for sure, it's NOT estimating the pose, so it might be an error in the tf publish code.
Hi @jlblancoc Code merged and compiled, but still no luck (with SF is still working). This is the output of running on debug:
(gdb) run Starting program: /home/jgmonroy/catkin_ws/devel/lib/mrpt_rawlog/rawlog_play_node [Thread debugging using libthread_db enabled] Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1". [New Thread 0x7fffd0273700 (LWP 11506)] [New Thread 0x7fffcf860700 (LWP 11508)] [New Thread 0x7fffcf05f700 (LWP 11509)] [New Thread 0x7fffce85e700 (LWP 11510)] [New Thread 0x7fffce05d700 (LWP 11515)] [ INFO] [1517832169.886303319]: rate: 10.000000 [ INFO] [1517832169.886967663]: parameter_update_skip: 1 [ INFO] [1517832169.887557417]: rawlog_file: /home/jgmonroy/catkin_ws/src/missions_pkg/others/1_hokuyo_processed.rawlog [ INFO] [1517832169.888110168]: odom_frame: odom [ INFO] [1517832169.888830443]: base_frame: base_link [ INFO] [1517832169.889570751]: tf_prefix: [ INFO] [1517832169.890411786]: publish_tf_odom: false [ INFO] [1517832169.890452635]: gaussianModel.a1: 0.034000 [ INFO] [1517832169.890489698]: gaussianModel.a2: 0.057000 [ INFO] [1517832169.890518340]: gaussianModel.a3: 0.014000 [ INFO] [1517832169.890553963]: gaussianModel.a4: 0.097000 [ INFO] [1517832169.890584199]: gaussianModel.minStdXY: 0.005000 [ INFO] [1517832169.890616463]: gaussianModel.minStdPHI: 0.050000 [ INFO] [1517832169.906391900]: debug: false
Thread 1 "rawlog_play_nod" received signal SIGSEGV, Segmentation fault. 0x000000000041a918 in RawlogPlayNode::nextEntry() ()
And the backtrace is: (gdb) bt #0 0x000000000041a918 in RawlogPlayNode::nextEntry() () #1 0x000000000041ae2b in RawlogPlayNode::loop() () #2 0x00000000004193de in main ()
By the way, there is absolutely no rush with this issue. Just thought it may be nice to have support for obs-only rawlogs.
#0 0x000000000041a918 in RawlogPlayNode::nextEntry() ()
Try building all ros nodes with "-g" as CPP flag (you can do it with cmake-gui, advanced vars, setting BUILD_DIR to catkin_ws/build) to see if gdb can show us the exact line number where the error is...
std::cout<<"runhere"<<std::endl; std::cout<<sensor_pose_on_robot<<std::endl; mrpt_bridge::convert(msg, sensor_pose_on_robot, *last_range_scan); std::cout<<"runhere"<<std::endl; Found problem at convert function. after this. there is only error. no return of runhere
Final Segmentation fault located at the update time section in mrpt_bridge. Any1 has any ideal on how to solve it?
Problem solved by complete remove mrpt-bridge. To work with the default mrpt-navigation, some1 need to rewrite mrpt-bridge to link to locally build version of mrpt.
For my current solution. Create new ros node. manually link your own build version of mrpt. then everything works like a charm. here is the sample config. hope can help others
cmake_minimum_required(VERSION 2.8.3) project(xxxxxxxx)
set(CMAKE_BUILD_TYPE "Release") set(CMAKE_CXX_FLAGS "-std=c++11") #-DEIGEN_USE_MKL_ALL") set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -g")
find_package(catkin REQUIRED COMPONENTS roscpp std_msgs roslib geometry_msgs nav_msgs sensor_msgs tf cv_bridge camera_model visualization_msgs )
SET("MRPT_DIR" "/home/snake/library/mrpt-mrpt-1.5/build/") find_package(OpenCV REQUIRED) find_package(MRPT 1.5 REQUIRED gui obs slam hwdrivers base) include_directories(${catkin_INCLUDE_DIRS})
set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake) find_package(Eigen3 REQUIRED) include_directories( ${catkin_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIR} )
catkin_package()
add_executable(xxxxxxxx src/recorder_node.cpp
)
#target_include_directories(xxxxxxxx PUBLIC "/home/snake/library/mrpt-mrpt-1.5/libs" /home/snake/library/mrpt-mrpt-1.5/build/lib) SET("MRPT_INCLUDE_DIRS" "/home/snake/library/mrpt-mrpt-1.5/build/libs") include_directories( ${MRPT_INCLUDE_DIRS})
target_link_libraries(xxxxxxxx ${catkin_LIBRARIES} ${OpenCV_LIBS} ${MRPT_LIBS} )
Closing, as this is now superseded by MOLA's ROS2 bridge, for example. Docs and examples will be added here: https://docs.mola-slam.org/latest/