Handling a delayed localization pose?
Basically I am getting a global pose for localization which is 60ms delayed.
So just setting this pose to current pose will add an error of 6cm by not compensating for the driven distance ( e.g. 1m/s) in this 60ms.
So what I am doing is taking the old odom ( now -60ms) and the current odom, subtracting each other and add the resulting transform to the incoming localization pose.
And in code it looks like this:
auto oldOdomTf = tf->lookupTransform( ODOM, currentTime, BASE_LINK, currentTime - 60ms,
ODOM );
auto yaw = tf_utils::getYawFromQuaternion( oldOdomTf.transform.rotation );
RCLCPP_INFO( node.get_logger(), "get transform from old %s to %s: x: %.2f y: %.2f yaw: %.2f",
BASE_LINK.c_str(), ODOM.c_str(), oldOdomTf.transform.translation.x,
oldOdomTf.transform.translation.y, yaw );
auto currentOdomTf = tf->lookupTransform( ODOM, currentTime, BASE_LINK, currentTime,
ODOM );
yaw = tf_utils::getYawFromQuaternion( currentOdomTf.transform.rotation );
RCLCPP_INFO( node.get_logger(), "get transform from current %s to %s: x: %.2f y: %.2f yaw: %.2f",
BASE_LINK.c_str(),ODOM.c_str(), currentOdomTf.transform.translation.x,
currentOdomTf.transform.translation.y, yaw );
tf2::Transform odomDelta, old, current;
tf2::fromMsg( oldOdomTf.transform, old );
tf2::fromMsg( currentOdomTf.transform, current );
odomDelta = current * old.inverse();
latest_tf_ = latest_tf_ * odomDelta; // get new map pose
Output is this:
[INFO 1566381525.298737439] [testNode]: transform from map to odom: x: 1.00 y: 1.61 yaw: -1.57
[INFO 1566381525.298759261] [testNode]: get transform from old base_link to odom: x: 0.60 y: 0.00 yaw: 0.00
[INFO 1566381525.298953778] [testNode]: get transform from current base_link to odom: x: 0.70 y: 0.00 yaw: 0.00
[INFO 1566381525.299004058] [testNode]: transform from old odom to new odom: x: 0.10 y: 0.00 yaw: 0.00
[INFO 1566381525.299014972] [testNode]: transform from map to odom with time compensation: x: 1.00 y: 1.51 yaw: -1.57
So, it looks good but my question is if this could be done simpler? Like with a direct tf call to transform spae and time? ;)
I was looking at the ros2 amcl pkg, where they write also something about integrating the odom data but in written code I only see a odom - base link transformation...
Why not use EKF to fuse the results?
robot_localization
EKF can handle pose sources with old timestamp.From what I know it's not ported to ROS2 yet.