]> defiant.homedns.org Git - ros_roboint.git/blobdiff - explorer_configuration.launch
rename chatter_pub to pub_inputs
[ros_roboint.git] / explorer_configuration.launch
index f9e4302caeef3fdaadf927bf25f4fc5207d2e7ca..4bff958d95845818ee8c56014dd4e0fc6bb7177e 100644 (file)
@@ -1,9 +1,18 @@
+<?xml version="1.0"?>
 <launch>
+       <param name="robot_description" textfile="$(find roboint)/urdf/explorer.urdf" />
+
        <node pkg="roboint" type="libft_adapter" name="libft_adapter" output="screen">
-               <param name="odom_param" value="param_value" />
        </node>
 
        <node pkg="roboint" type="robo_explorer.py" name="robo_explorer" output="screen">
-               <param name="sensor_param" value="param_value" />
+               <!-- Distance between both wheels in meter (18.55cm) -->
+               <param name="wheel_dist" value="0.1855" />
+               <!-- Size of wheel Diameter in meter (5.15cm) * gear ratio (0.5) = 2.575cm -->
+               <param name="wheel_size" value="0.02575" />
        </node>
+
+       <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
+
+       <include file="$(find roboint)/launch/move_base.launch"/>
 </launch>