]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - launch/wild_thumper.launch
configuration with manipulator
[ros_wild_thumper.git] / launch / wild_thumper.launch
index 88b66580db9cc20ecf3e4952c41f07156d588c16..ec21d0b80b5ff615e116e5294f2851c7ee8ca1d2 100644 (file)
@@ -6,12 +6,17 @@
 
        <node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager"/>
 
+       <!--
        <param name="robot_description" command="$(find xacro)/xacro.py $(find wild_thumper)/urdf/wild_thumper.urdf.xacro"/>
+       -->
+       <param name="robot_description" command="$(find xacro)/xacro.py $(find wt_open_manipulator)/urdf/wild_thumper_with_manipulator.urdf.xacro use_nominal_extrinsics:=false"/>
 
        <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
                <param name="publish_frequency" value="20.0" />
        </node>
-       <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" output="screen"/>
+       <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" output="screen">
+               <param name="robot_description" command="$(find xacro)/xacro.py $(find wild_thumper)/urdf/wild_thumper.urdf.xacro" />
+       </node>
 
        <node pkg="diagnostic_aggregator" type="aggregator_node" name="diagnostic_aggregator" output="screen">
                <rosparam command="load" file="$(find wild_thumper)/config/analyzers.yaml"/>
@@ -22,7 +27,7 @@
                <param name="enable_odom_tf" value="false" if="$(arg use_imu)"/>
        </node>
 
-       <node pkg="wild_thumper" type="tinkerforge_imu2.py" name="tinkerforge_imu_brick2" output="screen" if="$(arg use_imu)">
+       <node pkg="wild_thumper" type="tinkerforge_imu2.py" name="tinkerforge_imu_brick2" output="screen" respawn="true" if="$(arg use_imu)">
                <param name="uid" value="6DdNSn"/>
        </node>
 
        <include file="$(find rosbridge_server)/launch/rosbridge_websocket.launch"/>
 
        <node pkg="wild_thumper" type="sensor_board.py" name="sensor_board" output="screen"/>
+       <node pkg="wild_thumper" type="ledstripe.rb" name="led_stripe" output="screen"/>
+
+       <node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="screen">
+               <param name="serial_port"         type="string" value="/dev/rplidar"/>
+               <param name="serial_baudrate"     type="int"    value="115200"/><!--A1/A2 -->
+               <param name="frame_id"            type="string" value="lidar"/>
+               <param name="angle_compensate"    type="bool"   value="true"/>
+               <param name="scan_mode"           type="string" value="Standard"/>
+               <!--
+               A2 scan_modes:
+               Standard: max_distance: 16.0 m, Point number: 2.0K
+               Express: max_distance: 16.0 m, Point number: 4.0K
+                -->
+       </node>
 </launch>