]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
Testing robot_localization
authorErik Andresen <erik@vontaene.de>
Wed, 14 Jun 2017 19:40:18 +0000 (21:40 +0200)
committerErik Andresen <erik@vontaene.de>
Wed, 14 Jun 2017 19:40:18 +0000 (21:40 +0200)
launch/robot_localization.launch
launch/wild_thumper.launch

index a6e408dfaf8144cd14b4346c218b81fa805457f9..d3da3176d126d101ecd6ba882f80d79413ce5d0a 100644 (file)
@@ -67,7 +67,6 @@
                   parameters obviously have no default values, and must be specified. -->
                <param name="odom0" value="odom"/>
                <param name="imu0" value="imu"/>
-               <param name="odom1" value="gps"/>
 
                <!-- Each sensor reading updates some or all of the filter's state. These options give you greater control over
                   which values from each measurement are fed to the filter. For example, if you have an odometry message as input,
                   message types lack certain variables. For example, a TwistWithCovarianceStamped message has no pose information, so
                   the first six values would be meaningless in that case. Each vector defaults to all false if unspecified, effectively
                   making this parameter required for each sensor. -->
-               <rosparam param="odom0_config">[true, true, false, false, false, true, true, true, false, false, false, true, true, true, false]</rosparam>
-               <rosparam param="imu0_config">[false, false, false, true, true, true, false, false, false, true, true, true, true, true, true]</rosparam>
-               <rosparam param="odom1_config">[true, true, true, false, false, false, false, false, false, false, false, false, false, false, false]</rosparam>
-
+               <!-- x/y not included because of redundancy with velocities -->
+               <!-- vyaw not included in odom because too inaccurate -->
+               <rosparam param="odom0_config">[false, false, false, false, false, false, true, true, false, false, false, false, false, false, false]</rosparam>
+               <rosparam param="imu0_config">[false, false, false, false, false, true, false, false, false, false, false, true, false, false, false]</rosparam>
 
                <!-- The best practice for including new sensors in robot_localization's state estimation nodes is to pass in velocity
                   measurements and let the nodes integrate them. However, this isn't always feasible, and so the state estimation
@@ -97,9 +96,8 @@
                   integration of velocities leads to slowly increasing error in the absolute (pose) variable. For position variables,
                   this is acceptable. For orientation variables, it can lead to trouble. Users should make sure that all orientation
                   variables have at least one source of absolute measurement. -->
-               <param name="odom0_differential" value="true"/>
+               <param name="odom0_differential" value="false"/>
                <param name="imu0_differential" value="false"/>
-               <param name="odom1_differential" value="false"/>
 
                <!-- When the node starts, if this parameter is true, then the first measurement is treated as a "zero point" for all
                   future measurements. While you can achieve the same effect with the differential paremeter, the key difference is
                   you simply want your measurements to start at 0 for a given sensor, set this to true. -->
                <param name="odom0_relative" value="false"/>
                <param name="imu0_relative" value="false"/>
-               <param name="odom1_relative" value="true"/>
 
                <!-- If we're including accelerations in our state estimate, then we'll probably want to remove any acceleration that
                   is due to gravity for each IMU. If you don't want to, then set this to false. Defaults to false if unspecified. -->
                <param name="print_diagnostics" value="true"/>
 
                <remap from="odometry/filtered" to="odom_combined"/>
-
        </node>
-
 </launch>
index 7fd4e59574d8eb26b79449446aad9b3d7c8e6a80..9f2c28769b1640e084175144c0e7357e6db2f1b0 100644 (file)
                <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"/>
+       <node pkg="wild_thumper" type="tinkerforge_imu2.py" name="tinkerforge_imu_brick2" output="screen">
+               <param name="uid" value="6DdNSn"/>
+       </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" output="screen">
-               <remap from="odom" to="gps"/>
-               <param name="frame_id" value="odom"/>
-               <param name="child_frame_id" value="base_footprint"/>
-       </node>
+       <include file="$(find yocs_cmd_vel_mux)/launch/cmd_vel_mux.launch">
+               <arg name="config_file" value="$(find wild_thumper)/config/cmd_vel_mux.yaml" />
+               <arg name="nodelet_manager_name" value="nodelet_manager" />
+       </include>
 
        <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="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="true"/>
+               <param name="vo_used" value="false"/>
                <param name="debug" value="false"/>
                <param name="sensor_timeout" value="2.0"/>
        </node>
 
-       <include file="$(find yocs_cmd_vel_mux)/launch/cmd_vel_mux.launch">
-               <arg name="config_file" value="$(find wild_thumper)/config/cmd_vel_mux.yaml" />
-               <arg name="nodelet_manager_name" value="nodelet_manager" />
-       </include>
+       <node pkg="gps_common" type="utm_odometry_node" name="gps_conv" output="screen">
+               <remap from="odom" to="gps"/>
+               <param name="frame_id" value="odom"/>
+               <param name="child_frame_id" value="base_footprint"/>
+       </node>
+
+       <!--
+       <include file="$(find wild_thumper)/launch/robot_localization.launch" if="$(arg use_imu)"/>
+       <node pkg="robot_localization" type="navsat_transform_node" name="navsat_transform_node">
+               <param name="magnetic_declination_radians" value="0.48"/>
+               <param name="yaw_offset" value="1.5708"/>
+               <param name="zero_altitude" value="true"/>
+               <param name="broadcast_utm_transform" value="true"/>
+
+               <remap from="/imu/data" to="imu"/>
+               <remap from="/gps/fix" to="fix" />
+               <remap from="/odometry/filtered" to="odom_combined"/>
+               <remap from="/odometry/gps" to="gps"/>
+       </node>
+       -->
 </launch>