ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

navsat_transform_node gives zero output and warning in robot_localisation_node gives a warning - could not obtain transform

asked 2016-06-14 06:36:40 -0500

Anirvan0102 gravatar image

updated 2016-06-15 05:03:52 -0500

Hello I am new to ROS and using Robot_localisation package. As given in the tutorial I ran two instances of ekf_localisation. My navsat transform node gives zero output and I keep getting a warning : Could not obtain transform from gps_link to base_link. Error was "gps_link" passed to lookupTransform argument source_frame does not exist.

My launch file is :-

<!-- Test launch file for two EKF instances and one navsat_transform instance -->

<launch>

  <node pkg="tf2_ros" type="static_transform_publisher" name="bl_imu" args="0 0 0 0 0 0 1 base_link imu_link" />

  <!-- Local (odom) instance -->
  <node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization_local" clear_params="true">
    <param name="frequency" value="30"/>
    <param name="sensor_timeout" value="0.1"/>
    <param name="two_d_mode" value="true"/>

    <param name="map_frame" value="map"/>
    <param name="odom_frame" value="odom"/>
    <param name="base_link_frame" value="base_link"/>
    <param name="world_frame" value="odom"/>

    <param name="transform_time_offset" value="0.0"/>

    <param name="odom0" value="/RosAria/pose"/>
    <param name="imu0" value="/imu_data"/>

    <rosparam param="odom0_config">[false, false, false,
                                    false, false, false,
                                    true, true, true,
                                    false, false, true,
                                    false, false, false]</rosparam>

    <rosparam param="imu0_config">[false, false, false,
                                   true,  true,  true,
                                   false, false, false,
                                   true,  true,  true,
                                   true,  true,  true]</rosparam>

    <param name="odom0_differential" value="false"/>
    <param name="imu0_differential" value="false"/>

    <param name="odom0_relative" value="false"/>
    <param name="imu0_relative" value="false"/>

    <param name="imu0_remove_gravitational_acceleration" value="true"/>
    <param name="print_diagnostics" value="true"/>

    <param name="odom0_queue_size" value="10"/>
    <param name="imu0_queue_size" value="10"/>

    <param name="debug"           value="false"/>
    <param name="debug_out_file"  value="debug_ekf_localization.txt"/>

    <remap from="/odometry/filtered" to="/odometry/filtered/local"/>
  </node>

  <!-- Global (map) instance -->
  <node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization_global" clear_params="true">
    <param name="frequency" value="30"/>
    <param name="sensor_timeout" value="0.1"/>
    <param name="two_d_mode" value="true"/>

    <param name="map_frame" value="map"/>
    <param name="odom_frame" value="odom"/>
    <param name="base_link_frame" value="base_link"/>
    <param name="world_frame" value="map"/>

    <param name="transform_time_offset" value="0.0"/>

    <param name="odom0" value="/RosAria/pose"/>
    <param name="odom1" value="/odometry/gps"/>
    <param name="imu0" value="/imu_data"/>

    <rosparam param="odom0_config">[false, false, false,
                                    false, false, false,
                                    true, true, true,
                                    false, false, true,
                                    false, false, false]</rosparam>

    <rosparam param="odom1_config">[true, true, false,
                                    false, false, false,
                                    false, false, false,
                                    false, false, false,
                                    false, false, false]</rosparam>

    <rosparam param="imu0_config">[false, false, false,
                                   true,  true,  true,
                                   false, false, false,
                                   true,  true,  true,
                                   true,  true,  true]</rosparam>

    <param name="odom0_differential" value="false"/>
    <param name="odom1_differential" value="false"/>
    <param name="imu0_differential" value="false"/>

    <param name="odom0_relative" value="false"/>
    <param name="odom1_relative" value="false"/>
    <param name="imu0_relative" value="false"/>

    <param name="imu0_remove_gravitational_acceleration" value="true"/>
    <param name="print_diagnostics" value="true"/>

    <param name="odom0_queue_size" value="10"/>
    <param name="odom1_queue_size" value="10"/>
    <param name="imu0_queue_size" value="10"/>

    <param name="debug"           value="false"/>
    <param name="debug_out_file"  value="debug_ekf_localization.txt"/>

    <remap from="/odometry/filtered" to="/odometry/filtered/global"/>
 </node>

 <!-- navsat_transform -->
 <node pkg="robot_localization" type="navsat_transform_node" name="navsat_transform" respawn="true" output="screen">
    <param name="frequency" value="30"/>
    <param name="delay" value="3"/>
    <param name="magnetic_declination_radians" value="0.05"/>
    <param name="yaw_offset" value="0"/>
    <param name="zero_altitude" value="true"/>
    <param name="broadcast_utm_transform" value="true"/>
    <param name="publish_filtered_gps" value="true ...
(more)
edit retag flag offensive close merge delete

Comments

Thanks for this. There's an issue on the GH page for r_l regarding this very thing, so I'll look into it today or tomorrow.

Tom Moore gravatar image Tom Moore  ( 2016-06-14 06:55:05 -0500 )edit

Hello Tom, thanks for replying so quick. I included a static transform of base_link ->gps_link in the launch file and the warning message stopped also navsat_transform node gave the output in robot's local frame .

Anirvan0102 gravatar image Anirvan0102  ( 2016-06-14 09:12:46 -0500 )edit

this was the line I added in the launch file <node pkg="tf2_ros" type="static_transform_publisher" name="bl_gps" args="0 0 0 0 0 0 1 base_link gps_link"/> but I am getting terrible output from the odometry/filtered/global

Anirvan0102 gravatar image Anirvan0102  ( 2016-06-14 09:13:51 -0500 )edit

hi, @Anirvan0102, can you check your /odometry/gps topic ? is it NAN when you set use_odometry_yaw= false in navsat_transform_node? I met the same problem with you. but I just got one warning info of it, because I set the static tf transform.

asimay_y gravatar image asimay_y  ( 2016-06-14 09:23:49 -0500 )edit

Hey asimay_y, it is not NAN but the pose was exact zero and it was not changing as I was changing my robot's position. Later I set the static tf and I was getting the ouput of odometry/gps but my odometry/filtered/global was giving poor estimate.

Anirvan0102 gravatar image Anirvan0102  ( 2016-06-14 11:58:06 -0500 )edit

can you share your rosbag files and node graph? I also get poor estimate, and digging the cause..

asimay_y gravatar image asimay_y  ( 2016-06-14 12:17:26 -0500 )edit

Where is the attached bag file?

Tom Moore gravatar image Tom Moore  ( 2016-06-15 03:53:54 -0500 )edit

Sure asimay_y ... here is my bag file https://drive.google.com/open?id=0B3o... . My launch file is https://drive.google.com/open?id=0B3o... . I will be thankful to you if you could find out some solution, I have been stuck here for quite a time

Anirvan0102 gravatar image Anirvan0102  ( 2016-06-15 04:21:00 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2016-06-15 05:37:40 -0500

Tom Moore gravatar image

First, grab the latest source from the upstream repository.

Second, fix the following issues:

  1. Not sure how you recorded your bag file, but it looks to me like something other than ekf_localization_node is publishing the odom->base_link transform for your robot. You can't have two nodes publishing the same transform. Looking at the ROSARIA code, it appears to always publish the odom->base_link transform, and it appears you can't configure it. You'll have to either modify the ROSARIA code, use a different Pioneer ROS driver, or get rid of your odom instance of ekf_localization_node.
  2. (Minor, doesn't really affect anything) You have two_d_mode set to true, but you are fusing lots of 3D variables, including Z velocity from your odometry source and roll, pitch, their velocities, and Z acceleration from the IMU. Those will be ignored unless you turn of two_d_mode.
  3. In your odom EKF instance, you are fusing odometry variables that make sense, namely, the velocities. However, in your map instance, you are fusing absolute X and Y from both your GPS and your whee odometry. Those will probably not agree with each other, and the filter is going to jump back and forth rapidly.
  4. You are fusing the output of the odom EKF as an input to the map EKF. For a number of reasons, this isn't a good idea. Use the same raw input data for both.
  5. For some reason, your RosAria/pose topic has horrific covariances for yaw and yaw velocity, on the order of 1000.0. I'm going to venture a guess that the error on your rotational velocity is not 1000.0. This issue is very important, because it's going to cause strange behavior in the filter output. For example, when the robot turns, you may see lateral motion instead. This must be fixed.
  6. Your IMU data is really suspect. First, it's very low frequency, but beyond that, it also is all over the place. Do a rostopic echo /imu/data and watch it for a little.

You need to go back and do one thing at a time: make sure all your raw sensor data conforms to standards and is correct. Then fuse one sensor - e.g., odometry - into an EKF and make sure the output makes sense. Then fuse another sensor and verify again.

edit flag offensive delete link more

Comments

Thank you Tom. I will try to make the necessary changes in the code.

Anirvan0102 gravatar image Anirvan0102  ( 2016-06-15 08:43:51 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-06-14 06:36:40 -0500

Seen: 969 times

Last updated: Jun 15 '16