]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
added gpsd client
authorErik Andresen <erik@vontaene.de>
Sat, 18 Jul 2015 20:46:10 +0000 (22:46 +0200)
committerErik Andresen <erik@vontaene.de>
Sat, 18 Jul 2015 20:46:10 +0000 (22:46 +0200)
cfg/analyzers.yaml
launch/wild_thumper.launch

index f2327c5610b6feceb0d7838ba85aad4c8ea9fb7f..76d0bc08c5d8bf5c069761dc819aa4645e4e3928 100644 (file)
@@ -1,16 +1,16 @@
 analyzers:
         motors:
-                type: GenericAnalyzer
+                type: diagnostic_aggregator/GenericAnalyzer
                 path: Motors
                 startswith: 'Motor'
                 find_and_remove_prefix: motor
         reset:
-                type: GenericAnalyzer
+                type: diagnostic_aggregator/GenericAnalyzer
                 path: Reset
                 startswith: 'Reset'
                 timeout: -1
         voltage:
-                type: GenericAnalyzer
+                type: diagnostic_aggregator/GenericAnalyzer
                 path: Voltage
                 startswith: 'Voltage'
         Razor9DofImu:
index b0aa2ea0dd1cbadfe1856d4c552a545d82310053..c7c88ef995a8a0adb5762b22c5930e4b84d9c05b 100644 (file)
@@ -1,30 +1,41 @@
 <?xml version="1.0"?>
 <launch>
-       <arg name="use_imu" default="true" />
+       <arg name="use_imu" default="true"/>
 
-       <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 wild_thumper)/urdf/wild_thumper.urdf.xacro"/>
 
-       <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
+       <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen"/>
 
-       <node pkg="diagnostic_aggregator" type="aggregator_node" name="diagnostic_aggregator" >
-               <rosparam command="load" file="$(find wild_thumper)/cfg/analyzers.yaml" />
+       <node pkg="diagnostic_aggregator" type="aggregator_node" name="diagnostic_aggregator" output="screen">
+               <rosparam command="load" file="$(find wild_thumper)/cfg/analyzers.yaml"/>
        </node>
 
        <node pkg="wild_thumper" type="wt_node.py" name="wild_thumper" output="screen" respawn="true">
-               <param name="enable_odom_tf" value="true" unless="$(arg use_imu)" />
-               <param name="enable_odom_tf" value="false" if="$(arg use_imu)" />
+               <param name="enable_odom_tf" value="true" unless="$(arg use_imu)"/>
+               <param name="enable_odom_tf" value="false" if="$(arg use_imu)"/>
        </node>
 
        <node pkg="razor_imu_9dof" type="imu_node.py" name="imu_node" output="screen" if="$(arg use_imu)">
                <rosparam file="$(find wild_thumper)/cfg/razor.yaml" command="load"/>
        </node>
 
+       <node pkg="gpsd_client" type="gpsd_client"  name="gpsd_client" output="screen">
+               <param name="use_gps_time" value="false"/>
+       </node>
+
+       <node pkg="gps_common" type="utm_odometry_node" name="gps_conv">
+               <remap from="odom" to="odom_gps"/>
+               <param name="frame_id" value="base_footprint"/>
+       </node>
+
        <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen" if="$(arg use_imu)">
                <remap from="imu_data" to="imu"/>
+               <remap from="vo" to="odom_gps"/>
                <remap from="robot_pose_ekf/odom_combined" to="odom_combined"/>
                <param name="output_frame" value="odom"/>
                <param name="freq" value="20.0"/>
-               <param name="vo_used" value="false"/>
+               <param name="vo_used" value="true"/>
                <param name="debug" value="true"/>
+               <param name="sensor_timeout" value="2.0"/>
        </node>
 </launch>