demo_depth_camera_2d.launch and turtlebot_depth_camera_2d.launch fail to launch
nfopma opened this issue · comments
Thanks for the great package! It looks very promising and I can not wait to get it to work on my Turtlebot.
Unfortunately, for the last 2 days I have been struggling with the actual deployment. I followed the instructions of installing cartographer_ros and installing cartographer_turtlebot. I am able to run all of the demo's, except for demo_depth_camera_2d.launch. I am using Ubuntu 16.04 and ROS kinetic.
I seem to be getting the exact same errors when I try to launch turtlebot_depth_camera_2d.launch. Launching turtlebot_depth_camera_3d.launch works perfectly without errors, and I can see the 3D map being built in Rviz when I drive around the Turtlebot. Therefore, the problem seems to be specifically about the 2D mapping.
I put the terminal output I get in two txt files.
cartographer_terminal_output_2d_turtlebot.txt
cartographer_terminal_output_2d_demo.txt
For both files, the following is highlighted in red in the terminal:
[FATAL] [1528462899.578349680]: F0608 15:01:39.000000 16788 lua_parameter_dictionary.cc:410] Check failed: 1 == reference_counts_.count(key) (1 vs. 0) Key 'resolution' was used the wrong number of times.
And:
[cartographer_node-2] process has died [pid 16788, exit code -6, cmd /home/nathan/ros_ws/install_isolated/lib/cartographer_ros/cartographer_node -configuration_directory /home/nathan/ros_ws/install_isolated/share/cartographer_turtlebot/configuration_files -configuration_basename turtlebot_depth_camera_2d.lua __name:=cartographer_node __log:=/home/nathan/.ros/log/14f00552-6b1c-11e8-b200-a45e60d3ab15/cartographer_node-2.log]. log file: /home/nathan/.ros/log/14f00552-6b1c-11e8-b200-a45e60d3ab15/cartographer_node-2*.log
The launchfiles for 2D are very similar to 3D. The only difference seems to be the the passing of turtlebot_depth_camera_2d.lua vs. the passing of turtlebot_depth_camera_3d.lua
.
If anyone could help me with understanding and work towards solving this error I would greatly appreciate it!
Comment out
https://github.com/googlecartographer/cartographer_turtlebot/blob/f26a7246f0e2774e8f9658d8178a7a77420c22e6/cartographer_turtlebot/configuration_files/turtlebot_depth_camera_2d.lua#L57
and
https://github.com/googlecartographer/cartographer_turtlebot/blob/f26a7246f0e2774e8f9658d8178a7a77420c22e6/cartographer_turtlebot/configuration_files/turtlebot_depth_camera_3d.lua#L59-L60
Then build and install the code by doing a catkin_make_isolated --install --use-ninja
in the ros workspace, then source the workspace. run the launch file again, it should work!
Are the 3D parameters used in the 2d demo?
@gavanderhoorn I don't think so. But commenting out those params helped me run the 3D demo as well.
Thanks for the reply @SubMishMar!
I tried to remove the resolution parameter from the configuration file, but when I run the depth camera 2D demo with the provided bag I get the following mapping result:
Compared to the presumed correct mapping when running the LIDAR demo:
Did you have different results?
@nfopma I get the same results as you do. The result with 2D depth is not great and with LIDAR it gets a lot better.
@nfopma actually tuning the configuration file can improve the result. Try increasing the weight-age of translation and reduce it for rotation. I changed these in the lua config file for 2d case.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 1e10 TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 1
You may have to change some other things but you will discover it if you as you play more with your dataset.
Fixed by #95
Unfortunately, the proposed changes did not significantly improve the results that I got when I ran the 2d depth camera demo.