Skip to content

Commit

Permalink
added android_map_nav app
Browse files Browse the repository at this point in the history
  • Loading branch information
hershwg committed Jun 13, 2011
1 parent c72cddd commit 3ad5103
Show file tree
Hide file tree
Showing 4 changed files with 129 additions and 0 deletions.
1 change: 1 addition & 0 deletions .hgignore
Original file line number Diff line number Diff line change
Expand Up @@ -34,3 +34,4 @@ libdmtx/share
libdmtx/include
libdmtx/installed
/bin/
turtlebot_follower/lib/libturtlebot_follower.so$
40 changes: 40 additions & 0 deletions turtlebot_navigation/config/amcl_turtlebot_map_from_topic.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
<launch>
<node pkg="amcl" type="amcl" name="amcl" args="scan:=/scan">

<param name="use_map_topic" value="true"/>
<!-- Publish scans from best pose at a max of 10 Hz -->
<param name="odom_model_type" value="diff"/>
<param name="odom_alpha5" value="0.1"/>
<param name="gui_publish_rate" value="10.0"/>
<param name="laser_max_beams" value="60"/>
<param name="laser_max_range" value="12.0"/>
<param name="min_particles" value="500"/>
<param name="max_particles" value="2000"/>
<param name="kld_err" value="0.05"/>
<param name="kld_z" value="0.99"/>
<param name="odom_alpha1" value="0.2"/>
<param name="odom_alpha2" value="0.2"/>
<!-- translation std dev, m -->
<param name="odom_alpha3" value="0.2"/>
<param name="odom_alpha4" value="0.2"/>
<param name="laser_z_hit" value="0.5"/>
<param name="laser_z_short" value="0.05"/>
<param name="laser_z_max" value="0.05"/>
<param name="laser_z_rand" value="0.5"/>
<param name="laser_sigma_hit" value="0.2"/>
<param name="laser_lambda_short" value="0.1"/>
<param name="laser_model_type" value="likelihood_field"/>
<!-- <param name="laser_model_type" value="beam"/> -->
<param name="laser_likelihood_max_dist" value="2.0"/>
<param name="update_min_d" value="0.25"/>
<param name="update_min_a" value="0.2"/>
<param name="odom_frame_id" value="odom_combined"/>
<param name="resample_interval" value="1"/>
<!-- Increase tolerance because the computer can get quite busy -->
<param name="transform_tolerance" value="1.0"/>
<param name="recovery_alpha_slow" value="0.0"/>
<param name="recovery_alpha_fast" value="0.0"/>
<remap from="scan" to="narrow_scan"/>

</node>
</launch>
13 changes: 13 additions & 0 deletions turtlebot_teleop/android_map_nav.app
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
display: Map Nav
description: Drive a turtlebot around a pre-made map from an Android device.
platform: turtlebot
launch: turtlebot_teleop/android_map_nav.launch
interface: turtlebot_teleop/android_teleop.interface
icon: turtlebot_teleop/map.jpg
clients:
- type: android
manager:
api-level: 9
intent-action: ros.android.mapnav.MapNav
app:
gravityMode: 0
75 changes: 75 additions & 0 deletions turtlebot_teleop/android_map_nav.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,75 @@
<launch>
<!-- convert to a capability -->
<include file="$(find turtlebot_bringup)/base.launch" />

<param name="camera/rgb/image_color/compressed/jpeg_quality" value="22"/>

<include file="$(find openni_camera)/launch/kinect_frames.launch"/>

<!-- Make a slower camera feed available. -->
<node pkg="topic_tools" type="throttle" name="camera_throttle" output="screen"
args="messages camera/rgb/image_color/compressed 5"/>

<node pkg="tf" type="change_notifier" name="tf_throttle_for_android_gui" output="screen">
<param name="polling_frequency" value="5"/>
<param name="translational_update_distance" value="-1"/>
<param name="angular_update_distance" value="-1"/>
<rosparam param="frame_pairs">
- {source_frame: base_footprint, target_frame: map}
- {source_frame: kinect_depth_frame, target_frame: map}
</rosparam>
</node>

<!-- Additions for mapping -->
<!-- Kinect -->
<node pkg="nodelet" type="nodelet" name="openni_manager" output="screen" respawn="true" args="manager"/>

<node pkg="nodelet" type="nodelet" name="openni_camera" args="load openni_camera/OpenNINodelet openni_manager" respawn="true">
<param name="rgb_frame_id" value="kinect_rgb_optical_frame" />
<param name="depth_frame_id" value="kinect_depth_optical_frame" />
<param name="depth_registration" value="true" />
<param name="image_mode" value="2" />
<param name="depth_mode" value="2" />
<param name="debayering" value="2" />
<param name="depth_time_offset" value="0" />
<param name="image_time_offset" value="0" />

<rosparam command="load" file="$(find openni_camera)/info/openni_params.yaml" />
</node>

<!-- throttling -->
<node pkg="nodelet" type="nodelet" name="pointcloud_throttle" args="load pointcloud_to_laserscan/CloudThrottle openni_manager" respawn="true">
<param name="max_rate" value="20.0"/>
<remap from="cloud_in" to="/camera/depth/points"/>
<remap from="cloud_out" to="cloud_throttled"/>
</node>

<!-- Fake Laser -->
<node pkg="nodelet" type="nodelet" name="kinect_laser" args="load pointcloud_to_laserscan/CloudToScan openni_manager" respawn="true">
<param name="output_frame_id" value="/kinect_depth_frame"/>
<!-- heights are in the (optical?) frame of the kinect -->
<param name="min_height" value="-0.15"/>
<param name="max_height" value="0.15"/>
<remap from="cloud" to="/cloud_throttled"/>
</node>

<!-- Fake Laser (narrow one, for localization -->
<node pkg="nodelet" type="nodelet" name="kinect_laser_narrow" args="load pointcloud_to_laserscan/CloudToScan openni_manager" respawn="true">
<param name="output_frame_id" value="/kinect_depth_frame"/>
<!-- heights are in the (optical?) frame of the kinect -->
<param name="min_height" value="-0.025"/>
<param name="max_height" value="0.025"/>
<remap from="cloud" to="/cloud_throttled"/>
<remap from="scan" to="/narrow_scan"/>
</node>

<!--- Run Move Base and Robot Pose EKF -->
<include file="$(find turtlebot_navigation)/config/move_base_turtlebot.launch" />

<!-- Load the maps from a warehouse. -->
<include file="$(find warehouse)/launch/warehouse.launch"/>
<node pkg="map_store" type="map_loader" name="map_loader" output="screen"/>

<!--- Run AMCL -->
<include file="$(find turtlebot_navigation)/config/amcl_turtlebot_map_from_topic.launch" />
</launch>

0 comments on commit 3ad5103

Please sign in to comment.