
cd ~/ros2_ws/src
git clone https://github.com/cartographer-project/cartographer.git
git clone -b ros2 https://github.com/cartographer-project/cartographer_ros.git
cd ~/ros2_ws
rosdep update
rosdep install --from-paths src --ignore-src -r -y


CMakeLists.txt error_ final edit
cmake_minimum_required(VERSION 3.5)
project(my_robot)
# Default to C99
if(NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 99)
endif()
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(cartographer_ros REQUIRED)
# find_package(launch REQUIRED) # 이전에 주석 처리
# find_package(launch_ros REQUIRED) # 이전에 주석 처리
# find_package(ament_index_python REQUIRED) # 주석 처리 또는 제거
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all sources.
# set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
# set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
install(DIRECTORY launch config
DESTINATION share/${PROJECT_NAME}
)
ament_package()

anyway above setting doesn't work
so, change to this
sudo apt install ros-foxy-cartographer ros-foxy-cartographer-ros
cd ~/ros2_ws/src
ros2 pkg create --build-type ament_cmake my_robot
nano ~/ros2_ws/src/my_robot/config/my_robot.lua
write lua file
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map",
tracking_frame = "base_link",
published_frame = "base_link",
odom_frame = "odom",
provide_odom_frame = false,
use_odometry = false,
use_nav_sat = false,
use_landmarks = false,
publish_frame_projected_to_2d = false,
num_laser_scans = 1,
num_multi_echo_laser_scans = 0,
num_subdivisions_per_laser_scan = 1,
num_point_clouds = 0,
use_imu_data = false,
}
MAP_BUILDER.use_trajectory_builder_2d = true
TRAJECTORY_BUILDER_2D.min_range = 0.1
TRAJECTORY_BUILDER_2D.max_range = 12.0
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 5.0
TRAJECTORY_BUILDER_2D.use_imu_data = false
TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 1
return options
make launch directory
mkdir -p ~/ros2_ws/src/my_robot/launch
nano launch.py
~/ros2_ws/src/my_robot/launch/cartographer_launch.py
py script
from launch import LaunchDescription
from launch_ros.actions import Node
import os
from ament_index_python.packages import get_package_share_directory
def generate_launch_description():
cartographer_config_dir = os.path.join(
get_package_share_directory('my_robot'),
'config')
configuration_basename = 'my_robot.lua'
cartographer_node = Node(
package='cartographer_ros',
executable='cartographer_node',
name='cartographer_node',
output='screen',
arguments=[
'-configuration_directory', cartographer_config_dir,
'-configuration_basename', configuration_basename
],
)
occupancy_grid_node = Node(
package='cartographer_ros',
executable='occupancy_grid_node',
name='occupancy_grid_node',
output='screen',
parameters=[{'resolution': 0.05}],
)
return LaunchDescription([
cartographer_node,
occupancy_grid_node,
])
move to package.xml
nano ~/ros2_ws/src/my_robot/package.xml
edit package.xml
<?xml version="1.0"?>
<package format="3">
<name>my_robot</name>
<version>0.0.1</version>
<description>My robot package for Cartographer SLAM</description>
<maintainer email="your_email@example.com">Your Name</maintainer>
<license>Apache License 2.0</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<depend>cartographer_ros</depend>
<!-- launch 및 launch_ros apt로 설치했기에 launch 의존성은 제거 -->
<!-- <depend>launch</depend> -->
<!-- <depend>launch_ros</depend> -->
<exec_depend>ament_index_python</exec_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>
lastly, nano CMakeList.txt
nano ~/ros2_ws/src/my_robot/CMakeLists.txt
edit
cmake_minimum_required(VERSION 3.5)
project(my_robot)
# Default to C99
if(NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 99)
endif()
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(cartographer_ros REQUIRED)
# find_package(launch REQUIRED) # 이전에 주석 처리
# find_package(launch_ros REQUIRED) # 이전에 주석 처리
# find_package(ament_index_python REQUIRED) # 주석 처리 또는 제거
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all sources.
# set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
# set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
install(DIRECTORY launch config
DESTINATION share/${PROJECT_NAME}
)
ament_package()
pkg build (failed)
cd ~/ros2_ws
colcon build --packages-select my_robot
sourcing
source install/setup.bash
maybe pkg error. mainly cmake.file
Please tell me if anyone reading this is wrong with my cmake file
I command node launch
ros2 launch my_robot cartographer_launch.py
Errored like below
jetson@nano:~/ros2_ws$ ros2 launch my_robot cartographer_launch.py
[INFO] [launch]: All log files can be found below /home/jetson/.ros/log/2024-11-19-12-49-12-384947-nano-31197
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [cartographer_node-1]: process started with pid [31201]
[INFO] [occupancy_grid_node-2]: process started with pid [31203]
[cartographer_node-1] [INFO] [1732016953.472371842] [cartographer_ros]: I1119 12:49:13.000000 31201 configuration_file_resolver.cc:41] Found '/home/jetson/ros2_ws/install/my_robot/share/my_robot/config/my_robot.lua' for 'my_robot.lua'.
[cartographer_node-1] [INFO] [1732016953.474002963] [cartographer_ros]: I1119 12:49:13.000000 31201 configuration_file_resolver.cc:41] Found '/opt/ros/foxy/share/cartographer/configuration_files/map_builder.lua' for 'map_builder.lua'.
[cartographer_node-1] [INFO] [1732016953.474122861] [cartographer_ros]: I1119 12:49:13.000000 31201 configuration_file_resolver.cc:41] Found '/opt/ros/foxy/share/cartographer/configuration_files/map_builder.lua' for 'map_builder.lua'.
[cartographer_node-1] [INFO] [1732016953.474774955] [cartographer_ros]: I1119 12:49:13.000000 31201 configuration_file_resolver.cc:41] Found '/opt/ros/foxy/share/cartographer/configuration_files/pose_graph.lua' for 'pose_graph.lua'.
[cartographer_node-1] [INFO] [1732016953.474862405] [cartographer_ros]: I1119 12:49:13.000000 31201 configuration_file_resolver.cc:41] Found '/opt/ros/foxy/share/cartographer/configuration_files/pose_graph.lua' for 'pose_graph.lua'.
[cartographer_node-1] [INFO] [1732016953.475648460] [cartographer_ros]: I1119 12:49:13.000000 31201 configuration_file_resolver.cc:41] Found '/opt/ros/foxy/share/cartographer/configuration_files/trajectory_builder.lua' for 'trajectory_builder.lua'.
[cartographer_node-1] [INFO] [1732016953.475746222] [cartographer_ros]: I1119 12:49:13.000000 31201 configuration_file_resolver.cc:41] Found '/opt/ros/foxy/share/cartographer/configuration_files/trajectory_builder.lua' for 'trajectory_builder.lua'.
[cartographer_node-1] [INFO] [1732016953.476272324] [cartographer_ros]: I1119 12:49:13.000000 31201 configuration_file_resolver.cc:41] Found '/opt/ros/foxy/share/cartographer/configuration_files/trajectory_builder_2d.lua' for 'trajectory_builder_2d.lua'.
[cartographer_node-1] [INFO] [1732016953.476366597] [cartographer_ros]: I1119 12:49:13.000000 31201 configuration_file_resolver.cc:41] Found '/opt/ros/foxy/share/cartographer/configuration_files/trajectory_builder_2d.lua' for 'trajectory_builder_2d.lua'.
[cartographer_node-1] [INFO] [1732016953.477082025] [cartographer_ros]: I1119 12:49:13.000000 31201 configuration_file_resolver.cc:41] Found '/opt/ros/foxy/share/cartographer/configuration_files/trajectory_builder_3d.lua' for 'trajectory_builder_3d.lua'.
[cartographer_node-1] [INFO] [1732016953.477176037] [cartographer_ros]: I1119 12:49:13.000000 31201 configuration_file_resolver.cc:41] Found '/opt/ros/foxy/share/cartographer/configuration_files/trajectory_builder_3d.lua' for 'trajectory_builder_3d.lua'.
[cartographer_node-1] F1119 12:49:13.478155 31201 lua_parameter_dictionary.cc:399] Check failed: HasKey(key) Key 'lookup_transform_timeout_sec' not in dictionary:
[cartographer_node-1] {
[cartographer_node-1] map_builder = {
[cartographer_node-1] num_background_threads = 4.000000,
[cartographer_node-1] pose_graph = {
[cartographer_node-1] constraint_builder = {
[cartographer_node-1] ceres_scan_matcher = {
[cartographer_node-1] ceres_solver_options = {
[cartographer_node-1] max_num_iterations = 10.000000,
[cartographer_node-1] num_threads = 1.000000,
[cartographer_node-1] use_nonmonotonic_steps = true,
[cartographer_node-1] },
[cartographer_node-1] occupied_space_weight = 20.000000,
[cartographer_node-1] rotation_weight = 1.000000,
[cartographer_node-1] translation_weight = 10.000000,
[cartographer_node-1] },
[cartographer_node-1] ceres_scan_matcher_3d = {
[cartographer_node-1] ceres_solver_options = {
[cartographer_node-1] max_num_iterations = 10.000000,
[cartographer_node-1] num_threads = 1.000000,
[cartographer_node-1] use_nonmonotonic_steps = false,
[cartographer_node-1] },
[cartographer_node-1] occupied_space_weight_0 = 5.000000,
[cartographer_node-1] occupied_space_weight_1 = 30.000000,
[cartographer_node-1] only_optimize_yaw = false,
[cartographer_node-1] rotation_weight = 1.000000,
[cartographer_node-1] translation_weight = 10.000000,
[cartographer_node-1] },
[cartographer_node-1] fast_correlative_scan_matcher = {
[cartographer_node-1] angular_search_window = 0.523599,
[cartographer_node-1] branch_and_bound_depth = 7.000000,
[cartographer_node-1] linear_search_window = 7.000000,
[cartographer_node-1] },
[cartographer_node-1] fast_correlative_scan_matcher_3d = {
[cartographer_node-1] angular_search_window = 0.261799,
[cartographer_node-1] branch_and_bound_depth = 8.000000,
[cartographer_node-1] full_resolution_depth = 3.000000,
[cartographer_node-1] linear_xy_search_window = 5.000000,
[cartographer_node-1] linear_z_search_window = 1.000000,
[cartographer_node-1] min_low_resolution_score = 0.550000,
[cartographer_node-1] min_rotational_score = 0.770000,
[cartographer_node-1] },
[cartographer_node-1] global_localization_min_score = 0.600000,
[cartographer_node-1] log_matches = true,
[cartographer_node-1] loop_closure_rotation_weight = 100000.000000,
[cartographer_node-1] loop_closure_translation_weight = 11000.000000,
[cartographer_node-1] max_constraint_distance = 15.000000,
[cartographer_node-1] min_score = 0.550000,
[cartographer_node-1] sampling_ratio = 0.300000,
[cartographer_node-1] },
[cartographer_node-1] global_constraint_search_after_n_seconds = 10.000000,
[cartographer_node-1] global_sampling_ratio = 0.003000,
[cartographer_node-1] log_residual_histograms = true,
[cartographer_node-1] matcher_rotation_weight = 1600.000000,
[cartographer_node-1] matcher_translation_weight = 500.000000,
[cartographer_node-1] max_num_final_iterations = 200.000000,
[cartographer_node-1] optimization_problem = {
[cartographer_node-1] acceleration_weight = 1000.000000,
[cartographer_node-1] ceres_solver_options = {
[cartographer_node-1] max_num_iterations = 50.000000,
[cartographer_node-1] num_threads = 7.000000,
[cartographer_node-1] use_nonmonotonic_steps = false,
[cartographer_node-1] },
[cartographer_node-1] fixed_frame_pose_rotation_weight = 100.000000,
[cartographer_node-1] fixed_frame_pose_translation_weight = 10.000000,
[cartographer_node-1] huber_scale = 10.000000,
[cartographer_node-1] local_slam_pose_rotation_weight = 100000.000000,
[cartographer_node-1] local_slam_pose_translation_weight = 100000.000000,
[cartographer_node-1] log_solver_summary = false,
[cartographer_node-1] odometry_rotation_weight = 100000.000000,
[cartographer_node-1] odometry_translation_weight = 100000.000000,
[cartographer_node-1] rotation_weight = 300000.000000,
[cartographer_node-1] },
[cartographer_node-1] optimize_every_n_nodes = 90.000000,
[cartographer_node-1] },
[cartographer_node-1] use_trajectory_builder_2d = true,
[cartographer_node-1] use_trajectory_builder_3d = false,
[cartographer_node-1] },
[cartographer_node-1] map_frame = "map",
[cartographer_node-1] num_laser_scans = 1.000000,
[cartographer_node-1] num_multi_echo_laser_scans = 0.000000,
[cartographer_node-1] num_point_clouds = 0.000000,
[cartographer_node-1] num_subdivisions_per_laser_scan = 1.000000,
[cartographer_node-1] odom_frame = "odom",
[cartographer_node-1] provide_odom_frame = false,
[cartographer_node-1] publish_frame_projected_to_2d = false,
[cartographer_node-1] published_frame = "base_link",
[cartographer_node-1] tracking_frame = "base_link",
[cartographer_node-1] trajectory_builder = {
[cartographer_node-1] pure_localization = false,
[cartographer_node-1] trajectory_builder_2d = {
[cartographer_node-1] adaptive_voxel_filter = {
[cartographer_node-1] max_length = 0.500000,
[cartographer_node-1] max_range = 50.000000,
[cartographer_node-1] min_num_points = 200.000000,
[cartographer_node-1] },
[cartographer_node-1] ceres_scan_matcher = {
[cartographer_node-1] ceres_solver_options = {
[cartographer_node-1] max_num_iterations = 20.000000,
[cartographer_node-1] num_threads = 1.000000,
[cartographer_node-1] use_nonmonotonic_steps = false,
[cartographer_node-1] },
[cartographer_node-1] occupied_space_weight = 1.000000,
[cartographer_node-1] rotation_weight = 40.000000,
[cartographer_node-1] translation_weight = 10.000000,
[cartographer_node-1] },
[cartographer_node-1] imu_gravity_time_constant = 10.000000,
[cartographer_node-1] loop_closure_adaptive_voxel_filter = {
[cartographer_node-1] max_length = 0.900000,
[cartographer_node-1] max_range = 50.000000,
[cartographer_node-1] min_num_points = 100.000000,
[cartographer_node-1] },
[cartographer_node-1] max_range = 12.000000,
[cartographer_node-1] max_z = 2.000000,
[cartographer_node-1] min_range = 0.100000,
[cartographer_node-1] min_z = -0.800000,
[cartographer_node-1] missing_data_ray_length = 5.000000,
[cartographer_node-1] motion_filter = {
[cartographer_node-1] max_angle_radians = 0.017453,
[cartographer_node-1] max_distance_meters = 0.200000,
[cartographer_node-1] max_time_seconds = 5.000000,
[cartographer_node-1] },
[cartographer_node-1] num_accumulated_range_data = 1.000000,
[cartographer_node-1] real_time_correlative_scan_matcher = {
[cartographer_node-1] angular_search_window = 0.349066,
[cartographer_node-1] linear_search_window = 0.100000,
[cartographer_node-1] rotation_delta_cost_weight = 0.100000,
[cartographer_node-1] translation_delta_cost_weight = 0.100000,
[cartographer_node-1] },
[cartographer_node-1] submaps = {
[cartographer_node-1] grid_options_2d = {
[cartographer_node-1] grid_type = "PROBABILITY_GRID",
[cartographer_node-1] resolution = 0.050000,
[cartographer_node-1] },
[cartographer_node-1] num_range_data = 90.000000,
[cartographer_node-1] range_data_inserter = {
[cartographer_node-1] probability_grid_range_data_inserter = {
[cartographer_node-1] hit_probability = 0.550000,
[cartographer_node-1] insert_free_space = true,
[cartographer_node-1] miss_probability = 0.490000,
[cartographer_node-1] },
[cartographer_node-1] range_data_inserter_type = "PROBABILITY_GRID_INSERTER_2D",
[cartographer_node-1] },
[cartographer_node-1] },
[cartographer_node-1] use_imu_data = false,
[cartographer_node-1] use_online_correlative_scan_matching = false,
[cartographer_node-1] voxel_filter_size = 0.025000,
[cartographer_node-1] },
[cartographer_node-1] trajectory_builder_3d = {
[cartographer_node-1] ceres_scan_matcher = {
[cartographer_node-1] ceres_solver_options = {
[cartographer_node-1] max_num_iterations = 12.000000,
[cartographer_node-1] num_threads = 1.000000,
[cartographer_node-1] use_nonmonotonic_steps = false,
[cartographer_node-1] },
[cartographer_node-1] occupied_space_weight_0 = 1.000000,
[cartographer_node-1] occupied_space_weight_1 = 6.000000,
[cartographer_node-1] only_optimize_yaw = false,
[cartographer_node-1] rotation_weight = 400.000000,
[cartographer_node-1] translation_weight = 5.000000,
[cartographer_node-1] },
[cartographer_node-1] high_resolution_adaptive_voxel_filter = {
[cartographer_node-1] max_length = 2.000000,
[cartographer_node-1] max_range = 15.000000,
[cartographer_node-1] min_num_points = 150.000000,
[cartographer_node-1] },
[cartographer_node-1] imu_gravity_time_constant = 10.000000,
[cartographer_node-1] low_resolution_adaptive_voxel_filter = {
[cartographer_node-1] max_length = 4.000000,
[cartographer_node-1] max_range = 60.000000,
[cartographer_node-1] min_num_points = 200.000000,
[cartographer_node-1] },
[cartographer_node-1] max_range = 60.000000,
[cartographer_node-1] min_range = 1.000000,
[cartographer_node-1] motion_filter = {
[cartographer_node-1] max_angle_radians = 0.004000,
[cartographer_node-1] max_distance_meters = 0.100000,
[cartographer_node-1] max_time_seconds = 0.500000,
[cartographer_node-1] },
[cartographer_node-1] num_accumulated_range_data = 1.000000,
[cartographer_node-1] real_time_correlative_scan_matcher = {
[cartographer_node-1] angular_search_window = 0.017453,
[cartographer_node-1] linear_search_window = 0.150000,
[cartographer_node-1] rotation_delta_cost_weight = 0.100000,
[cartographer_node-1] translation_delta_cost_weight = 0.100000,
[cartographer_node-1] },
[cartographer_node-1] rotational_histogram_size = 120.000000,
[cartographer_node-1] submaps = {
[cartographer_node-1] high_resolution = 0.100000,
[cartographer_node-1] high_resolution_max_range = 20.000000,
[cartographer_node-1] low_resolution = 0.450000,
[cartographer_node-1] num_range_data = 160.000000,
[cartographer_node-1] range_data_inserter = {
[cartographer_node-1] hit_probability = 0.550000,
[cartographer_node-1] miss_probability = 0.490000,
[cartographer_node-1] num_free_space_voxels = 2.000000,
[cartographer_node-1] },
[cartographer_node-1] },
[cartographer_node-1] use_online_correlative_scan_matching = false,
[cartographer_node-1] voxel_filter_size = 0.150000,
[cartographer_node-1] },
[cartographer_node-1] },
[cartographer_node-1] use_imu_data = false,
[cartographer_node-1] use_landmarks = false,
[cartographer_node-1] use_nav_sat = false,
[cartographer_node-1] use_odometry = false,
[cartographer_node-1] }
[cartographer_node-1] [FATAL] [1732016953.479850561] [cartographer_ros]: F1119 12:49:13.000000 31201 lua_parameter_dictionary.cc:399] Check failed: HasKey(key) Key 'lookup_transform_timeout_sec' not in dictionary:
[cartographer_node-1] {
[cartographer_node-1] map_builder = {
[cartographer_node-1] num_background_threads = 4.000000,
[cartographer_node-1] pose_graph = {
[cartographer_node-1] constraint_builder = {
[cartographer_node-1] ceres_scan_matcher = {
[cartographer_node-1] ceres_solver_options = {
[cartographer_node-1] max_num_iterations = 10.000000,
[cartographer_node-1] num_threads = 1.000000,
[cartographer_node-1] use_nonmonotonic_steps = true,
[cartographer_node-1] },
[cartographer_node-1] occupied_space_weight = 20.000000,
[cartographer_node-1] rotation_weight = 1.000000,
[cartographer_node-1] translation_weight = 10.000000,
[cartographer_node-1] },
[cartographer_node-1] ceres_scan_matcher_3d = {
[cartographer_node-1] ceres_solver_options = {
[cartographer_node-1] max_num_iterations = 10.000000,
[cartographer_node-1] num_threads = 1.000000,
[cartographer_node-1] use_nonmonotonic_steps = false,
[cartographer_node-1] },
[cartographer_node-1] occupied_space_weight_0 = 5.000000,
[cartographer_node-1] occupied_space_weight_1 = 30.000000,
[cartographer_node-1] only_optimize_yaw = false,
[cartographer_node-1] rotation_weight = 1.000000,
[cartographer_node-1] translation_weight = 10.000000,
[cartographer_node-1] },
[cartographer_node-1] fast_correlative_scan_matcher = {
[cartographer_node-1] angular_search_window = 0.523599,
[cartographer_node-1] branch_and_bound_depth = 7.000000,
[cartographer_node-1] linear_search_window = 7.000000,
[cartographer_node-1] },
[cartographer_node-1] fast_correlative_scan_matcher_3d = {
[cartographer_node-1] angular_search_window = 0.261799,
[cartographer_node-1] branch_and_bound_depth = 8.000000,
[cartographer_node-1] full_resolution_depth = 3.000000,
[cartographer_node-1] linear_xy_search_window = 5.000000,
[cartographer_node-1] linear_z_search_window = 1.000000,
[cartographer_node-1] min_low_resolution_score = 0.550000,
[cartographer_node-1] min_rotational_score = 0.770000,
[cartographer_node-1] },
[cartographer_node-1] global_localization_min_score = 0.600000,
[cartographer_node-1] log_matches = true,
[cartographer_node-1] loop_closure_rotation_weight = 100000.000000,
[cartographer_node-1] loop_closure_translation_weight = 11000.000000,
[cartographer_node-1] max_constraint_distance = 15.000000,
[cartographer_node-1] min_score = 0.550000,
[cartographer_node-1] sampling_ratio = 0.300000,
[cartographer_node-1] },
[cartographer_node-1] global_constraint_search_after_n_seconds = 10.000000,
[cartographer_node-1] global_sampling_ratio = 0.003000,
[cartographer_node-1] log_residual_histograms = true,
[cartographer_node-1] matcher_rotation_weight = 1600.000000,
[cartographer_node-1] matcher_translation_weight = 500.000000,
[cartographer_node-1] max_num_final_iterations = 200.000000,
[cartographer_node-1] optimization_problem = {
[cartographer_node-1] acceleration_weight = 1000.000000,
[cartographer_node-1] ceres_solver_options = {
[cartographer_node-1] max_num_iterations = 50.000000,
[cartographer_node-1] num_threads = 7.000000,
[cartographer_node-1] use_nonmonotonic_steps = false,
[cartographer_node-1] },
[cartographer_node-1] fixed_frame_pose_rotation_weight = 100.000000,
[cartographer_node-1] fixed_frame_pose_translation_weight = 10.000000,
[cartographer_node-1] huber_scale = 10.000000,
[cartographer_node-1] local_slam_pose_rotation_weight = 100000.000000,
[cartographer_node-1] local_slam_pose_translation_weight = 100000.000000,
[cartographer_node-1] log_solver_summary = false,
[cartographer_node-1] odometry_rotation_weight = 100000.000000,
[cartographer_node-1] odometry_translation_weight = 100000.000000,
[cartographer_node-1] rotation_weight = 300000.000000,
[cartographer_node-1] },
[cartographer_node-1] optimize_every_n_nodes = 90.000000,
[cartographer_node-1] },
[cartographer_node-1] use_trajectory_builder_2d = true,
[cartographer_node-1] use_trajectory_builder_3d = false,
[cartographer_node-1] },
[cartographer_node-1] map_frame = "map",
[cartographer_node-1] num_laser_scans = 1.000000,
[cartographer_node-1] num_multi_echo_laser_scans = 0.000000,
[cartographer_node-1] num_point_clouds = 0.000000,
[cartographer_node-1] num_subdivisions_per_laser_scan = 1.000000,
[cartographer_node-1] odom_frame = "odom",
[cartographer_node-1] provide_odom_frame = false,
[cartographer_node-1] publish_frame_projected_to_2d = false,
[cartographer_node-1] published_frame = "base_link",
[cartographer_node-1] tracking_frame = "base_link",
[cartographer_node-1] trajectory_builder = {
[cartographer_node-1] pure_localization = false,
[cartographer_node-1] trajectory_builder_2d = {
[cartographer_node-1] adaptive_voxel_filter = {
[cartographer_node-1] max_length = 0.500000,
[cartographer_node-1] max_range = 50.000000,
[cartographer_node-1] min_num_points = 200.000000,
[cartographer_node-1] },
[cartographer_node-1] ceres_scan_matcher = {
[cartographer_node-1] ceres_solver_options = {
[cartographer_node-1] max_num_iterations = 20.000000,
[cartographer_node-1] num_threads = 1.000000,
[cartographer_node-1] use_nonmonotonic_steps = false,
[cartographer_node-1] },
[cartographer_node-1] occupied_space_weight = 1.000000,
[cartographer_node-1] rotation_weight = 40.000000,
[cartographer_node-1] translation_weight = 10.000000,
[cartographer_node-1] },
[cartographer_node-1] imu_gravity_time_constant = 10.000000,
[cartographer_node-1] loop_closure_adaptive_voxel_filter = {
[cartographer_node-1] max_length = 0.900000,
[cartographer_node-1] max_range = 50.000000,
[cartographer_node-1] min_num_points = 100.000000,
[cartographer_node-1] },
[cartographer_node-1] max_range = 12.000000,
[cartographer_node-1] max_z = 2.000000,
[cartographer_node-1] min_range = 0.100000,
[cartographer_node-1] min_z = -0.800000,
[cartographer_node-1] missing_data_ray_length = 5.000000,
[cartographer_node-1] motion_filter = {
[cartographer_node-1] max_angle_radians = 0.017453,
[cartographer_node-1] max_distance_meters = 0.200000,
[cartographer_node-1] max_time_seconds = 5.000000,
[cartographer_node-1] },
[cartographer_node-1] num_accumulated_range_data = 1.000000,
[cartographer_node-1] real_time_correlative_scan_matcher = {
[cartographer_node-1] angular_search_window = 0.349066,
[cartographer_node-1] linear_search_window = 0.100000,
[cartographer_node-1] rotation_delta_cost_weight = 0.100000,
[cartographer_node-1] translation_delta_cost_weight = 0.100000,
[cartographer_node-1] },
[cartographer_node-1] submaps = {
[cartographer_node-1] grid_options_2d = {
[cartographer_node-1] grid_type = "PROBABILITY_GRID",
[cartographer_node-1] resolution = 0.050000,
[cartographer_node-1] },
[cartographer_node-1] num_range_data = 90.000000,
[cartographer_node-1] range_data_inserter = {
[cartographer_node-1] probability_grid_range_data_inserter = {
[cartographer_node-1] hit_probability = 0.550000,
[cartographer_node-1] insert_free_space = true,
[cartographer_node-1] miss_probability = 0.490000,
[cartographer_node-1] },
[cartographer_node-1] range_data_inserter_type = "PROBABILITY_GRID_INSERTER_2D",
[cartographer_node-1] },
[cartographer_node-1] },
[cartographer_node-1] use_imu_data = false,
[cartographer_node-1] use_online_correlative_scan_matching = false,
[cartographer_node-1] voxel_filter_size = 0.025000,
[cartographer_node-1] },
[cartographer_node-1] trajectory_builder_3d = {
[cartographer_node-1] ceres_scan_matcher = {
[cartographer_node-1] ceres_solver_options = {
[cartographer_node-1] max_num_iterations = 12.000000,
[cartographer_node-1] num_threads = 1.000000,
[cartographer_node-1] use_nonmonotonic_steps = false,
[cartographer_node-1] },
[cartographer_node-1] occupied_space_weight_0 = 1.000000,
[cartographer_node-1] occupied_space_weight_1 = 6.000000,
[cartographer_node-1] only_optimize_yaw = false,
[cartographer_node-1] rotation_weight = 400.000000,
[cartographer_node-1] translation_weight = 5.000000,
[cartographer_node-1] },
[cartographer_node-1] high_resolution_adaptive_voxel_filter = {
[cartographer_node-1] max_length = 2.000000,
[cartographer_node-1] max_range = 15.000000,
[cartographer_node-1] min_num_points = 150.000000,
[cartographer_node-1] },
[cartographer_node-1] imu_gravity_time_constant = 10.000000,
[cartographer_node-1] low_resolution_adaptive_voxel_filter = {
[cartographer_node-1] max_length = 4.000000,
[cartographer_node-1] max_range = 60.000000,
[cartographer_node-1] min_num_points = 200.000000,
[cartographer_node-1] },
[cartographer_node-1] max_range = 60.000000,
[cartographer_node-1] min_range = 1.000000,
[cartographer_node-1] motion_filter = {
[cartographer_node-1] max_angle_radians = 0.004000,
[cartographer_node-1] max_distance_meters = 0.100000,
[cartographer_node-1] max_time_seconds = 0.500000,
[cartographer_node-1] },
[cartographer_node-1] num_accumulated_range_data = 1.000000,
[cartographer_node-1] real_time_correlative_scan_matcher = {
[cartographer_node-1] angular_search_window = 0.017453,
[cartographer_node-1] linear_search_window = 0.150000,
[cartographer_node-1] rotation_delta_cost_weight = 0.100000,
[cartographer_node-1] translation_delta_cost_weight = 0.100000,
[cartographer_node-1] },
[cartographer_node-1] rotational_histogram_size = 120.000000,
[cartographer_node-1] submaps = {
[cartographer_node-1] high_resolution = 0.100000,
[cartographer_node-1] high_resolution_max_range = 20.000000,
[cartographer_node-1] low_resolution = 0.450000,
[cartographer_node-1] num_range_data = 160.000000,
[cartographer_node-1] range_data_inserter = {
[cartographer_node-1] hit_probability = 0.550000,
[cartographer_node-1] miss_probability = 0.490000,
[cartographer_node-1] num_free_space_voxels = 2.000000,
[cartographer_node-1] },
[cartographer_node-1] },
[cartographer_node-1] use_online_correlative_scan_matching = false,
[cartographer_node-1] voxel_filter_size = 0.150000,
[cartographer_node-1] },
[cartographer_node-1] },
[cartographer_node-1] use_imu_data = false,
[cartographer_node-1] use_landmarks = false,
[cartographer_node-1] use_nav_sat = false,
[cartographer_node-1] use_odometry = false,
[cartographer_node-1] }
[occupancy_grid_node-2] [WARN] [1732016954.420018258] [occupancy_grid_node]: submap_slices and last_frame_id is empty
[cartographer_node-1] *** Check failure stack trace: ***
[cartographer_node-1] @ 0x7f81c03478 google::LogMessage::Fail()
[cartographer_node-1] @ 0x7f81c08114 google::LogMessage::SendToLog()
[cartographer_node-1] @ 0x7f81c0316c google::LogMessage::Flush()
[cartographer_node-1] @ 0x7f81c039ec google::LogMessageFatal::~LogMessageFatal()
[cartographer_node-1] @ 0x5583022328 (unknown)
[cartographer_node-1] @ 0x558302238c (unknown)
[cartographer_node-1] @ 0x5583022568 (unknown)
[cartographer_node-1] @ 0x5583007dec (unknown)
[cartographer_node-1] @ 0x5583008218 (unknown)
[cartographer_node-1] @ 0x5582f8264c (unknown)
[cartographer_node-1] @ 0x7f81275e10 __libc_start_main
[cartographer_node-1] @ 0x5582f84e28 (unknown)
[occupancy_grid_node-2] [WARN] [1732016955.420095089] [occupancy_grid_node]: submap_slices and last_frame_id is empty
[occupancy_grid_node-2] [WARN] [1732016956.420079375] [occupancy_grid_node]: submap_slices and last_frame_id is empty
[occupancy_grid_node-2] [WARN] [1732016957.420024398] [occupancy_grid_node]: submap_slices and last_frame_id is empty
[occupancy_grid_node-2] [WARN] [1732016958.420067504] [occupancy_grid_node]: submap_slices and last_frame_id is empty
[ERROR] [cartographer_node-1]: process has died [pid 31201, exit code -6, cmd '/opt/ros/foxy/lib/cartographer_ros/cartographer_node -configuration_directory /home/jetson/ros2_ws/install/my_robot/share/my_robot/config -configuration_basename my_robot.lua --ros-args -r __node:=cartographer_node'].
[occupancy_grid_node-2] [WARN] [1732016959.420067493] [occupancy_grid_node]: submap_slices and last_frame_id is empty
[occupancy_grid_node-2] [WARN] [1732016960.420077751] [occupancy_grid_node]: submap_slices and last_frame_id is empty
[occupancy_grid_node-2] [WARN] [1732016961.420116872] [occupancy_grid_node]: submap_slices and last_frame_id is empty
[occupancy_grid_node-2] [WARN] [1732016962.420207669] [occupancy_grid_node]: submap_slices and last_frame_id is empty
next page...