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

Revision history [back]

It would probably be easier to just post your configuration files from r_l, but I think I have the gist of what you're saying. Also, as some of these questions are unrelated, it might be better in the future to ask multiple questions. Regardless, here goes:

Answer to Q1

If your sensor configuration is set to only fuse X velocity, Y velocity, yaw, yaw velocity, and X acceleration, then the covariance matrix values for the other values don't matter (i.e., you can set them to anything). The filter will only use the state and covariance data from the variables you decide to fuse.

Answer to Q2

You are not fusing X, Y, and yaw from the wheel encoders, so their covariance values don't matter. In general, though, you would usually see static covariances for the velocity data that accumulates in the pose data.

Answer to Q3

The _differential setting only applies to pose variables. It will differentiate pose measurements and generate velocities from them, then fuse those values. You need to set the pose variables to true in the sensor configuration in that case. The _differential parameter is meaningless for twist data.

Answer to Q4

The use case for the _differential parameter is pretty small: if you have two pose inputs that measure the same variable, but they diverge from each other, you can use the _differential parameter to force one (or both) of them to be treated as a velocity, which will keep the filter's pose output from oscillating. In your configuration above, you are fusing only one pose variable (yaw), with the rest being velocities and accelerations, so you're all set.

Answer to Q5

Again, this won't apply to you, but in general, the _relative and _differential parameters are mutually exclusive. In fact, if you set both to true, the relative parameter gets ignored.

Answer to Q6

It's up to you, really. Ideally, you would have some principled means of determining the covariance data for your sensors, and then just set the initial_estimate_covariance to be larger than at least one of them. This is just to aid in accepting the initial measurements from your sensors: if the EKF's initial yaw velocity variance is 0.00001, and the first IMU measurement has a yaw velocity variance of 0.01, the filter isn't going to trust the measurement very much, and so it will be slow to converge. If both of your sensors have relatively high frequencies, it won't really matter whether the initial variance is higher than only one of them, since you're bound to get a measurement very quickly.

It would probably be easier to just post your configuration files from r_l, but I think I have the gist of what you're saying. Also, as some of these questions are unrelated, it might be better in the future to ask multiple questions. Regardless, here goes:

Answer to Q1

If your sensor configuration is set to only fuse X velocity, Y velocity, yaw, yaw velocity, and X acceleration, then the covariance matrix values for the other values don't matter (i.e., you can set them to anything). The filter will only use the state and covariance data from the variables you decide to fuse.

Answer to Q2

You are not fusing X, Y, and yaw from the wheel encoders, so their covariance values don't matter. In general, though, you would usually see static covariances for the velocity data that accumulates in the pose data.

Answer to Q3

The _differential setting only applies to pose variables. It will differentiate pose measurements and generate velocities from them, then fuse those values. You need to set the pose variables to true in the sensor configuration in that case. The _differential parameter is meaningless for twist data.

Answer to Q4

The use case for the _differential parameter is pretty small: if you have two pose inputs that measure the same variable, but they diverge from each other, you can use the _differential parameter to force one (or both) of them to be treated as a velocity, which will keep the filter's pose output from oscillating. In your configuration above, you are fusing only one pose variable (yaw), with the rest being velocities and accelerations, so you're all set.

Answer to Q5

Again, this won't apply to you, but in general, the _relative and _differential parameters are mutually exclusive. In fact, if you set both to true, the relative parameter gets ignored.

Answer to Q6

It's up to you, really. Ideally, you would have some principled means of determining the covariance data for your sensors, and then just set the initial_estimate_covariance to be larger than at least one of them. This is just to aid in accepting the initial measurements from your sensors: if the EKF's initial yaw velocity variance is 0.00001, and the first IMU measurement has a yaw velocity variance of 0.01, the filter isn't going to trust the measurement very much, and so it will be slow to converge. If both of your sensors have relatively high frequencies, it won't really matter whether the initial variance is higher than only one of them, since you're bound to get a measurement very quickly.

Answer to Q7

The number of measurements in the update cycle is irrelevant. The filter will look at the delta between the last measurement time stamp and the current one, do a predict across that time step, then correct for the new measurement, and update the last measurement time stamp. If there is another measurement in the queue, it will do the same thing, and so on, until the queue is empty.

Answer to Q8

I'd prefer not to make assumptions about what data you plan to fuse. I expect users are going to have to tweak parameters to get things working optimally. I also address this very issue in the wiki.

Answer to Q9

Many IMUs will report their error rates in their documentation. For odometry, I've previously used a source of ground truth, e.g., motion capture systems, to determine error rates. You could do less high-tech versions and try things as simple as driving your robot in a long, straight line, and seeing how the measured distance traveled compares to your odometry.

If you have further questions, I would recommend posting them as new questions, rather than adding any more to this one.