-
Notifications
You must be signed in to change notification settings - Fork 7
align API with psjac
#31
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
Changes from all commits
a8d52e5
cb31ecc
d3ba654
97f519d
f57eb48
1ddb06d
60d0610
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change | ||||
|---|---|---|---|---|---|---|
|
|
@@ -6,7 +6,7 @@ | |||||
| import argparse | ||||||
| import pypose as pp | ||||||
| from torch import nn | ||||||
| from bae.autograd.function import TrackingTensor, map_transform | ||||||
| from pypose.autograd.function import psjac | ||||||
|
|
||||||
| from bae.utils.pgo_dataset import G2OPGO | ||||||
| from bae.utils.pgo import plot_and_save, render_frame, save_gif | ||||||
|
|
@@ -25,47 +25,9 @@ | |||||
|
|
||||||
| torch.set_printoptions(precision=6) | ||||||
|
|
||||||
| def diff(residual=None, jacobian=None): | ||||||
| num_factors = residual.shape[0] if residual is not None else jacobian.shape[0] | ||||||
| import numpy as np | ||||||
| with open('data.s', 'r') as f: | ||||||
| ceres_residuals = [] | ||||||
| ceres_jacobians = [] | ||||||
| for i in range(num_factors): | ||||||
| # read from 'data.s' | ||||||
| data = f.readline() | ||||||
| discard_left = data.split('[')[1:] | ||||||
| discard_right = [x.split(']')[0] for x in discard_left] | ||||||
| discard_semi = [x.split(';') for x in discard_right] | ||||||
| # convert to float | ||||||
| ceres_residual = [float(y[0]) for y in discard_semi] | ||||||
| ceres_residuals.append(ceres_residual) | ||||||
|
|
||||||
| ceres_jacobian = [np.fromstring(y[1], sep=',') for y in discard_semi] | ||||||
| ceres_jacobians.append(ceres_jacobian) | ||||||
| ceres_residuals = torch.tensor(ceres_residuals) | ||||||
| ceres_jacobians = torch.tensor(ceres_jacobians) | ||||||
| if residual is not None: | ||||||
| ceres_residuals = ceres_residuals - residual | ||||||
| # absolute difference | ||||||
| print(ceres_residuals.norm(dim=-1).mean()) | ||||||
| # relative difference | ||||||
| print(((ceres_residuals.norm(dim=-1) / residual.norm(dim=-1)))[1:].mean()) | ||||||
| if jacobian is not None: | ||||||
| ceres_jacobians = ceres_jacobians - jacobian | ||||||
| # absolute difference | ||||||
|
|
||||||
| def write_ceres_txt(nodes, filename='data.s'): | ||||||
| with open(filename, 'w') as f: | ||||||
| # ID x y z q_x q_y q_z q_w | ||||||
| for i in range(nodes.shape[0]): | ||||||
| node = nodes[i] | ||||||
| f.write(f'{i} {node[0].item()} {node[1].item()} {node[2].item()} {node[3].item()} {node[4].item()} {node[5].item()} {node[6].item()}\n') | ||||||
|
|
||||||
| def _pose_graph_residual(poses, node1, node2, infos): | ||||||
| if isinstance(infos, TrackingTensor): | ||||||
| infos = infos.tensor() | ||||||
|
|
||||||
| @psjac | ||||||
| def pose_graph_residual(poses, node1, node2, infos): | ||||||
| pose_ab_est = node1.Inv() @ node2 | ||||||
| r_p = pose_ab_est.translation() - poses.translation() | ||||||
| # Match Ceres pose_graph_3d: 2 * vec(q_meas * q_est^{-1}). | ||||||
|
|
@@ -77,15 +39,11 @@ def _pose_graph_residual(poses, node1, node2, infos): | |||||
| return residual[..., 0] | ||||||
|
|
||||||
|
|
||||||
| @map_transform | ||||||
| def pose_graph_residual(poses, node1, node2, infos): | ||||||
| return _pose_graph_residual(poses, node1, node2, infos) | ||||||
|
|
||||||
| class PoseGraph(nn.Module): | ||||||
|
|
||||||
| def __init__(self, nodes): | ||||||
| super().__init__() | ||||||
| self.nodes = nn.Parameter(TrackingTensor(nodes)) | ||||||
| self.nodes = pp.Parameter(nodes, sjac=True) | ||||||
|
Contributor
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Initializing
Suggested change
|
||||||
|
|
||||||
| def forward(self, edges, poses, infos): | ||||||
| node1 = self.nodes[edges[..., 0]] | ||||||
|
|
@@ -96,7 +54,7 @@ def forward(self, edges, poses, infos): | |||||
| class PoseGraphFixedFirst(nn.Module): | ||||||
| def __init__(self, nodes_rest): | ||||||
| super().__init__() | ||||||
| self.nodes_rest = nn.Parameter(TrackingTensor(nodes_rest)) | ||||||
| self.nodes_rest = pp.Parameter(nodes_rest, sjac=True) | ||||||
|
Contributor
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. |
||||||
|
|
||||||
| def nodes_all(self, node_fixed): | ||||||
| return torch.cat([node_fixed, self.nodes_rest], dim=0) | ||||||
|
|
@@ -210,7 +168,6 @@ def forward(self, edges, poses, infos, node_fixed): | |||||
| nodes_current = graph.nodes | ||||||
| plot_and_save(nodes_current.translation(), name+'.png', title) | ||||||
| torch.save(graph.state_dict(), name+'.pt') | ||||||
| write_ceres_txt(nodes_current.tensor(), name+'.txt') | ||||||
| if args.gif: | ||||||
| save_gif(gif_frames, sample_prefix + '.gif', duration=args.gif_duration) | ||||||
|
|
||||||
|
|
||||||
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
The example should demonstrate initializing the parameter with a
pp.LieTensor(likepp.SE3) to ensure the 6D optimization behavior described in the notes below is actually triggered.