Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

cleanup of RobotStateMap led to clearer understanding of LidarProcessor requirements. #7

Open
wants to merge 5 commits into
base: master
Choose a base branch
from

Conversation

dbadb
Copy link

@dbadb dbadb commented Dec 31, 2018

(still need to debug the LidarProcessor, but it's now much more like the Encoder variant)

new Transform(lastPose).inverse(), // ie: LidarToField
mReferenceModel); // mReferenceMode in field coords
Twist2d fwdK = Pose2d.log(xform.inverse().toPose2d());
poseEstimate = lastPose.transformBy(Pose2d.exp(fwdK));

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Nitpick: I think we could reduce how much we operate on what gets integrated into pose here, to reduce accumulation of floating point errors. Maybe:

Pose2d xform = mICP.doICP(getCulledPoints(scan),
                                 new Transform(lastPose).inverse(),
                                 mReferenceModel).inverse().toPose2d();
poseEstimate = lastPose.transformBy(xform);
velMeasured = Pose2d.log(xform);

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

i believe the exp is actually needed, since it moves along an arg, whereas xform is a linear transformation.

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Aren't the inverses? So shouldn't Pose2d.exp(Pose2d.log(xform.inverse().toPose2d())) == xform.inverse().toPose2d()?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants