0
$\begingroup$

Rosanswers logo

Hello everyone ,

This link odom and imu covariances, is my odom0 and imu0 config,odom_pose_covariace, odom_twist_covariance, imu_orientation_covariace, imu_angular_velocity_covariance and imu_linear_acceleration_covariace picture(sorry ,i can't upload this picture).The left-up of the picture is odom0_config and Imu0_config,according to robot_localization_Fusing Unmeasured Variables,I use odom: X˙,Y˙and yaw˙and imu: yaw,yaw˙and X¨to fuse . The left-down of the picture is imu orientation_covariance,angular_velocity_covariaceandlinear_acceleration_covariance.The right of the picture is odom_pose_covarianceand odom_twist_covariance. Althrough i see some similar questions like these,i still have some confusions :

  • Q1 As we all know ,to 2d differential robot, odom output data: Z, vy(linear_y),vz(linear_z),wx(angular_x) and wy(angular_y)are all zero ,so when we setting the covariance for Z,roll,pitch,vy(linear_y),vz(linear_z),wx(angular_x) and wy(angular_y),should we set them a very very small value like 1e-6 ,or should we set them zero?

  • Q2 In the odom covariance for x,yand yaw,i set them are 0.01,0.01 and 0.1(actually,i have no experiance about how to set them).And then ,i think odom twist is more accurate than pose ,so i set odom_twist_covariance for and yaw˙is smaller than xand yaw. Covariance for is 0.001,and for yaw˙is 0.01.This practice is reasonable ??


In addition to the above questions,i have some questions about robot_localizationparams setting .

  • I see the ~[sensor]_differential , ~[sensor]_relative
  • -The first kind of understaning: i think if one source is enabled differential ,r_l will differentiate the variables which be used to fuse.For example,If we set odom0_config is X˙,Y˙and yaw˙and set odom0_differential:true,does it mean that :r_lwill convert X˙,Y˙and yaw˙ to X¨,Y¨,yaw''to following calculation.
  • The second kind of understaning: if one source is enabled differential ,r_l will differentiate the only pose variables X,Y,Z,roll,pitch,yaw.But if when we set odom0_config is X˙,Y˙and yaw˙and set odom0_differential:true,there is none of pose variables such as X,Y,Z,roll,pitch,yaw.
  • Q3So i'm confused about this param meaning.
  • Q4when i see The differential and relative Parameters,i have one odom and one imu .So which sensor i should enable differential,imu or odom ?
  • Q5Suppose we set odom_differential:true ,and imu_differential:false,does it mean that we must also set odom_relative:false and imu_relative:true? For the same sensor,we cannot set its differential and relative the same ,such as : false-false or true-true,because the differential and relative param are opposite meaning? Am i right?
  • Q6 AS @Tom Moore saied in this question, if you are measuring a variable, make the diagonal value in initial_estimate_covariance larger than that measurement's covariance.In my case (one odom and one imu),the diagonal value in initial_estimate_covariance should be larger than odom or imu ,or both of them ? In other words,odom belong to measurement or not ? In our case , odom :X˙,Y˙,yaw˙ are in question( because odom0_config above ) and imu:yaw,yaw˙,X¨(because imu0_config above ) are in question .when we set initial_estimate_covariance for yaw˙, we should larger than whose covariance for yaw˙,odom ? or imu?

Any advice will be appreciated much ,if i describe my question not clearly,please let me know .

JXL China


EDIT1:

  • As Tom saied,when we have greater than or equal to two pose inputs that measure the same variable, but they diverge from each other, we can use the _differential parameter to force one (or all) of them to be treated as a velocity.So in my configure: odom(X',Y',Yaw') and imu(Yaw,Yaw',X'')configs, i should set imu0_differential is false.And because _differential setting only applies to pose variables,it is meaningless for twist data and accle data,So i should set my odom0_differential is false.
  • Q7:when i have one odom and one imu, in r_l EKF update cycle, does it mean there will be one predict step(Kinematic model) and two correct steps,one for odom ,and the other for imu? But when i see the predict step,for one measurement , there will be one predict step and one correct step ,as long as (delta = measurement.time_ - lastMeasurementTime_,delta>0). Am i wrong ?
  • Q8: Why initial_estimate_covariance in ekf_template.yaml is so small(1e-9)? To make filter quickly converge, should we set it a little bigger (1e-3,1e-2 or something)?
  • Q9: you say i should have some principled means of determining the covariance data for my sensors.Did you know whether exist some knowledge or guidance on how to set odom and imu covariance in somewhere?How you did your odom and imu coverance?

Originally posted by jxl on ROS Answers with karma: 252 on 2016-12-30

Post score: 3

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

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.


Originally posted by Tom Moore with karma: 13689 on 2017-01-04

This answer was ACCEPTED on the original site

Post score: 4


Original comments

Comment by jxl on 2017-01-04:
@Tom,thanks very very much!!! To Q4, do you mean for odom(X',Y',Yaw') and imu(Yaw,Yaw',X'')configs,i should set both them _differentialare false,because as you say,i have only one input(imu) for pose(yaw) and _differential is meaningless for twist data?

Comment by jxl on 2017-01-04:
To Q6, you say i should have some principled means of determining the covariance data for my sensors.Did you know whether exist some knowledge or guidance on how to set odom and imu covariance in somewhere?How you did your odom and imu?

Comment by jxl on 2017-01-04:
BTW,when i have one odom and one imu, in EKF update cycle, does it means there will be one predict step(Kinematic model) and two correct steps,one for odom ,and the other for imu?

Comment by Tom Moore on 2017-01-13:
Can you please update your question with these? Thanks!

Comment by jxl on 2017-01-17:
Apologise for delay reply,thanks tom!!!

Comment by jxl on 2017-01-18:
Thanks very very much !!! I learned a lot of things~~~

Comment by HIT_LR on 2022-01-13:
兄弟你好,我也是深圳的,最近也是在使用r_l碰到了小问题,能否请教一下呢。

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.