Finally I was able to map using hector slam (tutorial.launch) and the Hokuyo URG-04LX
apparently the problem was this first of all had to modify the settings specified hector_mapping.launch setting for your robot. After that what you have to do is modify the file tutorial.launch use_sim_time setting the parameter to false, apparently when using .bag files. hector_slam works well by setting the parameter to true, but with some LIDAR use this parameter must be false.
and finally launch so are my files, put them in a package called "uprobotics"
slam.launch
<launch>
<param name="/use_sim_time" value="false"/>ros
<node pkg="rviz" type="rviz" name="rviz"
args="-d $(find hector_slam_launch)/rviz_cfg/mapping_demo.vcg"/>
<include file="$(find uprobotics)/launch/hector_mapping.launch"/>
<include file="$(find uprobotics)/launch/geotiff_mapper.launch">
<arg name="trajectory_source_frame_name" value="scanmatcher_frame"/>
</include>
</launch>
hector_mapping.launch
<launch>
<node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
<param name="pub_map_odom_transform" value="true"/>
<param name="map_frame" value="map" />
<param name="base_frame" value="base_link" />
<param name="odom_frame" value="base_link" />
<!-- Map size / start point -->
<param name="map_resolution" value="0.025"/>
<param name="map_size" value="2048"/>
<param name="map_start_x" value="0.5"/>
<param name="map_start_y" value="0.5" />
<param name="laser_z_min_value" value="-2.5" />
<param name="laser_z_max_value" value="7.5" />
<!-- Map update parameters -->
<param name="update_factor_free" value="0.4"/>
<param name="update_factor_occupied" value="0.7" />
<param name="map_update_distance_thresh" value="0.2"/>
<param name="map_update_angle_thresh" value="0.06" />
</node>
<node pkg="tf" type="static_transform_publisher" name="base_to_laser_broadcaster" args="0 0 0 0 0 0 /base_link /laser 100" />
</launch>
geotiff_mapper.launch
in this file was modified only thing is the path where you save the geotiff generated in this case / home / viki / Desktop / maps
<launch>
<arg name="trajectory_source_frame_name" default="/base_link"/>
<arg name="trajectory_update_rate" default="4"/>
<arg name="trajectory_publish_rate" default="0.25"/>
<node pkg="hector_trajectory_server" type="hector_trajectory_server" name="hector_trajectory_server" output="screen">
<param name="target_frame_name" type="string" value="/map" />
<param name="source_frame_name" type="string" value="$(arg trajectory_source_frame_name)" />
<param name="trajectory_update_rate" type="double" value="$(arg trajectory_update_rate)" />
<param name="trajectory_publish_rate" type="double" value="$(arg trajectory_publish_rate)" />
</node>
<node pkg="hector_geotiff" type="geotiff_node" name="hector_geotiff_node" output="screen" launch-prefix="nice -n 15">
<remap from="map" to="/dynamic_map" />
<param name="map_file_path" type="string" value="/home/viki/Desktop/maps" />
<param name="map_file_base_name" type="string" value="uprobotics" />
<param name="geotiff_save_period" type="double" value="0" />
<param name="draw_background_checkerboard" type="bool" value="true" />
<param name="draw_free_space_grid" type="bool" value="true" />
</node>
</launch>
and is run as follows
$ roscore
$ sudo chmod a+rw /dev/ttyACM0
$ ls -l /dev/ttyACM0
$ rosrun hokuyo_node hokuyo_node
$ uprobotics slam.launch
and so far seems to work wonders
I hope this is helpful for someone.
notes:
I'm using ros fuerte
I am running ros in a virtual machine with virtualbox
I'm using the Hokuyo URG-04LX for usb
You must also have an IMU for hector_slam.
I think this is not correct, @TJump. I think it can enhance the results, but it is not a requirement. At least I'm using HectorSlam without IMU.
Yes, as long as you take care to keep your LIDAR level (i.e. no roll/pitch motion), things should also work without an IMU (and just providing a fixed transform between laser and base_link)