Recent Changes - Search:

edit SideBar

ROS /

LocalizingTheScarab

Create a map and save it.

To run the HFN (navigation package) against a pre-saved map, you need to drive the scarab around and create the map:

roscore
roslaunch scarab scarab.launch
roslaunch scarab gmapping.launch
rosrun scarab_twist key_to_twist

Visualize the map from your PC

rosrun rviz rviz

When you have created a good map, you can load save it:

rosrun map_server map_saver -f "mymapname" map:=map_hokuyo

Load the map.

The localization.launch script in the scarab package launches the relevant packages to localize the Scarab.
In particular, it runs the amcl package to localize the Scarab against this map. This package subscribes to laser scans and an existing map, and runs a probabilistic localization algorithm to localize the Scarab.
The launch script also launches the HFN package which subscribes to waypoints on the /goal topic and runs an astar algorithm to plan a path.
The code in the ROS packages are stable, but the launch script may need to be edited if it doesn't work well. Here are some pointers in editing the launch file:

  1. Edit the map path name in the launch file to match your map name.
  2. Ensure the different packages are publishing and subscribing to the same topic. For example if you see:
    $rostopic list
    scarab/cmd_vel
    cmd_vel

edit the launch file to ensure all the topic names are the same. In particular, you want to look at remapping arguments, argument substitution, and environment variables to sync the topic names. Note: Prefixing the topics with a hostname or robot name such as "scarabXX" is useful when launching many robots.

Physical problems

  • Laser scan doesn't align with map

A problem I faced was that the laser scan didn't align with the map:

Attach:badMap.png Δ

The map I used was very symmetric. This may have affected the accuracy of the amcl package to localize. I found just adding a feature to one corner helped:

Attach:goodMap.png Δ

  • Robot moves slowly and gets stuck

Check parameters in the HFN package, especially 'v_opt' and 'w_max'

  • Robot drifts

Check the parameters in HFN package: 'goal_tolerance', 'goal_tolerance_ang'
One problem I faced was that pose was updating very slowly. Changing the parameters in acml: 'update_min_d', 'update_min_a' made it work better. These set the minimum physical movement of the robot before the acml package performs a filter update.

Attachments

The following launch file and parameters worked for me

<launch>
<!-- Launch map server and amcl -->
<arg name="init" default="false" />
<arg name="robot" value="scarab" />
<group>
<node name="map_server" pkg="map_server" type="map_server" output="screen"
args="$(find scarab)/maps/graspBlueCorner2.yaml">
<param name="frame_id" value="/map" />
</node>

<node name="pose_stamped" pkg="scarab" type="posestamped_node.py" output="screen" />

<node pkg="amcl" type="amcl" name="amcl" output="screen">
<param name="global_frame_id" value="/map" />
<param name="base_frame_id" value="$(arg robot)/base_link" />
<param name="odom_frame_id" value="$(arg robot)/odom_laser" />
<param name="update_min_d" value="0.1" />
<param name="update_min_a" value="0.26" />
<param name="initial_pose_x" value="0.0" if="$(arg init)"/>
<param name="initial_pose_y" value="0.0" if="$(arg init)"/>
<param name="initial_pose_a" value="1.57" if="$(arg init)" />
<param name="initial_cov_xx" value="0.3" if="$(arg init)"/>
<param name="initial_cov_yy" value="0.3" if="$(arg init)"/>
<param name="initial_cov_aa" value="0.25" if="$(arg init)"/>
</node>

<node name="hfn" pkg="hfn" type="hfn" output="screen">
<param name="base_frame_id" value="$(arg robot)/base_link" />

<param name="cost_occ_prob" value="0.01" />
<param name="cost_occ_dist" value="0.15" />
<param name="max_occ_dist" value="0.5" />
<param name="lethal_occ_dist" value="0.35" />
<param name="tau_1" value="1.0" />
<param name="tau_2" value="0.2" />
<param name="v_opt" value="0.16" />
<param name="w_max" value="0.7" />

<!-- 0.0873 rad ~= 5 degrees -->
<param name="goal_tolerance_ang" value="0.2" />
<param name="min_map_update" value="2.0" />
<param name="stuck_start" value="3.0" />
<param name="map_frame_id" value="/map" />
<remap from="odom" to="/odom_laser" />
<remap from="map" to="/map" />


<remap from="pose" to="pose_stamped" />
</node>

<node name="goal_to_action" pkg="hfn" type="goal_to_action.py" />

<node name="laser" pkg="hokuyo_node" type="hokuyo_node" output="screen">
<param name="cluster" value="1" />
<param name="skip" value="1" />
<param name="intensity" value="false" />
<param name="min_ang" value="-2.2689" />
<param name="max_ang" value="2.2689" />
<param name="port" value="/dev/hokuyo" />
<param name="frame_id" value="$(arg robot)/laser" />
<remap from="/diagnostics" to="laser_diagnostics" />
</node>

<node pkg="roboclaw" type="roboclaw_node" name="motor">
<param name="broadcast_tf" value="false" />
</node>

<node name="laser_odom" pkg="laser_odom" type="laser_odom"
output="screen" >
<param name="debug" value="true" />
<param name="base_frame" value="$(arg robot)/base_link" />
<param name="odom_frame" value="$(arg robot)/odom_laser" />
<param name="decay_duration" value="5" />
</node>
</group>

<node pkg="tf" type="static_transform_publisher" name="transformer"
args="0.0 0.0 0.0 0.0 0.0 0.0 $(arg robot)/base_link $(arg robot)/laser 500" />

</launch>

See Also

Edit - History - Print - Recent Changes - Search
Page last modified on April 13, 2017, at 10:42 PM