ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
I'm not sure that fusing GPS and amcl
data is a good idea. Can you give more information about what it is you're trying to do?
2 | No.2 Revision |
OK, I took a look at this, and you have a few things wrong:
navsat_transform_node
, and is the reason you were seeing NaN values. Since your IMU odometry topic appears to have a working orientation, I used that instead. Note that you will need to add a value for magnetic_declination
for the settings for navsat_transform_node
for your location. I'm assuming the IMU has a magnetometer from which it derives its yaw, correct? If not, then navsat_transform_node
won't work, as you need an earth-referenced yaw measurement.base_link
->nav_link
transform has an orientation in it. Note that this is meaningless for a navsat device, as it mounting orientation doesn't affect its measurement. You only need the linear offset in the static transform. That is not documented, and I've updated navsat_transform_node
to remove the orientation component of that transform before applying it.imu0_remove_gravitational_acceleration
. You can read more about that parameter on the wiki. This means that you may experience drift, particularly in the Z axis.I put together a launch and config file here. Note that it also automatically plays your bag file at 10x speed, though you will need to update the path to the file itself. You will need to download the latest r_l source for this to work. It worked just fine for me. Here's a screenshot of the data in the map frame:
...and in the odom frame:
If you see any remaining drift (like at the bottom of the odom frame image), then it's a result of your imu_odom
topic, which is likely integrating accelerations onboard the IMU, in which case drift may be inevitable. If you feed the filter velocity data that is incorrect, it won't fix it for you. For example, right at the beginning of the bag file, here's what your imu_odom
topic looks like:
header:
seq: 11903
stamp:
secs: 1465356225
nsecs: 286038297
frame_id: odom
child_frame_id: base_link
pose:
pose:
position:
x: -93.3040241217
y: 8.20038348484
z: 0.0
orientation:
x: -0.0
y: 0.0
z: 0.0303902439879
w: -0.999538109864
covariance: [0.001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001]
twist:
twist:
linear:
x: -2.91783475405
y: -0.091434393804
z: 0.0
angular:
x: 0.0
y: 0.0
z: 0.0
covariance: [0.001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001]
You have a linear velocity of nearly -3 meters per second in the X axis, so the state estimate is going to move backwards.
Anyway, I'll let you look at the launch and config files and work through it yourself. The best advice I can offer with amcl
in the loop is to make sure that fusing GPS you turn of amcl
's tf broadcasting, and make sure its state estimate agrees with the GPS. If they diverge over time, you're going to see it amcl
data is a good idea. Can you give more information about what is you're trying to do? jump back and forth rapidly between them.