nav2d_karto: LocalizedRangeScan contains unexpected numbers of range readings [closed]

asked 2015-11-11 09:59:20 -0500

g_gemignani gravatar image

updated 2015-11-13 03:56:01 -0500

Hello, I was able to run the third nav2d tutorial, mapping the example world provided in simulation. At this point, I tried to create a map playing a bag recorded with our robot (the bag seems ok since I was able to use it both with hector_slam and gmapping). The launch file adopted is the following:

<launch>

    <param name="use_sim_time" value="true" />
    <rosparam file="ros.yaml"/>

    <!-- Start Mapper to genreate map from laser scans -->
    <node name="Mapper" pkg="nav2d_karto" type="mapper">
        <remap from="scan" to="scan_front"/>
        <rosparam file="mapper.yaml"/>
    </node>

    <!-- RVIZ to view the visualization -->
    <node name="RVIZ" pkg="rviz" type="rviz" args=" -d $(find nav2d_tutorials)/param/tutorial3.rviz" />

</launch>

where ros.yaml is:

# Defines topics services and frames for all modules

### TF frames #############################################
laser_frame: base_front_laser_link
robot_frame: base_link
odometry_frame: odom
offset_frame: offset
map_frame: map

### ROS topics ############################################
map_topic: map
laser_topic: scan_front

### ROS services ##########################################
map_service: static_map

and mapper.yaml is:

### Mapper ################################################

grid_resolution: 0.1
range_threshold: 10.0
map_update_rate: 5
publish_pose_graph: true
max_covariance: 0.01
transform_publish_period: 0.1
min_map_size: 20

### Localizer #############################################

min_particles: 2500
max_particles: 10000

### Karto #################################################

# For a full list of available parameters and their
# corresponding default values, see OpenKarto/OpenMapper.h

MinimumTravelDistance: 1.0
MinimumTravelHeading: 0.52
LoopSearchMaximumDistance: 10.0

###########################################################

However, when I run the launch file, I repeatedly get the following error:

...
[/Mapper ERROR 1447255247.422253465, 1446138392.065241589]: LaserRangeFinder::Validate() - LocalizedRangeScan contains 450 range readings, expected 451
[/Mapper ERROR 1447255247.473642245, 1446138392.166068413]: LaserRangeFinder::Validate() - LocalizedRangeScan contains 450 range readings, expected 451
[/Mapper ERROR 1447255247.523607012, 1446138392.266683794]: LaserRangeFinder::Validate() - LocalizedRangeScan contains 450 range readings, expected 451
[/Mapper ERROR 1447255247.573577659, 1446138392.367428587]: LaserRangeFinder::Validate() - LocalizedRangeScan contains 450 range readings, expected 451
[/Mapper ERROR 1447255247.573836632, 1446138392.367428587]: LaserRangeFinder::Validate() - LocalizedRangeScan contains 450 range readings, expected 451
[/Mapper ERROR 1447255247.624776753, 1446138392.468281149]: LaserRangeFinder::Validate() - LocalizedRangeScan contains 450 range readings, expected 451
[/Mapper ERROR 1447255247.674386008, 1446138392.569080442]: LaserRangeFinder::Validate() - LocalizedRangeScan contains 450 range readings, expected 451
[/Mapper ERROR 1447255247.724970486, 1446138392.669702679]: LaserRangeFinder::Validate() - LocalizedRangeScan contains 450 range readings, expected 451
[/Mapper ERROR 1447255247.775455585, 1446138392.770533571]: LaserRangeFinder::Validate() - LocalizedRangeScan contains 450 range readings, expected 451
[/Mapper ERROR 1447255247.775564465, 1446138392.770533571]: LaserRangeFinder::Validate() - LocalizedRangeScan contains 450 range readings, expected 451
...

Am I missing something or there is a problem with the code?

Thank you so much for your help!

EDIT

I was able to solve the problem. The laser scanner driver that I am using is publishing 450 laser readings instead of the expected 451. I was able to use this mapper by replacing the line

m_NumberOfRangeReadings = static_cast<kt_int32u>(math::Round((GetMaximumAngle() - GetMinimumAngle()) / GetAngularResolution()) + 1);

with the line

m_NumberOfRangeReadings = static_cast<kt_int32u>(math::Round((GetMaximumAngle() - GetMinimumAngle()) / GetAngularResolution()));

in the nav2d_karto/OpenKarto/source/OpenKarto/Sensor.h file.

edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by g_gemignani
close date 2015-11-13 03:55:31.689939