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

Revision history [back]

I can see the following issues in your config:

  1. You are fusing two absolute sources of absolute pose data: you have yaw set to true for both of your inputs. Unless you have your covariances properly tuned, I would advise against this. Pick your best source of yaw data (likely the IMU) and only set yaw to true for that. Technically, since you have differential mode turned on for your IMU, you are really fusing yaw from the robot and yaw "velocity" (differentiated yaw) from the IMU, so you won't see the heading jumping back and forth, but see below for information on why this is probably backwards.
  2. You have relative and differential turned on for the IMU, which is a bit meaningless, as I believe differential mode is applied in that case.
  3. You're not using any velocity data. Unlike pose data, fusing disparate source of velocity data, even when the covariances aren't all that well tuned, will cause less erratic behavior.

Regardless, the main crux of your issue is that you are essentially telling the filter to fuse only the data from the Pioneer odometry. Absolute pose data will have a greater effect on filter output than velocity data, so your differentiated IMU pose (which gets turned into velocity by differential mode) is effectively being ignored. Also, if your IMU provides angular velocity, it typically comes from a completely different sensor (i.e., a gyroscope as opposed to a magnetometer), so you should really be fusing yaw velocity. Try this instead:

<param name="imu0" value="imu/data"/>
<rosparam param="imu0_config">[false, false, false,
                               false, false, true,
                               false, false, false,
                               false, false, true,
                               false,  false, false]</rosparam>
<param name="imu0_differential" value="false"/>

<param name="odom0" value="/odom/fixed_wheel"/>
<rosparam param="odom0_config">[false, false, false, 
                                false, false, false, 
                                true, true, false, 
                                false, false, true,
                                false, false, false]</rosparam>

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

You may want to disable yaw in your IMU altogether if you find it suddenly shifts for no reason while driving. Magnetometers are notoriously awful in the presence of sources of distortion. You may also want to re-enable X and Y in your odometry and disable X and Y velocity. Experiment with it, but whatever you do, don't enable yaw on your Pioneer wheel odometry.

I can see the following issues in your config:

  1. You are fusing two absolute sources of absolute pose data: you have yaw set to true for both of your inputs. Unless you have your covariances properly tuned, I would advise against this. Pick your best source of yaw data (likely the IMU) and only set yaw to true for that. Technically, since you have differential mode turned on for your IMU, you are really fusing yaw from the robot and yaw "velocity" (differentiated yaw) from the IMU, so you won't see the heading jumping back and forth, but see below for information on why this is probably backwards.
  2. You have relative and differential turned on for the IMU, which is a bit meaningless, as I believe differential mode is applied in that case.
  3. You're not using any velocity data. Unlike pose data, fusing disparate source of velocity data, even when the covariances aren't all that well tuned, will cause less erratic behavior.

Regardless, the main crux of your issue is that you are essentially telling the filter to fuse only the data from the Pioneer odometry. Absolute pose data will have a greater effect on filter output than velocity data, so your differentiated IMU pose (which gets turned into velocity by differential mode) is effectively being ignored. ignored (really, it's just smoothing the transition between yaw measurements from your wheel odometry). Also, if your IMU provides angular velocity, it typically comes from a completely different sensor (i.e., a gyroscope as opposed to a magnetometer), so you should really be fusing yaw velocity. Try this instead:

<param name="imu0" value="imu/data"/>
<rosparam param="imu0_config">[false, false, false,
                               false, false, true,
                               false, false, false,
                               false, false, true,
                               false,  false, false]</rosparam>
<param name="imu0_differential" value="false"/>

<param name="odom0" value="/odom/fixed_wheel"/>
<rosparam param="odom0_config">[false, false, false, 
                                false, false, false, 
                                true, true, false, 
                                false, false, true,
                                false, false, false]</rosparam>

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

You may want to disable yaw in your IMU altogether if you find it suddenly shifts for no reason while driving. Magnetometers are notoriously awful in the presence of sources of distortion. You may also want to re-enable X and Y in your odometry and disable X and Y velocity. Experiment with it, but whatever you do, don't enable yaw on your Pioneer wheel odometry.

I can see the following issues in your config:

  1. You are fusing two absolute sources of absolute pose data: you have yaw set to true for both of your inputs. Unless you have your covariances properly tuned, I would advise against this. Pick your best source of yaw data (likely the IMU) and only set yaw to true for that. Technically, since you have differential mode turned on for your IMU, you are really fusing yaw from the robot and yaw "velocity" (differentiated yaw) from the IMU, so you won't see the heading jumping back and forth, but see below for information on why this is probably backwards.
  2. You have relative and differential turned on for the IMU, which is a bit meaningless, as I believe differential mode is applied in that case.
  3. You're not using any velocity data. Unlike pose data, fusing disparate source of velocity data, even when the covariances aren't all that well tuned, will cause less erratic behavior.

Regardless, the main crux of your issue is that you are essentially telling the filter to fuse only the data from the Pioneer odometry. Absolute pose data will have a greater effect on filter output than velocity data, so your differentiated IMU pose (which gets turned into velocity by differential mode) is effectively being ignored (really, it's just smoothing the transition between yaw measurements from your wheel odometry). Also, if your IMU provides angular velocity, it typically comes from a completely different sensor (i.e., a gyroscope as opposed to a magnetometer), so you should really be fusing yaw velocity. Try this instead:

<param name="imu0" value="imu/data"/>
<rosparam param="imu0_config">[false, false, false,
                               false, false, true,
                               false, false, false,
                               false, false, true,
                               false,  false, false]</rosparam>
<param name="imu0_differential" value="false"/>

<param name="odom0" value="/odom/fixed_wheel"/>
<rosparam param="odom0_config">[false, false, false, 
                                false, false, false, 
                                true, true, false, 
                                false, false, true,
                                false, false, false]</rosparam>

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

You may want to disable yaw in your IMU altogether if you find it suddenly shifts for no reason while driving. Magnetometers are notoriously awful in the presence of sources of distortion. You may also want to re-enable X and Y in your odometry and disable X and Y velocity. Experiment with it, but whatever you do, don't enable yaw on your Pioneer wheel odometry.

EDIT 1:

Your Pioneer odometry appears to be missing a child_frame_id. Not sure why that is, but it will prevent the EKF from using the velocity data in the odometry message.