ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

The map in the video was generated using the hector_geotiff node. This node retrieves the map and trajectory via services as stated at the wiki page. The trajectory is tracked via the hector_trajector_server package, which provides a node that saves the a tf based trajectory given a source and target frame. The trajectory is published on a topic as well as available as a service.

Have you looked at the 'Mapping using logged data' tutorial? The process of mapping and saving to geotiff is described there. Note that the map saving functionality works with maps generated by gmapping or other SLAM systems as well.

The map in the video was generated using the hector_geotiff node. This node retrieves the map and trajectory via services as stated at the wiki page. The trajectory is tracked via the hector_trajector_server package, which provides a node that saves the a tf based trajectory given a source and target frame. The trajectory is published on a topic as well as available as a service.

Have you looked at the 'Mapping using logged data' tutorial? The process of mapping and saving to geotiff is described there. Note that the map saving functionality works with maps generated by gmapping or other SLAM systems as well.

/edit: This example launch file should work for you:

<?xml version="1.0"?>

<launch>

  <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="/base_link" />
    <param name="trajectory_update_rate" type="double" value="4" />
    <param name="trajectory_publish_rate" type="double" value="0.25" />
  </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="$(find hector_geotiff)/maps" />
    <param name="map_file_base_name" type="string" value="hector_slam_map" />
    <param name="draw_background_checkerboard" type="bool" value="true" />
    <param name="draw_free_space_grid" type="bool" value="true" />
  </node>

</launch>

The geotiff map image will be saved every time you publish on the syscommand topic like this:

rostopic pub syscommand std_msgs/String "savegeotiff"
click to hide/show revision 3
duplicate word / typo

The map in the video was generated using the hector_geotiff node. This node retrieves the map and trajectory via services as stated at the wiki page. The trajectory is tracked via the hector_trajector_server package, which provides a node that saves the a tf based trajectory given a source and target frame. The trajectory is published on a topic as well as available as a service.

Have you looked at the 'Mapping using logged data' tutorial? The process of mapping and saving to geotiff is described there. Note that the map saving functionality works with maps generated by gmapping or other SLAM systems as well.

/edit: This example launch file should work for you:

<?xml version="1.0"?>

<launch>

  <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="/base_link" />
    <param name="trajectory_update_rate" type="double" value="4" />
    <param name="trajectory_publish_rate" type="double" value="0.25" />
  </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="$(find hector_geotiff)/maps" />
    <param name="map_file_base_name" type="string" value="hector_slam_map" />
    <param name="draw_background_checkerboard" type="bool" value="true" />
    <param name="draw_free_space_grid" type="bool" value="true" />
  </node>

</launch>

The geotiff map image will be saved every time you publish on the syscommand topic like this:

rostopic pub syscommand std_msgs/String "savegeotiff"