Hector Slam creating map problem
I am a new user recently start to use ROS and want to build a robot that can automatically create a map. Finally, I find Hector Slam that helps me to solve the problem. I want to get familiar with the Hector Slam so I try to use STDR simulator with hector slam to simulate the map building process. I record the Laser scan(robot0laser0), tf into bag file while using the STDR simulator to control the robot. But when I launch Hector Slam with my launch file, the map is not created correctly.
I want to ask how to fix the launch file error so that i can use Hector Slam to build a map with the data from STDR simulator. Thanks so much for help. :)
The bag file:
types: sensormsgs/LaserScan [90c7ef2dc6895d81024acba2ac42f369] tf2msgs/TFMessage [94810edda583a504dfda3829e70d7eec] topics: /robot0/laser0 2805 msgs : sensormsgs/LaserScan /tf 25232 msgs : tf2_msgs/TFMessage (3 connections)
Here the error when running
lookupTransform robot0 to robot0laser0 timed out. Could not transform laser scan into base_frame.
[ WARN] [1475230770.771092273, 1475129730.487006582]: No transform between frames /map and scanmatcher_frame available after 1475129730.487007 seconds of waiting. This warning only prints once.
[ERROR] [1475230770.962404280, 1475129730.684182516]: Transform failed during publishing of mapodom transform: "nav" passed to lookupTransform argument targetframe does not exist.
The launch file:
<?xml version="1.0"?>
<launch>
<arg name="geotiff_map_file_path" default="$(find hector_geotiff)/maps"/>
<param name="/use_sim_time" value="true"/>
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find hector_slam_launch)/rviz_cfg/mapping_demo.rviz"/>
<arg name="tf_map_scanmatch_transform_frame_name" default="scanmatcher_frame"/>
<arg name="base_frame" default="robot0"/>
<arg name="odom_frame" default="nav"/>
<arg name="pub_map_odom_transform" default="true"/>
<arg name="scan_subscriber_queue_size" default="5"/>
<arg name="scan_topic" default="robot0/laser_0"/>
<arg name="map_size" default="2048"/>
<node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
<!-- Frame names -->
<param name="map_frame" value="map" />
<param name="base_frame" value="$(arg base_frame)" />
<param name="odom_frame" value="$(arg odom_frame)" />
<!-- Tf use -->
<param name="use_tf_scan_transformation" value="true"/>
<param name="use_tf_pose_start_estimate" value="false"/>
<param name="pub_map_odom_transform" value="$(arg pub_map_odom_transform)"/>
<!-- Map size / start point -->
<param name="map_resolution" value="0.050"/>
<param name="map_size" value="$(arg map_size)"/>
<param name="map_start_x" value="0.5"/>
<param name="map_start_y" value="0.5" />
<param name="map_multi_res_levels" value="2" />
<!-- Map update parameters -->
<param name="update_factor_free" value="0.4"/>
<param name="update_factor_occupied" value="0.9" />
<param name="map_update_distance_thresh" value="0.4"/>
<param name="map_update_angle_thresh" value="0.06" />
<param name="laser_z_min_value" value = "-1.0" />
<param name="laser_z_max_value" value = "1.0" />
<!-- Advertising config -->
<param name="advertise_map_service" value="true"/>
<param name="scan_subscriber_queue_size" value="$(arg scan_subscriber_queue_size)"/>
<param name="scan_topic" value="$(arg scan_topic)"/>
<param name="tf_map_scanmatch_transform_frame_name" value="$(arg tf_map_scanmatch_transform_frame_name)"/>
</node>
<include file="$(find hector_geotiff)/launch/geotiff_mapper.launch">
<arg name="trajectory_source_frame_name" value="scanmatcher_frame"/>
<arg name="map_file_path" value="$(arg geotiff_map_file_path)"/>
<node pkg="tf" type="static_transform_publisher" name="baselink_laser" args="0 0 0 0 0 0/base_link/laser 10"/>
<node pkg="hector_mapping" name="hector_mapping" type="hector_mapping" output="screen"/>
</include>
</launch>
Asked by abckwok123 on 2016-09-30 05:22:59 UTC
Comments
Are you sure you have good timestamps for tf? That's a common case.
Asked by kolya_rage on 2019-02-11 17:07:55 UTC