[ros-users] tu-darmstadt-ros-pkg announcement

Stefan Kohlbrecher stefan.kohlbrecher at googlemail.com
Wed Sep 28 21:25:55 UTC 2011


Hi Tim,

This is the launch file we use on our handheld mapping system. It
starts the Hokuyo node only if the REALROBOT environment variable is
set.
You might want to have a look at 'mapping_default' launch file in the
'hector_mapping' package. This launches just the mapping node and
nothing else.

There's only 2 things important about the source of laser scans (be it
a Hokuyo LIDAR, log files or anything else):
-It has to publish on the "scan" topic (or this has to be remapped).
-There has to be a transformation between the scan's frame_id and the
base_frame.

The perhaps most simple solution is to the the base_frame to be the
same as the laser scanner frame_id. I'm currently working on a short
"How to use hector_mapping on your own platform" tutorial, but that
might take a few days due to other commitments.

regards,
Stefan

2011/9/28 Tim Coddington <tim.coddington at rteamworks.com>:
> Stefan,
>
>   Nice work!
>
> What does it take to convert the hector_slam demo to run with the
> hokuyo_node?
>
> I've cut/pasted my attempt to modify the mapping_box.launch file below,
> which is the only one starting up Hokuyo, but no point cloud appears.  I
> suspect that one of the required initial transforms is not being
> published.  Can you help?   Thanks
>
>
>
> <launch>
>  <group if="$(optenv REALROBOT 0)">
>    <node pkg="hokuyo_node" type="hokuyo_node" name="hokuyo_node"
> output="screen">
>      <param name="min_ang" value=" -2.2689" />
>      <param name="max_ang" value="  2.2689" />
>    </node>
>  </group>
>
>  <node pkg="hector_mapping" type="hector_mapping" name="hector_mapping"
> output="screen">
>    <param name="base_frame" value="base_stabilized" />
>    <param name="odom_frame" value="nav"/>
>    <param name="output_timing" value="false"/>
>
>    <param name="use_tf_scan_transformation" value="true"/>
>    <param name="use_tf_pose_start_estimate" value="false"/>
>    <param name="scan_topic" value="scan"/>
>
>    <!-- Map size / start point -->
>    <param name="map_resolution" value="0.050"/>
>    <param name="map_size" value="2048"/>
>    <param name="map_start_x" value="0.5"/>
>    <param name="map_start_y" value="0.5" />
>
>    <!-- 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="pub_drawings" value="true"/>
>      <param name="pub_debug_output" value="true"/>
>    -->
>    </node>
>
>    <param name="hector_mapping/pub_map_odom_transform" value="false"/>
>    <node pkg="tf" type="static_transform_publisher"
> name="map_nav_broadcaster" args="0 0 0 0 0 0 map nav 100"/>
>
>  <node pkg="rviz" type="rviz" name="rviz"
>    args="-d $(find hector_slam_launch)/rviz_cfg/mapping_demo.vcg"/>
>
>  <include file="$(find hector_geotiff)/launch/geotiff_mapper.launch" />
>
>  </launch>
>
>
>
> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
>



More information about the ros-users mailing list