Closed ClintLiddick closed 7 years ago
To give a little bit of background information, we're running two copies of robot_localization
as suggested in the documentation.
localization_local
integrates odometry measurements from our mobile base and publishes the odom
to base_link
transform.localization_global
integrates the output of localization_local
with a GPS-like sensor and publishes the map
to odom
transform.Everything works as expected in 2.1.7, but exhibits the behavior that @ClintLiddick describes if we switch to the next commit. The problem affects the output of localization_local
even if we completely kill the localization_global
node, so the problem may be isolated to that instance.
We're using exactly the same launch files and setting ROS parameters in both cases.
Interesting. A few things:
navsat_transform_node
, this will not be alleviated, since navsat_transform_node
needs a message from one of the EKF instances, and I'm assuming you're giving it the output of the "global" instance. Does the warning happen constantly, or does it go away?Thanks for the information @ayrton04! In the end it was the differential vs. relative change. Changing our localization_local
and localization_global
's odom0
to relative instead of differential resolved the problem.
After reading the documentation more closely, I'm pretty sure that we should use differential mode and should not use relative mode.
We have two sources of pose information: (1) wheel odometry from the segway_rmp node and (2) pose from the stargazer node. The Stargazer is an indoor localization system that provides 6-DOF pose by tracking visual fiducials. The localization_local
filter publishes the odom
to base_link
transform by integrating the wheel odometry. The localization_global
filter publishes the map
to odom
transform by fusing the Stargazer with the output of localization_local
.
The description of the differential
setting
for a measurement at time t from the sensor in question, we first subtract the measurement at time t-1, and convert the resulting value to a velocity
exactly describes the behavior we want for wheel odometry. The description of the relative
setting
instead of removing the measurement at time t-1, we always remove the measurement at time 0, and the measurement is not converted to a velocity
treats the wheel odometry as an absolute measurement. This is incorrect and will cause our pose estimate to drift over time.
@ayrton04 Can you explain why differential
is correct for this use case? I'm sure I'm missing something here.
[Edit]
The reason it's yelling at you about yaw is that you turned on differential mode. As of 2.2.1, differential mode is implemented a bit differently. We convert the absolute pose information (in this case, your yaw) into velocities and integrate them as twists. The downside to this is that when you fuse velocity data, the error growth is unbounded. With position, this isn't a problem. With orientation, it is. See this page on the wiki. Short answer: turn on relative mode (new feature) for that sensor, and turn differential mode off
Our localization_local
node only subscribes to relative odometry information. There are no absolute measurements at all, so the error should grow unbounded. How can we use robot_localization
to publish the odom
to base_link
frame, which consists of only relative transformations, if this is an issue?
Let's focus on the localization_local
instance to start.
First, I'm not sure how much you gain by feeding only wheel encoder odometry into the filter. Presumably, the RMP driver produces the odometry message by integrating its wheel rotations. You're then attempting to decompose those back into velocities, and then feed them to a filter, which effectively just integrates them again. This buys you two things:
ekf_localization_node
motion model, which may or may not be helpful. If the RMP has its own internal model, you may be better off using theirs, as it could be customized for their robot (I don't know).ekf_localization_node
, you want to be fusing at least two sources of data within one instance of the node, e.g., wheel encoder odometry and an IMU.Our localization_local node only subscribes to relative odometry information. There are no absolute measurements at all, so the error should grow unbounded.
Looking at your config file, in version 2.1.7, you were fusing X, Y, and Yaw (absolute pose variables, as least as far as the filter is concerned), and doing so differentially. Internally, for each measurement, we'd take the delta from the previous measurement to the current, add that to the previous state, and fuse that as an absolute pose measurement. While this worked, it had a large-ish mathematical flaw regarding covariance, and it also resulted in a lot of overhead and bookkeeping (e.g., after processing any measurement, we'd have to loop through each remaining measurement in the queue for that timestamp and update it). As such, none of your variables were being fused as velocities. I'm not sure how the RMP driver works, but most of these robot drivers tend to put static variances on their yaw measurements, and while this is not correct, it would result in bounded error growth for your pose variables. If you revert to 2.1.7, run your system, and watch the yaw variance, I'd be interested to know if it grows or stays bounded.
Your statement above is true in general, but it can be seriously problematic for orientations. Imagine driving in a straight line until you amass 5 meters of error along that dimension. Now imagine turning in a circle until you amass 5 radians of error for yaw, and then driving in a straight line. Because you don't really have a good picture of which way you're facing, your position covariance is going to explode. As long as you don't have any absolute pose measurements being fused with that instance, then you're probably fine, but if you suddenly fuse an absolute variable with a low variance, all correlated variables in the filter will jump.
I'm digressing a bit, but the short answer is this: differential mode is intended to help you fuse multiple sources of pose data within the same instance of the node. For example, if you have one source of wheel encoder odometry that only produces absolute X and Y positions and no velocities, and you also have, say, some kind of optical flow technique that is also producing absolute X and Y positions, then you might turn on differential mode on one or both of them so that they remain consistent. In an ideal world, both sources would be correctly reporting their covariances, in which case differential mode would be unnecessary, but that is rarely the case.
Note also that when I say "absolute positions," I mean X, Y, Z, roll, pitch, and yaw, even if those sources are subject to drift. I'm simply differentiating from velocities.
Given your described setup, here's how I'd do it:
localization_local
: Keep your variables as they are now, but turn off differential mode. You can use relative mode if the odometry doesn't start at 0. Since this instance is providing the odom->_baselink transform, it's fine if your position drifts (see http://www.ros.org/reps/rep-0105.html). Alternatively, see if your RMP provides the odom->_baselink transform, and ditch the EKF.
localization_global
: You have two options.
localization_local
instance, except turn differential mode on, and then add an odom1 source for your Stargazer, with differential mode off. This way, you're directly fusing the wheel encoder odometry with the Stargazer output.localization_local
(+differential mode) with the Stargazer data (-differential mode). One quick question: does the RMP produce velocity/twist and pose data, or just pose?
@ayrton04 thanks for the good info.
We currently have the following and it appears to be working.
localization_local
:
odom0_relative: true
localization_global
:
odom0_relative: true
pose0_differential: false
When we change localization_global
to differential instead of relative the robot spins in simulation in map
fixed frame.
I have a few conceptual questions about what robot_localization
is doing internally:
_differential
is true
? My understanding is that the filter computes (observation_n - observation_{n-1}) / (time_n - time_{n-1})
internally and treats this as a velocity observations. The differences of Gaussians is not Gaussian, so I am not sure what the filter would use as the covariance for this update.yaw
variance growing unbounded an issue? If the system is linear and Gaussian, then changes in covariance do not affect the mean. This is only an issue if: (1) there are numerical stability problems or (2) another node uses the covariance matrix published by the filter.robot_localization
to fuse relative measurements? If I am fusing multiple relative measurements, then the covariance should grow unbounded. This is necessary if you are using robot_localization
to publish the odom
to base_link
transform, e.g. by fusing odometry and an IMU. I suppose this depends a lot on the answer to (1) and (2).@ayrton04 Thanks for all of your help! We really appreciate it. @ClintLiddick and I wouldn't have made it this far without you. :smile:
@ClintLiddick Can you possibly provide a bag file? The behavior you describe seems strange to me, and I'd like the chance to investigate. If your data is sensitive and you can't share, then no worries.
@mkoval
_relative
mode on, or something else? For the former case, let's say that you have a sensor that measures absolute global pose from some external source, e.g., your Stargazer. You fire up your robot's launch file anew, but your Stargazer node's first reported position is something like (17, 4), because its origin is some corner of the room in which it's placed. If you'd prefer that the output of the filter starts at (0, 0), you set the _relative
parameter to true for that sensor, but it's still measuring an absolute pose with a fixed (or at least bounded) covariance. In that case, I would expect the output covariance values for X and Y to remain bounded. In any case, you're very welcome, and feel free to keep the conversation going if you have more questions/inputs!
@ayrton04 I mean "relative" as in "only provides pose measurements relative to the previous observation." This is closer to the _differential
flag than the _relative
flag in robot_localization
. In some cases (e.g. visual SLAM) it may be from estimating a relative transformation between two measurements. In other cases, (e.g. wheel odometry, accelerometer, gyro) this is achieved by integrating velocity or acceleration measurements. These values may even be integrated by a different motion model than the one provided by robot_localization
.
Our goal is to use one instance of robot_localization
(aka localization_local
) to fuse all of these "relative" measurements (using the informal definition above) into the odom
to base_link
transform. As per REP-105, this transformation will vary continuously, but may drift over time. Then, we will use a second instance of robot_localization
, to fuse the output of localization_local
with our non-"relative" sensors (e.g. the Stargazer).
From my understanding, our configuration should be:
localization_local
odom0
: Segway RMP odometry_differential
: truelocalization_global
odom0
: output of localization_local
_differential
: truepose0
: Stargazer_differential
: false_relative
: falseHowever, like @ClintLiddick described, this the pose estimate to constantly spin in yaw. Thanks again!
Ah, so we've had a bit of a misunderstanding with terminology. The EKF and UKF can both run in "relative" and/or "differential" mode. Both of those settings only apply to pose variables. "Relative" mode is needed when you want a sensor that measures pose to start at 0, even if the raw sensor data doesn't. It literally creates an offset for all future measurements from that sensor. "Differential" mode should be used when you have multiple sources of pose data, as it keeps them consistent with one another. It converts measurements at subsequent time steps to velocities and fuses them as such. In this case, it uses the same logic that is used when it receives actual twist measurements.
But just so we're on the same page (and we may already be), setting _relative
to true does not mean "this is a sensor which makes relative measurements." Likewise, setting _differential
to true does not mean "this is a sensor that provides measurements differentially." The flags modify how the node processes the data before passing it into the core filter.
The data sources that you specify as "relative" (e.g., wheel encoder odometry or visual odometry) would ideally publish both pose and twist data. For example, many robot bases spit out a nav_msgs/Odometry message with both the twist and pose data filled out. In those cases, I tend to fuse the velocity data with the EKF and ignore the pose variables. Equivalently (I hope), you should be able to fuse the absolute pose variables (i.e., set their values to true in the configuration) and turn _differential
mode on. In either case, you will see the covariances on the pose variables grow without bound. If, however, you have a robot whose odometry data (incorrectly) publishes static covariances for pose data, and you fuse those variables with _differential
mode off, then the pose covariances in your outputs will not grow without bound.
EDIT: Sorry, I didn't comment on your proposed set up. It looks good to me!
Do you all consider this resolved, or is there an action you'd like to see come out of this discussion?
Our robot has been down for maintenance for the last ~two weeks, so we haven't been able to test the changes that you suggested. @ClintLiddick or I will post a follow-up as soon as we're able to get the robot moving again. :sweat:
@ayrton04 Thanks for all of your help!
Bummer! You're very welcome. I'll leave this open until I hear back from you. Thanks!
@ClintLiddick tried three different configurations (see below) and were not able to get any of them to successfully fuse the Odometry
output of the segway_rmp
with the Stargazer. I've included an example Segway odometry message and an example Stargazer message at the bottom of this comment.
To simplify debugging, we switched to integrating velocities and gave up on using a second instance of robot_localization to produce the odom
to herb_base
transform. We now use the segway_rmp
node to publish that transformation (and verified that it does so correctly).
Thanks again for your help @ayrton04 - hopefully we can get to the bottom of this.
robot_localization
ParametersIdeally, from reading the documentation, we think that our configuration should fuse (x_velocity, y_velocity, yaw_velocity) from the Segway and the full 6-DOF pose from the Stargazer. However, in practice, this produce the same (if not worse) artifacts than "Try 3" below. This is what we think the configuration should be:
map_frame: map
odom_frame: odom
base_link_frame: herb_base
odom0: odom
odom0_config: [
false, false, false, # x, y, z
false, false, false, # roll, pitch, yaw
true, true, false, # x dot, y dot, z dot
false, false, true, # roll dot, pitch dot, yaw dot
false, false, false # x ddot, y ddot, z ddot
]
pose0: stargazer/robot_pose
pose0_config: [
true , true , true , # x, y, z
true , true , true , # roll, pitch, yaw
false, false, false, # x dot, y dot, z dot
false, false, false, # roll dot, pitch dot, yaw dot
false, false, false # x ddot, y ddot, z ddot
]
Here are the three simplified configurations we used while debugging:
As a sanity check, we first attempted to configure robot_localization to integrate (x_velocity, y_velocity, yaw_velocity) measurements from the Odometry
message published by the segway_rmp
. We tested the result by looking at the odom -> herb_base
transform in RViz. The position was stable, but the orientation rapidly spun in place.
Here the configuration of robot_localization we used for testing:
two_d_mode: true
odom_frame: odom
base_link_frame: herb_base
odom0: odom
odom0_config: [
false, false, false, # x, y, z
false, false, false, # roll, pitch, yaw
true, true, false, # x dot, y dot, z dot
false, false, true, # roll dot, pitch dot, yaw dot
false, false, false # x ddot, y ddot, z ddot
]
We also tried fusing the linear velocities with (differential) orientation. Both the position and orientation were stable.
Here is the modified robot_localization configuration that we used for testing:
two_d_mode: true
odom_frame: odom
base_link_frame: herb_base
odom0: odom
odom0_config: [
false, false, false, # x, y, z
false, false, true, # roll, pitch, yaw
true, true, false, # x dot, y dot, z dot
false, false, false, # roll dot, pitch dot, yaw dot
false, false, false # x ddot, y ddot, z ddot
]
odom0_differential: true
We attempted to add the Stargazer back to "Try 2" configuration. In this test, we configured the segway_rmp
node to publish the map
to odom
transform. In this case, both the position and orientation of the robot became unstable.
Here is the configuration that we used for testing:
two_d_mode: true
frequency: 100.
map_frame: map
odom_frame: odom
base_link_frame: herb_base
odom0: odom
odom0_config: [
false, false, false, # x, y, z
false, false, true, # roll, pitch, yaw
true, true, false, # x dot, y dot, z dot
false, false, false, # roll dot, pitch dot, yaw dot
false, false, false # x ddot, y ddot, z ddot
]
odom0_differential: true
pose0: stargazer/robot_pose
pose0_config: [
true , true , true , # x, y, z
true , true , true , # roll, pitch, yaw
false, false, false, # x dot, y dot, z dot
false, false, false, # roll dot, pitch dot, yaw dot
false, false, false # x ddot, y ddot, z ddot
]
This is an example PoseWithCovarianceStamped
message published by the Stargazer:
header:
seq: 14004
stamp:
secs: 1444339712
nsecs: 506360054
frame_id: map
pose:
pose:
position:
x: -1.1342374962
y: 1.63940725134
z: -0.0015
orientation:
x: 0.0
y: 0.0
z: -0.713005742217
w: 0.701158192968
covariance: [0.04, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05]
And this is an example Odometry
message published by segway_rmp
:
header:
seq: 163914
stamp:
secs: 1444339692
nsecs: 131705478
frame_id: odom
child_frame_id: herb_base
pose:
pose:
position:
x: -9.64064383879e-11
y: -5.87766741944e-08
z: 0.0
orientation:
x: 0.0
y: 0.0
z: -0.000641460020808
w: 0.999999794264
covariance: [1e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1000000000000.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1000000000000.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1000000000000.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001]
twist:
twist:
linear:
x: 0.0
y: 0.0
z: 0.0
angular:
x: 0.0
y: 0.0
z: -0.0134256100282
covariance: [0.0025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1000000000000.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1000000000000.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1000000000000.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0025]
We also have a question about this phrase in the preparing your sensor data tutorial:
If the odometry provides both orientation and angular velocity, fuse the orientation, unless (A) you have a better source of absolute orientation (e.g., an IMU), or (B) your odometry source accurately captures the covariance values for your orientation data. In either of those cases, the user can either fuse the velocity data (if it's available), or set the _differential parameter to true for the odometry data.
This suggests that we should "fuse the orientation" unless "your odometry source accurately captures the covariance values for your orientation data." We must be misinterpreting this: why would fuse orientation if we know that it has an inaccurate covariance?
Nice write-up! I think our best bet would be a bag file. "Try 1" is as vanilla a use case as can be, so rotating in place means something is clearly wrong. It's best to iron these things out one level at a time.
Re: the tutorial, I think that must have been me writing documentation too late at night. What I meant was that if your odometry data source provides orientation, AND you have a second superior source of orientation data (e.g., an IMU), then you have a few options:
_differential
to true for one of them.Thanks for pointing it out (I'll go fix it), and for asking such thoroughly investigated questions.
Here are the bag files, one with robot localization running and one without, and here is a video of what we see in this running configuration: https://www.dropbox.com/s/tl6xr3ynpajifed/segway_only.bag?dl=1 https://www.dropbox.com/s/q810mgnsifrv760/segway_with_robot_localization.bag?dl=1 https://youtu.be/C6RlslWSSpQ (note the white thing at origin is one of our arms, which is currently disabled, not related to this).
Here's the setup for the bag files and video: https://github.com/personalrobotics/herb_launch/blob/bugfix/odom_jitter/config/localization_global.yaml https://github.com/personalrobotics/herb_launch/blob/bugfix/odom_jitter/launch/localization.launch
Odom comes from our edited fork for SegwayRMP: https://github.com/personalrobotics/segway_rmp/tree/bugfix/twist_covariance
Let us know if you notice any issues with our setup and we can test out something else.
EDIT: The problem is that you had a circular relationship that created a kind of positive feedback loop. The UKF is producing the map->odom transform. The odometry data you are feeding it (odom0
) is reported in the odom frame, so when the filter gets the data, it will try to transform it from odom->map, which is the very transform you are generating. I think what's happening - and this is not the first time I've seen this - is you get some small non-zero reading for your heading in the odom0
message, and so the heading in your map->odom transform moves a little bit, and then you get another measurement, and it now gets transformed by that previous transform, which causes a lager heading change, and so on. Using differential
mode won't help here. Fusing only velocity from odom0
is the way to go here. Your original settings look like they should be correct to me. What are you seeing that suggests otherwise?
EDIT 2: Sorry, I appear to be having trouble with "reading" today. Anyway, when I just use the velocity data from your Try 1 settings, I see no spinning in place. I'll throw together a movie.
Also, I should point out that I do see the heading rapidly rotate in place when I use the settings in the yaml file you attached, and for the settings in tries 2 and 3 (any time you use yaw and not just yaw velocity).
Thanks for looking so quickly. Are you saying with the setup we sent you you don't see spinning but correct output? Our current live setup (the same files but on the master branches, what we worked out with you previously), results in a jitter that you can see here (once the upload is done post-processing): https://www.youtube.com/watch?v=mSyIABvQJ-I
Sorry it's only the TF frames, had to grab it quick while running around today. If it's not very clear I can upload a better video tomorrow.
Sorry, the description above said you were seeing rapid spinning in place with the configuration in question. And does that jitter appear when you make the rviz fixed frame the odom frame? It looks like most of the motion is related to the map->odom transform moving around, which can happen when one of the frames moves and the other doesn't (e.g., when you have a GPS involved). Or is the video just from fusion of the wheel encoder odometry?
In any case, yes, when I run your Try 1 above, I do not see spinning in place.
Very odd that it's not spinning for you. Sorry if I was unclear. When we try configuration "Try 1" we see rapid spinning. I'll try to get a bag with the Stargazer (GPS) data soon as well.
The second video I posted is the "real problem," where when we use the configuration we want to use (posted above "Try 1"), it jitters. It doesn't jitter when in fixed_frame = odom. However because our underlying planning and collision checking software operates in the map frame the jittering is actually causing problems when doing motion planning and perception.
Is there any jitter in the StarGazer data itself? Also, do you do global planning in the map frame, and local planning/control in the odom frame? Is there any jitter if you fuse only the StarGazer data? Also, is the pose itself experiencing jitter, or is it just the transform between the two frames? I'm thinking one would cause the other. Can you plot the pose coming from the map frame r_l topic?
Did you all ever have any luck here?
Sorry to be a pain, but is there any update on this? The package has changed quite a bit since it was reported, and I'm wondering if you've all got it sorted.
I'm so sorry. I've been absolutely flooded and ignoring my notifications. To be completely honest, we still have a lot of problems with our localization system, but I'm not convinced it is a problem of this package. We're working on an overhaul of our system, so if in the future we do discover some kind of bug with this package we'll open a specific issue, but for now we're very grateful for your assistance and will use your advice in setting up and tuning our new system. Thank you for working so hard to maintain such a useful package!
You're welcome! Good luck.
Using version 2.1.7 our localization nodes run without problems, but starting in 64b945da6ebf59e7da8145beadcdac9ae0b5306f our "global" localization (odom->map transform) warns:
We've tracked this to an error in our "local" localization config, which outputs the following on
/diagnostics
withprint_diagnostics
settrue
.We definitely see that "unbounded error growth and erratic filter behavior" because our robot spins around continuously in rviz simulation. We know it is our "local" localization because running only that node still causes issues with the TF frames.
Our
/odom
source is publishing YAW information, and reverting back to 2.1.7 tag everything works.We haven't been able to identify what part of the commit is causing the change/regression.