Skip to content
This repository has been archived by the owner on Mar 10, 2023. It is now read-only.

ndt_mapping: fix no output of transformation matrix #60

Open
wants to merge 1 commit into
base: master
Choose a base branch
from

Conversation

Kin-Zhang
Copy link

Bug fix

Fixed bug

In version 1.14, ndt_mapping.cpp rewrite the tf things, but it forgot to compute

    tf_btol = (tl_btol * rot_z_btol * rot_y_btol * rot_x_btol).matrix();
    tf_ltob = tf_btol.inverse();

so it still need to get the previous tf thing and use it to compute tf_ltob and then we will have the output of the transformation matrix

Relate issue:
#58

@mertyavuz41
Copy link

I encountered this problem too, thanks for the solution

@Kin-Zhang
Copy link
Author

I encountered this problem too, thanks for the solution

Great to help you.

@JWhitleyWork
Copy link

@Kin-Zhang Thank you for the fix! Please sign your commits (see the DCO item below for details). This will be included in the 1.15.1 release.

In version 1.14, ndt_mapping.cpp rewrite the tf things, but it forgot to compute
```cpp
    tf_btol = (tl_btol * rot_z_btol * rot_y_btol * rot_x_btol).matrix();
    tf_ltob = tf_btol.inverse();
```
so it still need get previous tf thing and use it to compute tf_ltob and then we will have the output of transformation matrix

Signed-off-by: Kin <[email protected]>
@Kin-Zhang
Copy link
Author

@Kin-Zhang Thank you for the fix! Please sign your commits (see the DCO item below for details). This will be included in the 1.15.1 release.

Thanks for replying, and happy to contribute.
I finished about what the DCO item said.

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

Successfully merging this pull request may close these issues.

3 participants