]> defiant.homedns.org Git - ros_wild_thumper.git/blob - launch/wild_thumper.launch
1e1bf66e2f9bd046783695201f89c87eda7c61b8
[ros_wild_thumper.git] / launch / wild_thumper.launch
1 <?xml version="1.0"?>
2 <launch>
3         <env name="ROSCONSOLE_CONFIG_FILE" value="$(find wild_thumper)/config/rosconsole.config"/>
4
5         <arg name="use_imu" default="true"/>
6
7         <node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager"/>
8
9         <!--
10         <param name="robot_description" command="$(find xacro)/xacro.py $(find wild_thumper)/urdf/wild_thumper.urdf.xacro"/>
11         -->
12         <param name="robot_description" command="$(find xacro)/xacro.py $(find wt_open_manipulator)/urdf/wild_thumper_with_manipulator.urdf.xacro use_nominal_extrinsics:=false"/>
13
14         <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
15                 <param name="publish_frequency" value="20.0" />
16         </node>
17         <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" output="screen">
18                 <param name="robot_description" command="$(find xacro)/xacro.py $(find wild_thumper)/urdf/wild_thumper.urdf.xacro" />
19         </node>
20
21         <node pkg="diagnostic_aggregator" type="aggregator_node" name="diagnostic_aggregator" output="screen">
22                 <rosparam command="load" file="$(find wild_thumper)/config/analyzers.yaml"/>
23         </node>
24
25         <node pkg="wild_thumper" type="wt_node.py" name="wild_thumper" output="screen" respawn="false" required="true">
26                 <param name="enable_odom_tf" value="true" unless="$(arg use_imu)"/>
27                 <param name="enable_odom_tf" value="false" if="$(arg use_imu)"/>
28         </node>
29
30         <node pkg="tinkerforge_imu_ros" type="tinkerforge_imu_ros" name="tinkerforge_imu_brick2" output="screen" respawn="true" if="$(arg use_imu)">
31                 <param name="uid" value="6DdNSn"/>
32                 <param name="frame_id" value="base_imu_link"/>
33                 <param name="period_ms" value="20"/>
34                 <!-- Observed orientation variance: 0.0 (10k samples)
35                      Magnometer heading accuracy is +-2.5 deg => 0.088 rad
36                      With heading accuracy as std dev, variance = 0.088^2 = 0.008 -->
37                 <param name="variance_orientation" value="0.008"/>
38                 <remap from="/tinkerforge_imu_brick2/imu" to="imu"/>
39         </node>
40
41         <include file="$(find yocs_cmd_vel_mux)/launch/cmd_vel_mux.launch">
42                 <arg name="config_file" value="$(find wild_thumper)/config/cmd_vel_mux.yaml" />
43                 <arg name="nodelet_manager_name" value="nodelet_manager" />
44         </include>
45
46         <node pkg="robot_localization" type="ekf_localization_node" name="ekf" clear_params="true" output="screen" if="$(arg use_imu)">
47                 <rosparam command="load" file="$(find wild_thumper)/config/robot_localization.yaml"/>
48                 <remap from="odometry/filtered" to="odom_combined"/>
49         </node>
50
51         <node pkg="gpsd_client" type="gpsd_client"  name="gpsd_client" output="screen">
52                 <param name="use_gps_time" value="false"/>
53                 <param name="frame_id" value="base_footprint"/>
54         </node>
55
56         <node pkg="robot_localization" type="navsat_transform_node" name="navsat_transform_node" output="screen">
57                 <param name="magnetic_declination_radians" value="0.047"/>
58                 <param name="yaw_offset" value="0.0"/>
59                 <param name="zero_altitude" value="true"/>
60                 <param name="broadcast_utm_transform" value="true"/>
61                 <param name="transform_timeout" value="0.2"/>
62
63                 <remap from="/imu/data" to="imu"/>
64                 <remap from="/gps/fix" to="fix" />
65                 <remap from="/odometry/filtered" to="odom_combined"/>
66                 <remap from="/odometry/gps" to="gps"/>
67         </node>
68
69         <include file="$(find rosbridge_server)/launch/rosbridge_websocket.launch"/>
70
71         <node pkg="wild_thumper" type="sensor_board.py" name="sensor_board" output="screen"/>
72         <node pkg="wild_thumper" type="ledstripe.rb" name="led_stripe" output="screen"/>
73
74         <node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="screen">
75                 <param name="serial_port"         type="string" value="/dev/rplidar"/>
76                 <param name="serial_baudrate"     type="int"    value="115200"/><!--A1/A2 -->
77                 <param name="frame_id"            type="string" value="lidar"/>
78                 <param name="angle_compensate"    type="bool"   value="true"/>
79                 <param name="scan_mode"           type="string" value="Standard"/>
80                 <!--
81                 A2 scan_modes:
82                 Standard: max_distance: 16.0 m, Point number: 2.0K
83                 Express: max_distance: 16.0 m, Point number: 4.0K
84                  -->
85         </node>
86 </launch>