Skip to content

Fix odometry twist computation#2

Merged
efernandez merged 1 commit intoindigo-develfrom
fix_twist
Jun 16, 2015
Merged

Fix odometry twist computation#2
efernandez merged 1 commit intoindigo-develfrom
fix_twist

Conversation

@efernandez
Copy link
Copy Markdown
Member

The twist is computed as the relative transformation in SE(2) between
the previous and current odometry pose, divided by the time step dt.
In order to avoid inconsistencies we avoid the exp and log mappings to change the translation part of SE(2), so the result is equivalent to using homogeneous matrices, and is valid later in the classical state function of an EKF like in robot_localization package.

The y component of the twist wrt the integration scheme is:

  • Euler: 0
  • RK2: != 0, approximately equal to v * sin(w/2) / dt
  • Exact: != 0, with an expression more complex than RK2 one.

For RK2 and the Exact integration schemes, the value for y is very small in both cases.

The twist is computed as the relative transformation in SE(2) between
the previous and current odometry pose, divided by the time step dt.
@efernandez
Copy link
Copy Markdown
Member Author

@servos

@servos
Copy link
Copy Markdown

servos commented Jun 11, 2015

LGTM

efernandez pushed a commit that referenced this pull request Jun 16, 2015
Fix odometry twist computation
@efernandez efernandez merged commit 4095264 into indigo-devel Jun 16, 2015
@efernandez efernandez deleted the fix_twist branch June 16, 2015 13:24
@efernandez efernandez mentioned this pull request Jun 16, 2015
@efernandez efernandez restored the fix_twist branch June 6, 2017 22:16
@efernandez efernandez deleted the fix_twist branch June 6, 2017 22:18
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