Closed ghost closed 5 years ago
Also, I have same problem. It may be good to use pointcloud_to_laserscan, but I'd like to do it with pointcloud2 directly.
So you are not running pure localization on an existing map. You run 2D mapping with a 3D lidar. Then, you do a quick turn and Cartographer does incorrect scan matching. Is that correct?
If this is the case, you could try out real_time_correlative_scan_matcher which does a more expensive search across a larger area and range of rotations.
gaschler,
That is all correct, I am trying to produce a 2d map in real time with a 3d lidar because I thought it would be easier to get 2d working before starting 3d. Using real_time_correlative_scan_matcher seems to correct the scan matching and produce an accurate map.
Additional note, I had to decrease the angle of view of the 3d lidar as it saw the floor and thought it was a wall.
Thanks Jeff
decrease the angle of view of the 3d lidar as it saw the floor
For documentation, the standard way to remove the floor from 3D scans to do 2D SLAM in to tune
TRAJECTORY_BUILDER_2D.min_z = -0.5
TRAJECTORY_BUILDER_2D.max_z = 0.5
or similar, depending on what z means in your tracking_frame
.
I am trying to use real time SLAM using cartographer with an Ouster LIDAR. The error that seems to occur is the localization part of SLAM not being able to determine where the robot currently is located within the map, therefor it doesn't update properly when moving. I have tried incorporating an IMU with cartographer, but I have disabled it with this example because it displays the exact same results. Cartographer should be able to localize without IMU data, correct?
For more clarification on whats going on, when running cartographer using:
roslaunch cartographer_ros my_robot.launch
Which contains the code:
I obtain the following images:
As you can see, the mapping works well when the robot is stationary, but as soon as I move the robot, it doesn't update the position correctly and maps the new map onto the previous map. What am I doing wrong?
Here is additional information that may help:
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 = true, publish_frame_projected_to_2d = false, use_odometry = false, use_nav_sat = false, use_landmarks = false, num_laser_scans = 0, num_multi_echo_laser_scans = 0, num_subdivisions_per_laser_scan = 1, num_point_clouds = 1, lookup_transform_timeout_sec = 2.0, 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 = 0., landmarks_sampling_ratio = 1., }
MAP_BUILDER.use_trajectory_builder_2d = true TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 10 TRAJECTORY_BUILDER_2D.use_imu_data = false
return options