ncnynl / turbot3

turtlebot3 custom version
https://ncnynl.com
17 stars 12 forks source link

Lua parameter error #1

Closed hiseholuwa closed 6 years ago

hiseholuwa commented 6 years ago

Hi, I am trying to recreate your success with using ros_cartographer with turtlebot but upon running the cartographer.launch file in the turbot3_slam package, I get this error:

[FATAL] [1524865124.337052405]: F0427 17:38:44.000000 15245 lua_parameter_dictionary.cc:399] Check failed: HasKey(key) Key 'use_landmarks' not in dictionary:
{
  fixed_frame_pose_sampling_ratio = 1.000000,
  imu_sampling_ratio = 1.000000,
  lookup_transform_timeout_sec = 0.200000,
  map_builder = {
    num_background_threads = 4.000000,
    pose_graph = {
      constraint_builder = {
        ceres_scan_matcher = {
          ceres_solver_options = {
            max_num_iterations = 10.000000,
            num_threads = 1.000000,
            use_nonmonotonic_steps = true,
          },
          occupied_space_weight = 20.000000,
          rotation_weight = 1.000000,
          translation_weight = 10.000000,
        },
        ceres_scan_matcher_3d = {
          ceres_solver_options = {
            max_num_iterations = 10.000000,
            num_threads = 1.000000,
            use_nonmonotonic_steps = false,
          },
          occupied_space_weight_0 = 5.000000,
          occupied_space_weight_1 = 30.000000,
          only_optimize_yaw = false,
          rotation_weight = 1.000000,
          translation_weight = 10.000000,
        },
        fast_correlative_scan_matcher = {
          angular_search_window = 0.523599,
          branch_and_bound_depth = 7.000000,
          linear_search_window = 7.000000,
        },
        fast_correlative_scan_matcher_3d = {
          angular_search_window = 0.261799,
          branch_and_bound_depth = 8.000000,
          full_resolution_depth = 3.000000,
          linear_xy_search_window = 5.000000,
          linear_z_search_window = 1.000000,
          min_low_resolution_score = 0.550000,
          min_rotational_score = 0.770000,
        },
        global_localization_min_score = 0.700000,
        log_matches = true,
        loop_closure_rotation_weight = 100000.000000,
        loop_closure_translation_weight = 11000.000000,
        max_constraint_distance = 15.000000,
        min_score = 0.650000,
        sampling_ratio = 0.300000,
      },
      global_constraint_search_after_n_seconds = 10.000000,
      global_sampling_ratio = 0.003000,
      log_residual_histograms = true,
      matcher_rotation_weight = 1600.000000,
      matcher_translation_weight = 500.000000,
      max_num_final_iterations = 200.000000,
      optimization_problem = {
        acceleration_weight = 1000.000000,
        ceres_solver_options = {
          max_num_iterations = 50.000000,
          num_threads = 7.000000,
          use_nonmonotonic_steps = false,
        },
        fixed_frame_pose_rotation_weight = 100.000000,
        fixed_frame_pose_translation_weight = 10.000000,
        huber_scale = 10.000000,
        local_slam_pose_rotation_weight = 100000.000000,
        local_slam_pose_translation_weight = 100000.000000,
        log_solver_summary = false,
        odometry_rotation_weight = 100000.000000,
        odometry_translation_weight = 100000.000000,
        rotation_weight = 300000.000000,
      },
      optimize_every_n_nodes = 90.000000,
    },
    use_trajectory_builder_2d = true,
    use_trajectory_builder_3d = false,
  },
  map_frame = "map",
  num_laser_scans = 1.000000,
  num_multi_echo_laser_scans = 0.000000,
  num_point_clouds = 0.000000,
  num_subdivisions_per_laser_scan = 1.000000,
  odom_frame = "odom",
  odometry_sampling_ratio = 1.000000,
  pose_publish_period_sec = 0.005000,
  provide_odom_frame = false,
  published_frame = "odom",
  rangefinder_sampling_ratio = 1.000000,
  submap_publish_period_sec = 0.300000,
  tracking_frame = "imu_link",
  trajectory_builder = {
    pure_localization = false,
    trajectory_builder_2d = {
      adaptive_voxel_filter = {
        max_length = 0.500000,
        max_range = 50.000000,
        min_num_points = 200.000000,
      },
      ceres_scan_matcher = {
        ceres_solver_options = {
          max_num_iterations = 20.000000,
          num_threads = 1.000000,
          use_nonmonotonic_steps = false,
        },
        occupied_space_weight = 1.000000,
        rotation_weight = 40.000000,
        translation_weight = 10.000000,
      },
      imu_gravity_time_constant = 10.000000,
      loop_closure_adaptive_voxel_filter = {
        max_length = 0.900000,
        max_range = 50.000000,
        min_num_points = 100.000000,
      },
      max_range = 8.000000,
      max_z = 2.000000,
      min_range = 0.100000,
      min_z = -0.800000,
      missing_data_ray_length = 5.000000,
      motion_filter = {
        max_angle_radians = 0.001745,
        max_distance_meters = 0.200000,
        max_time_seconds = 5.000000,
      },
      num_accumulated_range_data = 1.000000,
      real_time_correlative_scan_matcher = {
        angular_search_window = 0.349066,
        linear_search_window = 0.100000,
        rotation_delta_cost_weight = 0.100000,
        translation_delta_cost_weight = 0.100000,
      },
      submaps = {
        grid_options_2d = {
          grid_type = "PROBABILITY_GRID",
          resolution = 0.050000,
        },
        num_range_data = 90.000000,
        range_data_inserter = {
          probability_grid_range_data_inserter = {
            hit_probability = 0.550000,
            insert_free_space = true,
            miss_probability = 0.490000,
          },
          range_data_inserter_type = "PROBABILITY_GRID_INSERTER_2D",
        },
      },
      use_imu_data = true,
      use_online_correlative_scan_matching = true,
      voxel_filter_size = 0.025000,
    },
    trajectory_builder_3d = {
      ceres_scan_matcher = {
        ceres_solver_options = {
          max_num_iterations = 12.000000,
          num_threads = 1.000000,
          use_nonmonotonic_steps = false,
        },
        occupied_space_weight_0 = 1.000000,
        occupied_space_weight_1 = 6.000000,
        only_optimize_yaw = false,
        rotation_weight = 400.000000,
        translation_weight = 5.000000,
      },
      high_resolution_adaptive_voxel_filter = {
        max_length = 2.000000,
        max_range = 15.000000,
        min_num_points = 150.000000,
      },
      imu_gravity_time_constant = 10.000000,
      low_resolution_adaptive_voxel_filter = {
        max_length = 4.000000,
        max_range = 60.000000,
        min_num_points = 200.000000,
      },
      max_range = 60.000000,
      min_range = 1.000000,
      motion_filter = {
        max_angle_radians = 0.004000,
        max_distance_meters = 0.100000,
        max_time_seconds = 0.500000,
      },
      num_accumulated_range_data = 1.000000,
      real_time_correlative_scan_matcher = {
        angular_search_window = 0.017453,
        linear_search_window = 0.150000,
        rotation_delta_cost_weight = 0.100000,
        translation_delta_cost_weight = 0.100000,
      },
      rotational_histogram_size = 120.000000,
      submaps = {
        high_resolution = 0.100000,
        high_resolution_max_range = 20.000000,
        low_resolution = 0.450000,
        num_range_data = 160.000000,
        range_data_inserter = {
          hit_probability = 0.550000,
          miss_probability = 0.490000,
          num_free_space_voxels = 2.000000,
        },
      },
      use_online_correlative_scan_matching = false,
      voxel_filter_size = 0.150000,
    },
  },
  trajectory_publish_period_sec = 0.030000,
  use_nav_sat = false,
  use_odometry = true,
}
*** Check failure stack trace: ***
    @ 0x76e8586e  google::LogMessage::Fail()
    @ 0x76e86e6a  google::LogMessage::SendToLog()
    @ 0x76e8551c  google::LogMessage::Flush()
    @ 0x76e8748c  google::LogMessageFatal::~LogMessageFatal()
    @   0x1d1062  cartographer::common::LuaParameterDictionary::CheckHasKey()
    @   0x1d10b0  cartographer::common::LuaParameterDictionary::CheckHasKeyAndReference()
    @   0x1d129e  cartographer::common::LuaParameterDictionary::GetBool()
    @   0x19e1ae  cartographer_ros::CreateTrajectoryOptions()
    @   0x19ee94  cartographer_ros::LoadOptions()
    @   0x18358a  cartographer_ros::(anonymous namespace)::Run()
    @   0x180d3a  main
    @ 0x763328aa  __libc_start_main

I have tried poking around with the lua files in the package but I can't seem to figure it out. I'd appreciate any help you can offer. Thanks!

hiseholuwa commented 6 years ago

I readjusted the lua parameters to match the default ones in the ros_cartographer package and it works now.

ncnynl commented 5 years ago

Please update as :

include "map_builder.lua" include "trajectory_builder.lua"

options = { map_builder = MAP_BUILDER, trajectory_builder = TRAJECTORY_BUILDER, map_frame = "map", tracking_frame = "imu_link", published_frame = "odom", odom_frame = "odom", provide_odom_frame = false, publish_frame_projected_to_2d = false, use_odometry = true, use_nav_sat = false, use_landmarks = false, num_laser_scans = 1, num_multi_echo_laser_scans = 0, num_subdivisions_per_laser_scan = 1, num_point_clouds = 0, lookup_transform_timeout_sec = 0.2, submap_publish_period_sec = 0.3, pose_publish_period_sec = 5e-3, trajectory_publish_period_sec = 30e-3, rangefinder_sampling_ratio = 1., odometry_sampling_ratio = 1., fixed_frame_pose_sampling_ratio = 1., imu_sampling_ratio = 1., landmarks_sampling_ratio = 1., }

MAP_BUILDER.use_trajectory_builder_2d = true

TRAJECTORY_BUILDER_2D.min_range = 0.1 TRAJECTORY_BUILDER_2D.max_range = 8. TRAJECTORY_BUILDER_2D.missing_data_ray_length = 5. TRAJECTORY_BUILDER_2D.use_imu_data = true TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(0.1)

POSE_GRAPH.constraint_builder.min_score = 0.65 POSE_GRAPH.constraint_builder.global_localization_min_score = 0.7

return options